Kinematics and the Implementation of an Elephant's Trunk Manipulator and Other Continuum St

合集下载

Design and Implementation of a Bionic Robotic Hand

Design and Implementation of a Bionic Robotic Hand

Design and Implementation of a Bionic Robotic Hand with Multimodal Perception Based on ModelPredictive Controlline 1:line 2:Abstract—This paper presents a modular bionic robotic hand system based on Model Predictive Control (MPC). The system's main controller is a six-degree-of-freedom STM32 servo control board, which employs the Newton-Euler method for a detailed analysis of the kinematic equations of the bionic robotic hand, facilitating the calculations of both forward and inverse kinematics. Additionally, MPC strategies are implemented to achieve precise control of the robotic hand and efficient execution of complex tasks.To enhance the environmental perception capabilities of the robotic hand, the system integrates various sensors, including a sound sensor, infrared sensor, ultrasonic distance sensor, OLED display module, digital tilt sensor, Bluetooth module, and PS2 wireless remote control module. These sensors enable the robotic hand to perceive and respond to environmental changes in real time, thereby improving operational flexibility and precision. Experimental results indicate that the bionic robotic hand system possesses flexible control capabilities, good synchronization performance, and broad application prospects.Keywords-Bionic robotic hand; Model Predictive Control (MPC); kinematic analysis; modular designI. INTRODUCTIONWith the rapid development of robotics technology, the importance of bionic systems in industrial and research fields has grown significantly. This study presents a bionic robotic hand, which mimics the structure of the human hand and integrates an STM32 microcontroller along with various sensors to achieve precise and flexible control. Traditional control methods for robotic hands often face issues such as slow response times, insufficient control accuracy, and poor adaptability to complex environments. To address these challenges, this paper employs the Newton-Euler method to establish a dynamic model and introduces Model Predictive Control (MPC) strategies, significantly enhancing the control precision and task execution efficiency of the robotic hand.The robotic hand is capable of simulating basic human arm movements and achieves precise control over each joint through a motion-sensing glove, enabling it to perform complex and delicate operations. The integration of sensors provides the robotic hand with biological-like "tactile," "auditory," and "visual" capabilities, significantly enhancing its interactivity and level of automation.In terms of applications, the bionic robotic hand not only excels in industrial automation but also extends its use to scientific exploration and daily life. For instance, it demonstrates high reliability and precision in extreme environments, such as simulating extraterrestrial terrain and studying the possibility of life.II.SYSTEM DESIGNThe structure of the bionic robotic hand consists primarily of fingers with multiple joint degrees of freedom, where each joint can be controlled independently. The STM32 servo acts as the main controller, receiving data from sensors positioned at appropriate locations on the robotic hand, and controlling its movements by adjusting the joint angles. To enhance the control of the robotic hand's motion, this paper employs the Newton-Euler method to establish a dynamic model, conducts kinematic analysis, and integrates Model Predictive Control (MPC) strategies to improve operational performance in complex environments.In terms of control methods, the system not only utilizes a motion-sensing glove for controlling the bionic robotic hand but also integrates a PS2 controller and a Bluetooth module, achieving a fusion of multiple control modalities.整整整整如图需要预留一个图片的位置III.HARDWARE SELECTION AND DESIGN Choosing a hardware module that meets the functional requirements of the system while effectively controlling costs and ensuring appropriate performance is a critical consideration prior to system design.The hardware components of the system mainly consist of the bionic robotic hand, a servo controller system, a sound module, an infrared module, an ultrasonic distance measurement module, and a Bluetooth module. The main sections are described below.A.Bionic Mechanical StructureThe robotic hand consists of a rotating base and five articulated fingers, forming a six-degree-of-freedom motion structure. The six degrees of freedom enable the system to meet complex motion requirements while maintaining high efficiency and response speed. The workflow primarily involves outputting different PWM signals from a microcontroller to ensure that the six degrees of freedom of the robotic hand can independently control the movements of each joint.B.Controller and Servo SystemThe control system requires a variety of serial interfaces. To achieve efficient control, a combination of the STM32 microcontroller and Arduino control board is utilized, leveraging the advantages of both. The STM32 microcontroller serves as the servo controller, while the Arduino control board provides extensive interfaces and sensor support, facilitating simplified programming and application processes. This integration ensures rapid and precise control of the robotic hand and promotes efficient development.C.Bluetooth ModuleThe HC-05 Bluetooth module supports full-duplex serial communication at distances of up to 10 meters and offers various operational modes. In the automatic connection mode, the module transmits data according to a preset program. Additionally, it can receive AT commands in command-response mode, allowing users to configure control parameters or issue control commands. The level control of external pins enables dynamic state transitions, making the module suitable for a variety of control scenarios.D.Ultrasonic Distance Measurement ModuleThe US-016 ultrasonic distance measurement module provides non-contact distance measurement capabilities of up to 3 meters and supports various operating modes. In continuous measurement mode, the module continuously emits ultrasonic waves and receives reflected signals to calculate the distance to an object in real-time. Additionally, the module can adjust the measurement range or sensitivity through configuration response mode, allowing users to set distance measurement parameters or modify the measurement frequency as needed. The output signal can dynamically reflect the measurement results via level control of external pins, making it suitable for a variety of distance sensing and automatic control applications.IV. DESIGN AND IMPLEMENTATION OF SYSTEMSOFTWAREA.Kinematic Analysis and MPC StrategiesThe control research of the robotic hand is primarily based on a mathematical model, and a reliable mathematical model is essential for studying the controllability of the system. The Denavit-Hartenberg (D-H) method is employed to model the kinematics of the bionic robotic hand, assigning a local coordinate system to each joint. The Z-axis is aligned with the joint's rotation axis, while the X-axis is defined as the shortest distance between adjacent Z-axes, thereby establishing the coordinate system for the robotic hand.By determining the Denavit-Hartenberg (D-H) parameters for each joint, including joint angles, link offsets, link lengths, and twist angles, the transformation matrix for each joint is derived, and the overall transformation matrix from the base to the fingertip is computed. This matrix encapsulates the positional and orientational information of the fingers in space, enabling precise forward and inverse kinematic analyses. The accuracy of the model is validated through simulations, confirming the correct positioning of the fingertip actuator. Additionally, Model Predictive Control (MPC) strategies are introduced to efficiently control the robotic hand and achieve trajectory tracking by predicting system states and optimizing control inputs.Taking the index finger as an example, the Denavit-Hartenberg (D-H) parameter table is established.The data table is shown in Table ITABLE I. DATA SHEETjoints, both the forward kinematic solution and the inverse kinematic solution are derived, resulting in the kinematic model of the ing the same approach, the kinematic models for all other fingers can be obtained.The movement space of the index finger tip is shownin Figure 1.Fig. 1.Fig. 1.The movement space at the end of the index finger Mathematical Model of the Bionic Robotic Hand Based on the Newton-Euler Method. According to the design, each joint of the bionic robotic hand has a specified degree of freedom.For each joint i, the angle is defined as θi, the angular velocity asθi, and the angular acceleration as θi.The dynamics equation for each joint can be expressed as:τi=I iθi+w i(I i w i)whereτi is the joint torque, I i is the joint inertia matrix, and w i and θi represent the joint angular velocity and acceleration, respectively.The control input is generated by the motor driver (servo), with the output being torque. Assuming the motor input for each joint is u i, the joint torque τi can be mapped through the motor's torque constant as:τi=kτ∙u iThe system dynamics equation can be described as:I iθi+b iθi+c iθi=τi−τext,iwhere b i is the damping coefficient, c i is the spring constant (accounting for joint elasticity), and τext,i represents external torques acting on the joint i, such as gravity and friction.The primary control objective is to ensure that the end-effector of the robotic hand (e.g., fingertip) can accurately track a predefined trajectory. Let the desired trajectory be denoted as y d(t)and the actual trajectory as y(t)The tracking error can be expressed as:e(t)=y d(t)−y(t)The goal of MPC is to minimize the cumulative tracking error, which is typically achieved through the following objective function:J=∑[e(k)T Q e e(k)]N−1k=0where Q e is the error weight matrix, N is the prediction horizon length.Mechanical constraints require that the joint angles and velocities must remain within the physically permissible range. Assuming the angle range of the i-th joint is[θi min,θi max]and the velocity range is [θi min,θi max]。

六自由度机械手运动控制

六自由度机械手运动控制

.西南交通大学本科毕业设计(论文)六自由度机械手复杂运动控制年级:200X级学号:200XXXX姓名:XXX专业: 机械工程系数控技术指导老师:XXX0X年 6月院系机械工程系专业数控技术年级 200X级姓名 XXX 题目六自由度机械手复杂运动控制指导教师评语指导教师 (签章)评阅人评语评阅人 (签章)成绩答辩委员会主任 (签章)年月日毕业设计(论文)任务书班级 0X级数控技术(1)班学生姓名 XXX 学号 200XXXXX发题日期: 0X年 3月 1 日完成日期: 6月 18日题目六自由度机械手复杂运动控制1、本论文的目的、意义本设计主要以实验室设备(六自由度串联机械手)为基础,运用六自由度串联机械手完成现实工程及实际需要为出发点。

通过对机械手的系统分析建立机器人坐标系的方法,并对其进行正运动分析和逆运动学分析结合矩阵的变换等研究该机器人系统在平面轨迹方面的设计。

并利用MATLAB对该设计的准确行进行验证。

本次设计让我们能有效的利用学校的设备对实际需要进行分析设计,从而使我们能将理论与实际有效结合。

并从中掌握了工程设计的主要方法和了解了现存技术中需要我们进行探索的必要。

2、学生应完成的任务由于本课题取材于实际生产运用中,不仅从理论方面对设计有分析等要求,更要结合理论做出实际需要的运动控制。

下面主要以学生的设计为主提出其需要完成的任务:(1)完成一万字符的外文翻译;(2)完成复杂运动控制设计的总体方案;(3)通过老师指导可以对机械手进行熟悉的操作和运用;(4)利用现有资料对机械手进行运动学理论分析,并结合矩阵工具对其建立的运动学方程进行求解;(5)利用机械手完成平面文字轨迹的运动控制;(6)对复杂运动控制的总结,分析其优缺点,并提出其缺点的解决方案和需要注意的问题;(7)完成毕业设计论文。

3、论文各部分内容及时间分配:(共 17 周)第一部分阅读相关文献并收集资料 ( 3周)第二部分熟悉设备操作并进行相关简单的操作 ( 3周)第三部分轨迹设计过程和相关计算分析( 4周)第四部分完成设计部分到实际运行部分( 3周)第五部分撰写毕业论文 ( 2周)评阅及答辩准备好答辩的演示文档及进行答辩 ( 2周)备注指导教师:XXX 0X年 3月日审批人:年月日摘要本文以示教型六自由度串联机械手为试验设备,进行机械手的复杂运动控制,使机械手完成各种复杂轨迹的运动控制等功能,能够在现代工业焊接、喷漆等方面的任务。

软体机器人研究现状综述

软体机器人研究现状综述

软体机器人研究现状综述作者:曹玉君, 尚建忠, 梁科山, 范大鹏, 马东玺, 唐力, CAO Yujun, SHANG Jianzhong, LIANG Keshan, FAN Dapeng, MA Dongxi, TANG Li作者单位:国防科学技术大学机电工程与自动化学院 长沙410073刊名:机械工程学报英文刊名:JOURNAL OF MECHANICAL ENGINEERING年,卷(期):2012,48(3)1.TRIVEDI D;RAHN C;KIER W Soft robotics:Biological inspiration,state of the art,and future research 2008(03)2.CRESPI A;LJSPEERT A Amphibot Ⅱ:An amphibious snake robot that crawls and swims using a central pattern generator 20063.李斌;马书根;王越超一种具有三维运动能力的蛇形机器人的研究[期刊论文]-机器人 2004(06)4.赵铁石;林永光;缪磊一种基于空间连杆机构的蛇形机器人[期刊论文]-机器人 2006(06)5.Biorobotics Lab,Carnegie Mellon University Modular snake robots 20106.叶长龙;马书根;李斌三维蛇形机器人巡视者Ⅱ的开发[期刊论文]-机械工程学报 2009(05)7.Rice University The elephant's trunk robotic arm 20108.HANNAN M;WALKER I D Kinematics and the implementation of an elephant's trunk manipulator and other continuumstyle robots[外文期刊] 2003(02)9.KAO C Chembots posts 200910.Technovelgy LLC Chembot squishy squish bot robots desired by DARPA 201011.Octopus Research Group Octopus project 201012.TRIMMER B A;ISSBERNER J I Kinematics of soft-bodied,legged locomotion in Manduca sexta larvae[外文期刊] 2007(02)13.KATE M;BETTENCOURT G;MARQUIS J SoftBot:A soft-material flexible robot based on caterpillar biomechamics 201014.SIMONITE T Chemical 'caterpillar' points to electronicsfree robots 201015.HOGAN R Fleshy robotic blobs give me nightmares 200916.SAENZ A Nothing can stop the blob bot 200917.News Group Newspapers Ltd Oozy new military robot 200918.MAEDA S A study on self-oscillating gel actuator for chemical robot 200819.SHIOTSU A;YAMANAKA M;MATSUYAMA Y Crawling and jumping soft robot KOHARO 200620.SUGIYAMA Y;HIRAI S Crawling and jumping by a deformable robot 2006(5-6)21.MATSUMOTO Y Crawling and jumping soft robots 201022.MARKS P Robot octopus will go where no sub has gone before 2010SCHI C;MAZZOLAI B;MATTOLI V Design of a biomimetic robotic octopus arm[外文期刊] 2009(01)24.MIT Chembots project 201025.刘伟庭;方向生;陈裕泉仿生"蚯蚓"机器人的SMA执行器实现[期刊论文]-传感技术学报 2005(03)26.付宜利;李显凌;梁兆光基于形状记忆合金的自主导管导向机器人设计[期刊论文]-机械工程学报 2008(09)27.CHAPMAN G Versatility of hydraulic systems[外文期刊] 1975(01)28.The New York Times Company Wriggling its way forward 201029.SAENZ A Nothing can stop the blob bot 201030.MAZZOLAI B;LASCHI C;CIANCHETTI M Biorobotic investigation on the muscle structure of an octopus tentacle 200731.MATZNER H;GUTFREUND Y;HOCHNER B Neuromuscular system of the flexible arm of the octopus physiological characterization[外文期刊] 2000(03)32.ROKNI D;HOCHNER B Ionic currents underlying fast action potentials in the obliquely striated muscle cells of the octopus arm[外文期刊] 2002(06)33.CIANCHETTI M;MATTOLI A;MAZZOLAI B A new design methodology of electrostrictive actuators for bio-inspiredrobotics[外文期刊] 2009(01)34.Massachusetts Institute of Technology Hex roller 201035.BAR-COHEN Y Electroactive polymer(EAP) actuators as artificial muscles reality,potential,and challenges 200436.VOCHIN A ChIMERA robot looks,behaves just like an Amoeba:A brand new type of whole-skin locomotion robot 201037.DEYLE T Amoeba-like whole-skin locomotion robots ooze right on by 201038.RoMeLa Lab, Virginia Tech WSL: Whole skin locomotion 201039.GRIETHULJSEN L I;TRIMMER B A Kinematics of horizontal and vertical caterpillar crawling[外文期刊] 2009(10)40.BELANGER J H;TRIMMER B A Combined kinematic and electromyographic analyses of proleg function during crawling by the caterpillar Manduca Sexta[外文期刊] 2000(11)41.BELANGER J H;BENDER K J;TRIMMER B A Context dependency of a limb withdrawal reflex in the caterpillar Manduca Sexta[外文期刊] 2000(11)42.WOODS WA;FUSILLO S J;TRIMMER B A Dynamic properties of a locomotory muscle of the tobacco hornworm Manduca sexta during strain cycling and simulated natural crawling[外文期刊] 2008(06)43.YEKUTIELI Y;MITELMAN R;HOCHNER B Analyzing octopus movements using three-dimensional reconstruction[外文期刊] 2007(03)44.YEKUTIELI Y;SAGIV-ZOHAR R;AHARONOV R Dynamic model of the octopus arm I.Biomechanies of the octopus reaching movement 2005(02)45.YEKUTIELI Y;SAGIV-ZOHAR R;HOCHNER B Dynamic model of the octopus arm II.Control of reaching Movements 2005(02)46.YIANG Y;MCMEEKING R;EVANS A A finite element simulation scheme for biological muscular hydrostats[外文期刊] 2006(01)47.YAO Yufeng;ZHAO Jianwen;HUANG Bo Motion planning algorithms of redundant manipulators based on self-motion manifolds[期刊论文]-Chinese Journal of Mechanical Engineering 2010(01)48.HE Guangping;LU Zhen Self-reconfiguration of underactuated redundant manipulators with optimizing the flexibility ellipsoid[期刊论文]-Chinese Journal of Mechanical Engineering 2005(01)49.CHO K J;KOH J S;KIM S Review of manufacturing processes for soft biomimetic robots[外文期刊] 2009(03)50.LEESTER-SCHADEL M;HOXHOLD B;LESCHE S Micro actuators on the basis of thin SMA foils 2008(04)COUR S P;JONES J;SUO Z Design and performance of thin metal film interconnects for skin-like electronic circuits[外文期刊] 2004(04)COUR S P;JONES J;WAGNER S Stretchable interconnects for elastic electronic surfaces[外文期刊] 2005(08)53.KIM D H;ROGERS J A Stretchable electronics:Materials strategies and devices[外文期刊] 2008(24)54.KHANG D Y;JIANG H;HUANG Y Silicon does the wave 2006(13)55.SOMEYA T;KATO Y;SEKITANI T Conformable,flexible,large-area networks of pressure and thermal sensors with organic transistor active matrixes[外文期刊] 2005(35)56.ZULLO L;SUMBRE G;AGNISOLA G Nonsomatotopic organization of the higher motor centers in octopus[外文期刊]2009(19)本文链接:/Periodical_jxgcxb201203004.aspx。

并联机器人综述(英文经典),Parallel kinematics

并联机器人综述(英文经典),Parallel kinematics

_______________________________________________________________________________________ Parallel Kinematics 12P a r a l l e l K i n e m a t i c shis document surveys parallel-kinematics literature and identifies its usefulness. Thedocument has been developed while we were developing our SimParallel machine.On of the aims of this document is to propose an effective solution to the limitations of thetwo rotary axes of five-axis machines that are currently used in industry. However, thesurvey of the parallel-kinematics literature will not be limited to this (two DOFs) family ofparallel kinematics mechanisms lest a seed for an idea for our sought mechanism does existin parallel-kinematics mechanisms with other DOFs. The available parallel mechanismsconcepts will be mentioned and then their kinematics usefulness to our purpose will be morecritically stated in the conclusion section.The document consists of the following 11 sub-sections;•Parallel-Kinematics Mechanisms. •Six DOFs Parallel-Kinematics Mechanisms. •Spatial Translational Three-DOFs Parallel-Kinematics Mechanisms. •Spatial Rotational Three-DOFs Parallel-Kinematics Mechanisms. • Other Three-DOFs Parallel-Kinematics Mechanisms.•Asymmetric Parallel-Kinematics Mechanisms. •Two DOFs Parallel-Kinematics Mechanisms. •Four and Five-DOFs Parallel-Kinematics Mechanisms. •Parallel-Kinematics Mechanisms Redundancy. •Parallel-Kinematics Mechanisms in Industrial Machine-Tools. •Summary and Conclusions1. Parallel-Kinematics MechanismsThe conceptual design of PKMs can be dated back to the middle of the last century whenGough established the basic principles of a mechanism with a closed-loop kinematicsstructure and then built a platform for testing tyre wear and tear [Gough, 1956]. A sketch ofthe mechanism is shown in Figure 1. As shown in the figure, that mechanism allowschanging the position and the orientation of a moving platform with respect to the fixedplatform.T______________________________________________________________________________________ Parallel Kinematics 13Later in 1965 Stewart designed another parallel-kinematics platform for use as an aircraftsimulator [Stewart, 1965]. A sketch of that Stewart mechanism is shown in Figure 2. Forsome reason the mechanisms of Figure 1 and that of Figure 2 as well as many variations (e.g.the one shown in Figure 3 ) are frequently called in the literature Stewart platform. They arealso called Hexapod mechanisms.Figure 2 Stewart Platform Figure 1Gough Platform______________________________________________________________________________________Parallel Kinematics 14Of course other mechanisms related, may be less formally, to PKM existed well before andsoon before Gough’s platform. Bonev [2003] surveyed many of these earlier mechanisms.Gough though is the one who gave some formalization to the concept. It might beinteresting to know that Gough’s platform remained operational till year 1998 and it is nowkept at the British National Museum of Science and Industry. See Figure 4 for photos of theoriginal and current shapes of Gough platform.Many have extensively analyzed Gough/Hexapod platform [Hunt, 1983, Fichter 1986,Griffis and Duffy, 1989; Wohlhart, 1994]. One problem with these six-DOFs platforms isthe difficulty of their forward-kinematics solution, because of the nonlinearity and the highlycoupled nature of their governing equations. This difficulty has been overcome byintroducing some assumptions [Zhang and Song, 1994] and a closed-form solutiuon can befound in [Wen and Liang, 1994]. Others introduced some sensors to measure at least one ofFigure 4Old and Revived Gough Platform Figure 3 Gough-Stewart-Hexapod Platformthe variables of the platform and hence reduce the unknowns of the governing equations[Merlet, 1993; Bonev et al, 1999]. The above mechanisms are six DOFs mechanisms becauseeach of them allows the moving platform to move arbitrarily (within the limit of the work-space) in the six DOF space.Having had a look on the mechanisms above one can now introduce a formal definition ofparallel-kinematics mechanisms; A parallel-kinematics mechanism (or parallel manipulator) isa closed-loop mechanism. That is, a moving plate (ie end-effector) is connected to thestationary base by at least two independent kinematic chains, each of which is actuated. Onthe other hand, A serial-kinematics mechanism (or serial manipulator) is an open-loopmechanism in which each link is connected to ONLY two neighbouring links. All themechanisms discussed in the introduction of Chapter 1 are serial-kinematics mechanisms.The advantages of parallel-kinematics mechanisms in general are;•Excellent load/weight ratios, as a number of kinematic chains are sharing the load.•High stiffness, as the kinematics chains (limbs) are sharing loads and in many cases the links can be designed such that they are exposed to tensile and compressive loadsonly [Hunt, 1978]. This high stiffness insures that the deformations of the links willbe minimal and this feature greatly contributes to the high positioning accuracy ofthe manipulator.•Low inertia, because most of the actuators are attached to the base, and thus no heavy mass need to be moved.•The position of the end-effector is not sensitive to the error on the articular sensors.Higher accuracy due to non-cumulative joint error.•Many different designs of parallel manipulators are possible and the scientific literature on this topic is very rich, as will be shown later in this chapter.•The mechanisms are of low cost since most of the components are standard.•Usually, all actuators can be located on the fixed platform.•Work-space is easily accessible.•The possibility of using these mechanisms as a 6-component force-sensor. Indeed it can be shown that the measurement of the traction-compression stress in the linksenables to calculate the forces and torques acting on the mobile platform. This isespecially useful in haptic devices [Tsumaki et al, 1998].On the other hand, the disadvantages of parallel-kinematics mechanisms in general are;•For many configurations there are some analytical difficulties ( eg the forward kinematics solution is not easy or finding all the mechanism singularities can beextremely difficult task).•The need in many cases for the expensive spherical joints.•Limited useful work-space compared to the mechanism size.•Limited dexterity.•Scaling up PKMs can enlarge the translational DOFs and usually is unable to enlarge the rotational DOFs.•Potential mechanical-design difficulty.•Mechanism assembly has to be done with care.•Time-consuming calibration might be necessary. See [Ryu and Abdul-rauf, 2001] to realize that calibration of PKMs is not a trivial issue.______________________________________________________________________________________ Parallel Kinematics 15______________________________________________________________________________________Parallel Kinematics 16Many other different points of view about the benefits of PKMs and their drawbacks can befound in the literature [Brogårdh, 2002].2. Six-DOFs PKMsThe PKMs mentioned in the previous section are six-DOFs PKMs. Some of thesemechanisms have S-P-S kinematics chains. S-P-S chains are preferred as they, as discussed inAppendix A, transmit no torque through the limbs. These PKMs can also be realized usingS-P-U chains or any other chain that has six-DOFs associated with its joints. One can checkthat against Grübler/Kutzbach criterion above, or review Appendix A. In fact acomprehensive attempt to enumerate the joints combinations and permutations that can beutilized when all the limbs are identical has been reported [Tsai, 1998]. It can also be shownthat the DOFs associated with the limbs joints need to be at least six. See Appendix A too.Figure 5 shows one PKM that has been proposed. It uses six P-R-U-U limbs [Wiegand et al,1996]. Similar to the PKMs above this one also has limited tilting ability. The reachabletilting angle changes strongly with the position of the P joints and fluctuates between 20 and45 degrees. In special poses up to 57 degrees can be reached.It is important to notice that changing the number of limbs in symmetrical six-DOFs PKMswill not change the DOFs of the platform. This has been shown using Grübler/Kutzbachcriterion in Appendix A, and also can be observed in Figure 6 to Figure 9. In these examplesthough we need more than one actuator per limb, and if there are less than six actuatorssome of the DOFs will not be controllable.A Symmetrical PKM is one that has identical kinematics chains (also called limbs or legs)each of which utilize identical actuator.Figure 6 shows another six-DOFs PKM [Tsai and Tahmasebi, 1993]. This PKM has three P-P-S-R limbs. However, planar motors can not provide high load-carrying capacity and theyoccupy the whole base leaving no space to the material to be processed. A similar PKM waslater built and studied [Ben-Horin et al, 1996]. Figure 7 shows a PKM with three P-P-R-Slimbs [Kim and Park, 1998; Ryu et al, 1998]. The range of tilting angles of the platform ofthis mechanism is one of the widest that can found in the literature. However, themechanism uses 8 actuators (for the six P joints and two of the R joints) to realize themotion that can be realized with six actuators only, and many translational motions can beFigure 5 Six-DOFs PKM withsix P-S-U limbs______________________________________________________________________________________ Parallel Kinematics 17realized in direct straight lines. A PKM similar to that shown in Figure 7 has been proposedearlier [Alizade and Tagiyev, 1994]. That earlier PKM had three P-R-P-S limbs instead.Figure 6 Six-DOFs PKM with three P-P-S-R chains Figure 7 Six-DOFs PKM with three P-P-R-S chains Figure 8 Six-DOFs PKM using three Scott mechanisms( b ) ( c )______________________________________________________________________________________Parallel Kinematics 18Probably no mechanism is more famous than the single DOF crank-slider of Figure 8.a. It isa P-R-R-R kinematic chain that coverts linear to rotary motion or vice versa. Scott’smechanism of Figure 8.b [Khurmi and Gupta, 1985] is another traditional planar mechanismthat greatly resembles the well known crank-slider mechanism. Three of these Scottmechanisms have been put together, as shown in Figure 8.c, to realize a three-DOFsmechanism and then each of the Scott mechanism was made to displace vertically, resultingin a six-DOFs mechanism [Zabalza et al l, 2002]. Some of the R joints of the originalmechanism have been replaced by S joints to allow spatial motion of the arms. Theadvantage of the concept is that if one attempts to express the position and the orientationof the platform via its three vertices, then the kinematics relations will be fairly decoupled.The PKMs of Figure 6 and Figure 7 could be considered decoupled. Other six-DOFsdecoupled PKMs have also been proposed [Zlatanov et al. 1992; Wohlhart, 1994].Spherical actuators that can provide three-DOFs actuation are expensive and notcommercially available [Williams and Poling, 2000], but if two of these actuators are used theGough-Stewart platform of Figure 3 can be reduced to the one shown in Figure 9. Pendingthe quality and the mechanical characteristics of these spherical actuators, the solution offersan elegant and promising solution. The work-space, as least the translational part of it, is stilllimited though and load is shared between two rather than six limbs.Six-DOFs PKMs represent the roots of the concept of PKMs and hence they had to belooked at. However, one might say that a six DOFs PKM is PKMs at their extreme, andconsequently one might think that reducing the number of DOFs that act in parallel mightalleviate the disadvantages of parallel-kinematics mechanisms while benefiting from theiradvantages. This is actually true in many cases. In trials to avoid the disadvantages of sixDOFs parallel-kinematics mechanisms while utilizing the other benefits of parallel-kinematics mechanisms, two, three, four and five DOFs PKMs were proposed, as will beshown in the subsequent sections.3. Spatial Translational Three-DOFs PKMsThree-DOFs PKMs for pure rotation or pure translation are of special importance as theyare, in our view, represent a low-level entity or building block of PKMs that helps deepeningthe understanding of these mechanisms. One can subsequently hybridize these two buildingFigure 9 Six-DOFs PKM with two S-P-U Chains______________________________________________________________________________________ Parallel Kinematics 19blocks or sub-systems from them. Spatial translational three-DOFs PKMs are discussed inthis section and spatial rotational three-DOFs PKMs are discussed in the next section.Using Grübler/Kutzbach criterion one can see that using three limbs (legs) each having five-DOFs is one way to realize three-DOFs symmetrical PKMs. See Appendix A for examples.Many of such PKMs have been built and Figure 10 to Figure 13 show examples of thisfamily of translational three-DOFs PKMs. That is, Figure 10 shows a PKM with three limbseach with U-P-U joints [Tsai, 1996]. This mechanism has been studied by others [DiGregorio and Parenti-Castelli, 1998] and been further optimized [Tsai and Joshi, 2000] andits mobility also has been discussed in details [Di Gregorio and Parenti-Castelli, 2002].Obviously the same kind of motion can also be obtained using P-U-U kinematic chains[Tasora et al, 2001], as shown in Figure 11.Figure 10 Translational U-P-U PKM Figure 11 Translational P-U-U PKM______________________________________________________________________________________Parallel Kinematics 20One should notice that the U-P-U mechanism is a special case from the R-R-P-R-Rmechanism, when the axes of each R-R pairs are perpendicular. This R-R-P-R-R has beenstudied and the conditions that need to be satisfied to enable its pure translational motionhas been established [Di Gregorio and Parenti-Castelli,1998]. The P joints can also bereplaced by R joints and the result is shown in Figure 12 [Tsai, 1999]. Alternatively one ofthe R joints could be replaced by P joints resulting in R-P-R-P-R (or R-C-C; C forCylindrical) [Callegari and Marzitti, 2003]. This is shown in Figure 13.In fact all the combinations and permutations the basic R and/or P joints that would resultin PKMs with three five-DOFs limbs have been enumerated [Tsai, 1998; Kong andGosselin, 2001]. Notice that if pure translation is sought using symmetrical PKMs, then Sjoints would not be a favorable choice as one S joint in each limb simply means that rotationcannot be constrained.The Delta mechanism [Clavel, 1988] is one of the earliest and the most famous spatialtranslational three-DOFs parallel-kinematics robots, as it has been marketed and usedindustrially for pick and place applications. A sketch of this mechanism is shown in Figure14. This mechanism can provide pure 3D translational motion to its moving platform usingits three rotary actuators via its three limbs. Each of these limbs actually is a R-R-Pa-RFigure 12 Translational R-U-U PKM Figure 13 Translational R-P-R-P-R (R-C-C) PKM______________________________________________________________________________________ Parallel Kinematics 21 (Revolute-Revolute-Parallelogram-Revolute) kinematic chain. The mechanism can alsoprovide a rotary independent motion about the Z axis as a 4th decoupled DOF.Many variations of that Delta mechanism has been proposed and implemented. One ofthese close variations is the patented Tsai’s manipulator [ Tsai, 1997; Stamper 1997 ], whichalso provides 3D translational motion to its platform. Here, the parallelograms areconstructed using R joints instead of S joints and Stirrups in the previous case. Thatmechanism is shown in Figure 15. Another close variation was also presented [Mitova andVatkitchev, 1991]. The kinematic chains of that variation were R-Pa-R-R instead.A P-R-Pa-R with vertical prismatic joints was also suggested [Zobel et al, 1996]. Variationsextremely similar to that were later implemented using pneumatic drives [Kuhlbusch andNeumann, 2002]. These variations are shown in Figure 16.Figure 14Clavel-Delta translational PKMFigure 15Tsai or Meryland translationalPKM______________________________________________________________________________________When the lines of action of the three prismatic joints are tilted further till all of them are inthe horizontal plane, the star mechanism of Figure 17 is then obtained. This mechanism wasdeveloped by Hervé [Hervé and Sparacino, 1992]. Notice here that the prismatic joints arereplaced by helical ones (ie screw & nut), which should not represent a difference fromkinematics points of view.Figure 16Translational P-R-Pa-R PKMs Figure 17 Herve ’ Star translational PKM Figure 18 The Orthoglide translational PKM ( a ) ( b )( c )______________________________________________________________________________________ Parallel Kinematics 23 The orthoglide mechanism [Wenger and Chablat, 2000 and 2002] is another variation withthe angles between the action lines of the prismatic joints are changed further resulting inbetter motion transformation (from joints to platform) quality. This is shown in Figure 18.Prior to that a similar mechanism has also been designed and built as a coordinate-measuring-machine [Hiraki et al, 1997]. In that mechanism the lines of action of theprismatic joints are changed further to guarantee that the heavy parts if the mechanism areresting on the machine base.Parallelograms represent a common thread among the mechanisms of Figure 14 to Figure 18as a parallelogram would directly constrain the rotational motion about certain axis. SeeAppendix A. Notice also that in all the designs above the two axes of the two revolute jointsof each chain are always parallel, sometimes parallel to the direction of the prismatic joint (ifany) and sometimes perpendicular to it, which agrees with conditions shown later in theliterature [Kong and Gosselin, 2004b].It is important to notice that each limb of each of the PKMs of Figure 14 to Figure 18 hasonly four-DOFs associated with its joints. According to Grübler/Kutzbach criterion thesePKMs are not mobile [Stamper, 1997]. In fact some mechanisms are mobile only undersome geometric conditions. These are called internally over-constrained mechanisms. SeeAppendix A for more about these over-constrained mechanisms. Screw theory can beutilized in conjunction with the Grübler/Kutzbach criterion [Huang and Li, 2002] to showthe mobility of these over-constrained mechanisms.Further, other (that do not utilize parallelograms) spatial translational PKMs with three limbseach of which having four-DOFs have been proposed. Symmetrical PKMs that have three(P-R-R-R) limbs and are aimed at realizing pure spatial translational motion have been built[Kong and Gosselin, 2002a; Kong and Gosselin, 2002b]. Two of these PKMs are shown inFigure 19. For these over-constrained PKMs to realize pure translation the followinggeometrical conditions need to be satisfied;• The axes of the 3 R joints within the same limb are parallel.• The three directions of the R joints of the limbs should not be in the same plane orparallel to the same plane.• Within the same leg the axis of the P joint is not perpendicular to the direction of the R joints axes.Figure 19 Translational Over-Constrained P-R-R-R PKMThe directions of the P joints don’t have to be parallel, but if they are this will help enlarging the work-space. Also, it has been shown that if the three directions of the R joints are perpendicular to each other linear isotropic transformations will be obtained throughout the work-space (and thus no singularities). Compare that to the isotropic conditions reported for the orthoglide mechanism of Figure 18. Isotropic transformation is discussed further in Chapter 4.The geometrical conditions of the mobility of a similar over-constrained PKMs that has three C-P-R (P-R-P-R) limbs, shown in Figure 20, have also been found [Callegari and Tarantini, 2003]. These conditions are;•The axes of the 2 R joints within the same limb are parallel.•The three directions of the R joints of the three limbs should not be in the same plane or parallel to the same plane.It has been shown that singularity of that mechanism can be kept outside the work-space while maintaining a convex work-space. The isotropic points of that mechanism have also been shown.Figure 20Translational Over-ConstrainedP-R-P-R Symmetrical PKMIn fact the geometrical conditions of the different over-constrained PKMs that utilize four-DOFs limbs have been enumerated [Hervé and Sparacino, 1991; Kong and Gosselin, 2004a].Using three limbs each with P-P-P joints is actually another, may be trivial, over-constrained translational PKMs.Another concept that has been extensively utilized at the industrial level is presented now. If three limbs each with six-DOFs (eg U-P-S kinematic chain) associated with its joints are used, then the platform will have six DOFs (as discussed in Appendix A). However, if less than six actuators are used with these three limbs then some DOFs will not be controllable.After choosing which DOFs are to be controlled, one can compensate for the known but uncontrolled motion of the remaining DOFs using other, may be serial, mechanism. One can also use some limbs to mechanically constraint some of the platform DOFs. In fact this is the basic idea behind Neumann’s patented mechanism [Neumann, 1988] of Figure 21.This seems like creating some DOFs that are needed and then constraining or compensating for them. Still, the idea has been utilized. Various aspects of this PKM has been studied extensively [eg Siciliano, 1999] and a further utilization of the concept will be shown in a subsequent section of this chapter. One might say or think that this concept/mechanism is actually is under-utilization of resources because of a prior conviction to utilize a Gough-like platform/limbs.____________________________________________________________________________________________________________________________________________________________________________ Parallel Kinematics 254. Spatial Rotational Three-DOFs PKMsExactly as in the case of spatial translational three-DOFs PKMs spatial rotational three-DOFs PKMs can be realized using three limbs each with five-DOFs associated with itsjoints. The difference now is how the joints of the PKM would be assembled. A PKM withthree U-P-U limbs, just like the one discuused in conjunction with Figure 10, has beenproposed [Karouia, and Hervé, 2000]. Another PKM with three R-R-S (or R-S-R) limbs, asshown in Figure 22, has also been proposed [Karouia, and Hervé, 2002a]. PKM with threeR-U-U have also been presented as well [Hervé and Karouia, 2002b]. Figure 23 also showshow to use three P-R-P-R-R (or C-P-U) limbs to realize a spherical/rotation three-DOFsPKMs [Callegari et al 2004]. PKMs with three U-R-C and with three R-R-S legs have beenproposed as well [Di Gregorio, 2001; Di Gregorio, 2002]. A PKM that utilizesparallelograms (similar to the delta PKM above) within its three R-Pa-S limbs was yetanother propsoed spehrical PKM [Vischer and Clavel, 2000]. In fact the possible sphericalPKMs that are based on five-DOFs limbs are enumerated [Kong and Gosselin 2004b; Kong and Gosselin 2004c; Karouia, and Hervé, 2002b; Karouia, and Hervé, 2003].Figure 21 Neumann ’s constrained U-P-S PKM Synthesis of three-DOFs translational PKMs based on either Lie/Displacement group theory [Hervé and Sparacino, 1991; Hervè, 1999] or on screw theory [Tsai, 1999; Kong and Gosselin, 2004a] have been discussed. Figure 22 Orientation R-S-E PKM______________________________________________________________________________________Again, as in the translational case, over-constrained PKMs can be used to realizeorientational PKMs. If only R joints are used then three R-R-R legs can be used [Gosselinand Angeles, 1989]. The geometric condition that will mobilize this over-constrained PKM isthat all the axes of the used R joints are to be concurrent at the rotation center of themechanism. See Figure 24. Figure 25 shows one of these R-R-R limbs separately. Notice thatin this case the space freedom ( λ ) is three as no element of the mechanism is translating,which should simplify the application of Grübler/Kutzbach criterion. Notice also that onlytwo R-R-R legs can theoretically be used to realize a three-DOFs rotational PKM. SeeAppendix A. This is not usually favorable though as one actuator will not be placed on thePKM base. For isotropic transformation the axes of the R joints of each limb should beperpendicular to each other [Wiitala and Stanisi ć, 2000].Figure 24 Orientation R-R-R over-constrained PKM Figure 25 Orientation R-R-R limb Figure 23 Orientation C-P-U PKMWhen P joints are used then four-DOFs legs can be used to realize over-constrainedrotational PKMs [Kong and Gosselin, 2004c]. The combinations and permutations ofpossible over-constrained spherical PKMs as well as their necessary geometrical conditionsare enumerated [Kong and Gosselin, 2004b; Kong and Gosselin, 2004c].As happened in the translational case using Neumann’s PKM of Figure 21, three six-DOFslegs can be used to realize a six-DOFs PKM and then mechanically constrain thetranslational DOFs. The limbs used can have kinematic structure of P-U-S or R-U-S or theirvariations, as per Figure 26. In these cases an arm extending from the base is used topivot/constrain the platform. The P-U-S or R-U-S chains can theoretically be replaced by S-P-S chain, which also has six DOFs associated with its joints [Mohammadi et al, 1993], asshown in Figure 27.( a ) ( b)( c)Figure 26Orientation U-P-S or R-U-S PKMFigure 27Orientation S-P-S PKM______________________________________________________________________________________ Parallel Kinematics 27Type synthesis of three-DOFs rotational PKMs based on either Lie/Displacement group theory [Karouia and Hervé, 2003] or on screw theory [Kong and Gosselin, 2004b] have been discussed.5.Other Three-DOFs PKMsSo far spatial three DOFs mechanisms have been discussed. Three DOFs mechanisms can provide planar motion too. That is, they can provide the platform with two translational motions and one rotational motion about the plane normal. If, one relies on P and/or R joints as well as Grübler/Kutzbach criterion, then one can find that there are 7 possible symmetrical mechanisms. These are (RRR, RRP, RPR, PRR, RPP PRP, and PPR). S and U joints here not useful here. Each of the three identical kinematic chains in this case needs to have 3 DOFs [Tsai, 1998]. Figure 28 [Hunt, 1983] and Figure 29 [Tsai, 1998] represent two of these possible seven mechanisms that have actually been implemented.Figure 28Planar R-R-R PKMFigure 29Planar P-R-P PKMFigure 30Planar PKM with three PRR limbsor redundancyThe mechanism of Figure 30 is another planar symmetrical 3 DOF PKM that has been proposed [Marquet et al, 2001]. Three P-R-R limbs are used. In the figure one can actually see a 4th chain. This is actually a redundant one to treat singularity, which will be discussed in Section 7. With this fourth P-R-R limb P-U-S limbs have also been proposed.Planar PKMs cannot provide two spatial rotational DOFs and hence they can not directly serve the purpose of this work, and hence they are surveyed thoroughly. Other PKMs can ______________________________________________________________________________________。

FESTO CP Factory系统介绍说明书

FESTO CP Factory系统介绍说明书

The introduction of CP Factory production line, ideal technological platform for study andresearch in the field of automationIng. Jan JirsaThe College of Polytechnics in Jihlava, Czech RepublicAbstract: This year we have open a new laboratory of automation and robotics in the Department of Technical Studies at the College of Polytechnics in Jihlava. Our laboratory is equipped with a FESTO CP Factory production line in the biggest configuration in the middle Europe. This system which includes physical components and many virtual tools can be used in education, research and cooperation with industrial companies.Keywords: INDUSTRY 4.0, VIRTUALIZATION, MES, DIGITAL TWIN, FESTO1. IntroductionThe CP Factory system is an educational industrial productionline comprised of individual stations. Every station consists of aconveyor and an application module (drilling module, heating, pressetc.). Both the parts are independent and can be easily switched.The control system is based on PLC Siemens ET200. Its programcontains not only a control loop for the application and theconveyor but also a web server and primarily an interface of theMES4 program, which creates the user interface of the entire line.Further, every station is equipped with a Siemens HMI panel formanual control and potential configuration in the offline mode.Online communication is based on a unique protocol, defined by FESTO, which uses the standard TCP/IP protocol at the transport layer, but it is ready for OPC UA implementation..Fig. 1 This figure shows the actual installation of the CP Factory production line in the Laboratory of Automation and Robotics at the College of Polytechnics in Jihlava.2. MesMES role in Industry 3.0 a 4.0The main principle of the Industry 3.0 system is a hierarchical control structure. In this approach, MES is the central control system which directly manages all subsystems and components at lower levels. It is the master giving orders to the target PLC and other systems.In the Industry 4.0 definition, MES is only a datasource, ideally distributed over all subsystems of the target production process including the processed material and workpieces.But the user function of this system must be the same. MES has to provide us especially with:•Process control system (information about resources, storages, material etc.)•On- line process control by lower control levels•Order management•Process and order history•Production tracking and history monitoring•Quality parameters reporting Fig. 2 The basic Industry 4.0 idea is a change of hierarchical control structure to open communication interface between independent and intelligent objects.FESTO implementationFESTO MES4 is a graphic tool containing a database connector and a communication interface to all parts of the production line.The database contains complete information of production stations (resources), materials, products and actual or planned operations. Each type of a production part is represented by a record in the database. The record unambiguously identifies all information about the history of the part and its connections to the target production process.The MES4 database is used as a data source when the production station is to decide whether and by means of which operation the target part will be produced. On the product, there is only one component ID that is stored in an RFID chip of every product carrier and connected to the database record. From this point of view, it is a data-controlled production process. FESTO implementation is therefore really close to the ideal Industry 4.0 MES idea, but it is not completely faithful. The datasource is centralized to one physically MS Access database here. It is not distributed over lower subsystems.Communication protocolThe communication between the MES system and target resources is executed by a special communication protocol, defined by FESTO and based on the standard TCP/IP layer. Each operation or query is represented by a unique command with defined ID and structure. These commands can be transported via the TCP layer in the binary form or as a pure text. The string form is ideal for education and for demonstration of the function of target command. The binary form is intended for real deployment.In the OSI model, this protocol could be placed in presentation or application layer. Session layer is not used in this case. This protocol can be switched to the OPC UA standard, ideally without any change at lower layers. FESTO currently does not have a satisfactory implementation of OPC UA, so there is space for our further research and development.3.Virtual part of the systemCIROSCIROS is a 3D development studio that provides not only the 3D model drawing but also programming and simulation of its behavior. The created model can be connected to a virtual or physical PLC. Hundreds of models of industry robots from many global producers are integrated in the studio (Kuka, ABB, Mitsub ishi etc.). In CIROS it is possible to develop a robot’s software in native programming languages and run the program not only in simulation, but also upload it to the real robot.The line and robotino modelThe picture shows a model of our actual CP Factory line. On the MES level, this model is a digital twin of the real system. It is not a full-blown virtual twin, however, if we focus on deep detail. This model is not able to simulate, for example, physical properties of the components or the environment, such as inertia, thermal expansion or gravity. It is therefore clear that the term “digital twin” cannot be considered absolute. It is necessary to relate it to thecontext and level of detail of the model.Box making machine modelThe picture shows a basic proposal of a robotic machine for paper box completion. This is an example of a machine that is currently being designed in the Department of Technical Studies at the College of Polytechnics in Jihlava. It is convenient to create it inCIROS and show its function to a customer.4.RobotinoAutonomous robots called Robotino are an independent part of the CP Factory system. They are mobile robots equipped with multiple sensors and cameras that are able to move independently and that provide material transport. They can be included in the CP Factory system, but they can also work quite independently. Robotino is Linux-based and every mode of behavior is started as a regular UNIX application. For the mode independent of the CPFactory system, a number of development tools are provided. FESTO provides the RobotinoVIEW development tool, which offers graphical programming such as LabVIEW (a tool from National Instruments). However, there are many others programming interfaces provided, e.g. libraries for C, MATLAB or LabVIEW. Not all of these development platforms are provided for the latest version Robotino 3, though. For example, libraries for MATLAB are provided only for the 2011b version or later. To develop in the current MATLAB version, HTTP communication protocol and REST-API have to be used. A library for direct MATLAB control of Robotino is the aim of our current research in the Department of Technical Studies at the College of Polytechnics in Jihlava.Robotino in CP Factory systemTwo different communication protocols used for the interaction between Robotino and the CP Factory system must be distinguished. Firstly, there is the MES protocol, and secondly, the protocol for Robotino. Both protocols are independent and have their own unique commands and attributes. FleetManager is a special software tool serving as a bridge between these two protocols.A typical command of the MES protocol is GetOperationForResource . This is a general query which gets an ID of the planned operation for the target resource. An example of Robotino protocol command can be LoadBox , a specific order for loading a box with material, applicable only for Robotino.However, both of these protocols are based on standard TPC/IP. Due to the absolute openness of the whole system, it is possible to communicate via Robotino protocol manually and therefore simulate not only the MES system, but also the FleetManager bridge, but only in case that Robotino is switched to the CP Factory compatible mode. We can order Robotino to go to a target position in the CP Factory map system, but we cannot control single sensors, motor drivers or the camera. This is possible only in the mode independent on CP Factory via RobotinoVIEW or other programming tools.RobotinoSimRobotinoSim is a virtual t ool for the simulation of Robotino’s behavior and its interaction with its environment. The tool implements basic kinematics principles and the behavior of all designed objects is consequently really close to reality.5. ConclusionVirtualization and simulation is an integral part of industry production in this time and their importance will be increasing in the future. It is because of requests of maximal efficiency of production and production processes. The basic goal is an integration of many different subsystems and solutions over all production process. In this case, CP Factory system, based on maximal openness is a good solution offered easy integration of other components from third part producers. Our next research in the Department of Technical Studies will be focused on integration of an industry communication standard OPC UA.。

六轴工业机器人的轨迹规划与控制系统研究

六轴工业机器人的轨迹规划与控制系统研究

学校代码:10213 密级:公开
工学硕士学位论文
六轴工业机器人的轨迹规划 与控制系统研究
硕 士 研究生 : 导 申 请 专 所 在 答 辩 师: 学 位: 业: 单 位: 日 期:
宋金华 马新军 工学硕士 电气工程 深圳研究生院 2013 年 12 月 哈尔滨工业大学
授予学位单位 :
万方数据
Classified Index: TP24 U.D.C: 629.7
硕士学位论文
ON TRAJECTORY PLANNING AND CONTROL SYSTEM OF SIX AXIS INDUSTRIAL ROBOT
宋金华
哈尔滨工业大学 2013 年 12 月
万方数据
国内图书分类号:TP24 国际图书分类号:629.7
kinematicsanalysiscontrolsystemtrajectoryplanningopenglii万方数据哈尔滨工业大学工学硕士学位论文目录摘要iabstractii第一章绪论111研究的背景和意义112工业机器人研究现状2121国内工业机器人发展状况2122国外工业机器人发展状况313工业机器人未来的发展趋势314课题的来源及主要研究内容4第二章六轴工业机器人的硬件系统设计621控制系统硬件总体设计622机器人本体设计823本章小结9第三章六轴工业机器人建模1031概述1032坐标变换1133正运动学分析1334逆运动学分析1735本章小结22第四章六轴工业机器人的轨迹规划算法及其优化2341概述2342机器人笛卡尔空间的轨迹规划23421笛卡尔空间轨迹的三次样条插值234225段s曲线加减速控制算法25423s曲线加减速控制算法的优化26424笛卡尔空间三次样条插值的matlab仿真2843本章小结31第五章六轴工业机器人的软件系统设计3251概述3252上位机控制界面设计3353rs232总线数据通信程序设计351万方数据哈尔滨工业大学工学硕士学位论文54视觉信息处理软件设计3755基于opengl的机器人三维仿真工具设计38551软件框架的设计39552机械臂实体的绘制39553仿真工具的功能4056本章小结41结论43参考文献44哈尔滨工业大学学位论文原创性声明和使用权限47致谢482万方数据哈尔滨工业大学工学硕士学位论文第1章绪论11研究的背景和意义到现在为止人类在机器人技术方面进步的已经得到了很大的提升

arm 位置无关指令实现原理

arm 位置无关指令实现原理

arm 位置无关指令实现原理Arm position-independent instruction is a concept that refers to a set of instructions that can be executed on an arm without the need to specify the exact position of the arm in space. This is an important feature in robotics, as it allows for more flexible and adaptable control of robotic arms in various applications.Arm位置无关指令是一个概念,指的是一组指令,可以在机械臂上执行,而无需指定机械臂在空间中的确切位置。

这在机器人技术中是非常重要的,因为它可以更灵活和可适应地控制机械臂在各种应用中。

The implementation of arm position-independent instructions is based on the use of kinematic algorithms and forward and inverse kinematics. These algorithms are used to calculate the position and orientation of the end-effector of the robot arm, without the need for explicit position information. This allows for the generation of motion commands that are independent of the initial position of the arm, making it possible to execute the same set of instructions regardless of the starting position of the arm.Arm位置无关指令的实现基于运动学算法和正向逆向运动学。

工业机器人手部三指抓取的结构设计说明书

工业机器人手部三指抓取的结构设计说明书

工业机器人手部三指抓取的结构设计机械设计及其自动化学生指导教师【摘要】:随着工业的大规模的发展,越来越多工业机器人操作手应用于各个场所并逐渐受到各国开发者关注和重视。

而最后执行者作为机器人于环境互相作用的机械指已经被提到了新的高度,文中简要介绍机械抓取机构的概念,机械抓取机构的组成与分类国内外的发展状况及发展前景。

调研现有工业机器抓取机构工作原理和结构设计提出工业机器人三指抓取机构的结构原理,然后将任务要求和对象物体的几何物理特性以及环境信息综合起来考虑,经过分析建立于东学的模型,仿真各个手指在抓取时的运动姿态,同时完成分析在静平衡状态下手指和外界环境之间的作用力。

并将抓取的姿态推理出来,同时寻找抓取物体特征平面,确定出所需要抓取的平面,再在抓取的平面上进一步规划出三个抓取点,并最终完成抓取结构设计。

【关键词】工业机器人三指抓取机构结构设计Industrial robot manipulators three fingers grab theinstitutional structure design【Abstract】With the large-scale industrial development, more and more industrial robot manipulators used in various places, and gradually by the concern and attention of the Inter-developer. Mechanical means as robots interact with the environment the final implementation, has been referred to a new level. The paper briefly introduces the mechanical grab the concept of the composition and classification of mechanical grab institutions, the industrial robot refers to crawl the principle of the structure. And comprehensive task requirements and object geometrical physical characteristics, and environmental information into consideration to establish the kinematics of the model through the analysis, simulation of individual fingers crawl athletic stance, and finger to complete the analysis in the static equilibrium state and the external environment between the forces. Attitude reasoning and crawl out and grab objects by looking for characteristic plane, identified the need to capture the plane 3 crawl further planning, and then grab the plane, and the final completion of the crawl structure design.【Key words】Industrial robots Three fingers grab the institutional Structure design目录绪论.........................................................1.前言1.1机械手概述...............................................1.2机械手的组成和分类.......................................1.2.1机械手的组成.......................................1.2.2机械手的分类.......................................2.机械手的设计方案2.1机械手的坐标型式与自由度.............................. 2.2机械手的手部结构方案设计.............................. 2.3机械手的手臂结构方案设计.............................. 2.4机械手的手臂结构方案设计............................... 2.5机械手的驱动方案设计................................... 2.6机械手的控制方案设计................................... 2.7机械手的主要参数.......................................2.8机械手的技术参数列表...................................3.手部结构设计3.1夹持式手部结构......................................... 3.1.1手指的形状和分类................................. 3.1.2设计时考虑的几个问题.............................3.1.3动力设计...............................4.手臂伸缩的尺寸设计与校核4.1手臂伸缩结构的尺寸设计与校核....................... 4.1.1手臂尺寸.............................................. 4.2 尺寸校核.............................................4.3 尺寸校核.............................................5.结论.................................................致谢......................................................参考文献...................................................专业相关的资料.............................................绪论1.前言1.1机械手概述:机械手是可以模仿人手和臂的某些动作和功能的,常常用在按固定顺序抓取、搬运物件或操作难度大的工具的自动操作装置。

  1. 1、下载文档前请自行甄别文档内容的完整性,平台不提供额外的编辑、内容补充、找答案等附加服务。
  2. 2、"仅部分预览"的文档,不可在线预览部分如存在完整性等问题,可反馈申请退款(可完整预览的文档不适用该条件!)。
  3. 3、如文档侵犯您的权益,请联系客服反馈,我们会尽快为您处理(人工客服工作时间:9:00-18:30)。
1
Kinematics and the Implementation of an Elephant’s Trunk Manipulator and other Continuum Style Robots
Michael W. Hannan and Ian D. Walker Dept. of Electrical and Computer Engineering, Clemson University, Clemson, 29634, USA mhannan@, ianw@
2
Fig. 1. Discrete Manipulator
the desired end-effector position requirements. Another drawback of discrete manipulators is that they require some specialized device for manipulation of an object. Most often this manipulation is done by attaching a gripper/hand at the end of the robot. Once again this design works well in many cases, but it is possible that a strategy where the
Abstract Traditionally, robot manipulators have been a simple arrangement of a small number of serially connected links and actuated joints. Though these manipulators prove to be very effective for many tasks, they are not without their limitations, due mainly to their lack of maneuverability or total degrees of freedom. Continuum style (i.e. continuous “backbone”) robots on the other hand, exhibit a wide range of maneuverability, and can have a large number of degrees of freedom. The motion of continuum style robots is generated through the bending of the robot over a given section; unlike traditional robots where the motion occurs in discrete locations, i.e. joints. The motion of continuum manipulators is often compared to that of biological manipulators such as trunks and tentacles. These continuum style robots can achieve motions that could only be obtainable by a conventionally designed robot with many more degrees of freedom. In this paper we present a detailed formulation and explanation of a novel kinematic model for continuum style robots. The design, construction, and
sections of a manipulator do the grasping, i.e. whole arm grasping, might be a better solution. The addition of more DOF for these conventional manipulators can further enhance their maneuverability and flexibility. We can relate this situation to the diversity of biological manipulators. As noted earlier, discrete manipulators resemble the human arm in structure, but if we look at other biological manipulators we see that this is not the only design. Animals such as snakes, elephants, and octopuses can produce motions from their appendages or body that allow the effective manipulation of objects, even though they are very different in structure compared to the human arm. Even among these appendages, i.e. trunks, tentacles, etc., their physical structure can vary, but they all share the trait of having a relatively large number of DOF. Research into manipulators with a large number of DOF or a high degree of maneuverability has spawned many different designs. The most popular design uses some type of “backbone” structure that is actuated by sets of cables [1][2][3][4][5]. Another design uses fluid filled tubes for actuation [6][7]. There are also other designs that are based on more conventional robot construction techniques [8]. These types of manipulators are commonly referred to as
a hyper-redundant manipulators due to their number of actuatable DOF being much larger than the DOF of their intended workspace. Due to the vast design possibilities Robinson and Davies [9] developed three classifications for
implementation of our continuum style robot called the Elephant Trunk Manipulator is presented. Experimental results are then provided to verify the legitimacy of our model when applied to our physical manipulator. We also provide a set of obstacle avoidance experiments that help to exhibit the practical implementation of both our manipulator and our kinematic model.
பைடு நூலகம்
the different possible designs. As introduced earlier, the first class which describes conventional manipulators is termed discrete robots. As the redundancy/maneuverability of the manipulator increases over that of discrete manipulators by increasing the number of discrete joints, it moves into the second classification known as serpentine robots. This classification would include hyper-redundant manipulators. The third classification of robots known as continuum Instead the manipulator
I. Introduction Over the last several decades the research area of robotic manipulators has focused mainly on designs that resemble the human arm. These conventional robots can be best described as discrete manipulators [9], where their design is based on a small number of actuatable joints that are serially connected by discrete rigid links, see Fig. 1. Discrete manipulators have been proven to be very useful and effective for many different tasks, but they are not without their limitations. These robots most often have five to seven degrees of freedom (DOF), thus in a spatial environment they will most often need all of their DOF just to position the end-effector. This design is very efficient for open environments, but as constraints are added to the environment it is possible that the manipulator can not reach its desired end-effector position. This failure is due to the lack of DOF in the robot to meet both the environmental constraint conditions and
相关文档
最新文档