A CONTROL ARCHITECTURE FOR DYNAMICALLY STABLE GAITS OF SMALL SIZE HUMANOID ROBOTS. Andrea Manni,1, Angelo di Noi and Giovanni Indiveri

Size: px
Start display at page:

Download "A CONTROL ARCHITECTURE FOR DYNAMICALLY STABLE GAITS OF SMALL SIZE HUMANOID ROBOTS. Andrea Manni,1, Angelo di Noi and Giovanni Indiveri"

Transcription

1 A CONTROL ARCHITECTURE FOR DYNAMICALLY STABLE GAITS OF SMALL SIZE HUMANOID ROBOTS Andrea Manni,, Angelo di Noi and Giovanni Indiveri Dipartimento di Ingegneria dell Innovazione, Università di Lecce, via per Monteroni, 7 Lecce, Italy, Fax: , {andrea.manni, giovanni.indiveri, angelo.dinoi}@unile.it Abstract: From the 97 s biped robots have had a large attention from the robotic research community. Yet the issue of controlling dynamically stable walking for arbitrary biped robots is still open. We propose a simple control architecture based on the use of the FRI (Foot Rotation Indicator) point and the support polygon. The major advantage of the proposed architecture is that motion planning (and eventually sensor based re-planning (slower feedback loop)) is limited to the leg joints whereas the trunk and arm degrees of freedom are controlled in closed loop (faster feedback loop) to achieve overall dynamic stability. Such architecture allows to decouple the problem of dynamic stable walking in the two relatively simpler problems of gait generation and robot stabilization. This architecture is particularly suited for small size robots having limited onboard computational power and limited sensor suits. The effectiveness of the proposed method has been validated through Matlab R simulations and experimental tests performed on a Robovie-MS platform. Copyright c IFAC Keywords: control architecture, dynamically stable gait, foot rotation indicator, support polygon.. INTRODUCTION Humanoid robots are enjoying increasing popularity as their anthropomorphic body allows the investigation of human-like motion and multimodal communication. Currently, examples of advanced humanoid robots include Asimo (Honda, Inc) or Qrio (Sony, Global), whereas simpler designs include Vstone (Vstone, Co. Ltd), Kondo (Kagaku, Co. Ltd) or RoboSapien (Wowwee, Robosapien), which has been developed for the toy market. Small humanoid robots can have from a few to Corresponding author over twenty actuated degrees of freedom and generally they carry some microcontroller electronics board for the low level control, i.e. to generate target signals for the actuators. Higher level control loops need by far more computational power and are usually implemented either on industrial controllers as, by example, PC or on handheld computers (Behnke et al., July a)(behnke et al., May b), such as Pocket PC and alike. The communication link between low and higher level control loops is most often of serial RS kind. The actuators are usually low power servo motors from the radio control (RC) models market.

2 Fig.. Robovie-MS Biped locomotion is one of the most important issues to be faced: the basic characteristics of all biped locomotion systems are (Vukobratović and Borovac, ): () the possibility of rotation of the overall system about one of the feet edges caused by strong disturbances; () gait repeatability; () regular interchangeability of single and double support phases. In this paper, we propose a control architecture for the motion control of a humanoid robot that allows to decouple the gait generation issue and the overall dynamic stability of the system. The analysis of dynamic stability is addressed on the basis of the Foot Rotation Indicator (FRI) (Goswami, 999). The remainder of the paper is organized as follows: the used robot is described in the section, the proposed architecture in section. Implementation issue are discussed in section. Simulation and experimental results are presented in section and, finally, conclusions are briefly discussed in section.. ROBOT DESCRIPTION The considered robot, shown in figure, is the Robovie-MS, a small humanoid robot kit made by Vstone (Vstone, Co. Ltd). The robot has 7 degrees of freedom (DOFs): in each leg, in each arm and one in the head. It is 8 cm tall and has a total weight of about 8g. It has one axis acceleration sensor and 7 joint angle sensors. The servos control board is composed by an H8 CPU at MHz, a KByte FLASH- ROM memory, a KByte RAM and a 8KByte External-EEPROM.. CONTROL ARCHITECTURE In this section we present the control architecture proposed to obtain a dynamically stable gait for the biped robot. The issue of planning desired Fig.. Definition of the support polygon (single (a) and double (b) support phases) joint trajectories for dynamic walking is an important research area: several methods have been presented in the literature. Some of these are based on the inverted pendulum model for the biped legs (Tsuji and Ohnishi, ), (Goswami et al., 997). Other more complicated techniques take directly into account dynamic stability indicators as the zero moment point (ZMP) (Zhou et al., ) or the foot rotation indicator (FRI) (Hoffman et al., ). We consider a control architecture based on the FRI (Foot rotation Indicator) (Goswami, 999), which is a point on the foot/ground contact surface where the net ground reaction force would have to act to keep the foot stationary. To ensure the absence of foot rotations around any axis laying in the ground plane, the FRI point must remain within the convex hull of the foot support area. The proposed control architecture is shown in figure. The basic idea, is that the leg joints only are considered for locomotion planning while the upper body and arm joints are used for dynamic stabilization. The aim is to design an architecture that allows to decouple the gait generation and dynamic stabilization problems. In essence, this architecture is inspired by classical task based control architectures (Sciavicco and Siciliano, ) of industrial robots that allow to design separate control laws for concurrent, but different tasks. As for the gait generation, basically this will be commanded to the leg joints based on an off line (or loose feedback) planning phase. Any of the standard gait planning approaches described in the literature may be considered, eventually including obstacle avoidance tasks as suggested in figure. With reference to figure, the gait generator is a planner for the leg joints only generating either leg joint torques (in case of a dynamic planner) or leg joint reference velocities (in case of a kinematics planner). In either case the gait generator output is used to define the leg joint commands. As pictorially represented in figure, such planner may use joint information to perform obstacle avoidance planning or re-planning. As for the

3 Fig.. Control architecture. dynamic stability control, the direct kinematics model will be used to compute the velocity and position of the center of the support polygon as a function of the joint values. The support polygon can be defined as the contact area between the humanoid robot and the ground; therefore in the single support phase, it is given by the sole in contact with the ground (seen figure (a)), while in the double support phase, it is given by the convex hull of contact points between the soles and the ground (seen figure (b)). The dynamic stabilization controller will have as input the vector difference of the position of a target point inside the support polygon with the position of the FRI, and its aim will be to drive this error to zero by acting on the upper body degrees of freedom. Indeed if FRI is in the support polygon, we are sure that the robot s motion is dynamically stable. It should be noticed that according to its definition (Goswami, 999), the FRI tends to the ground projection of the center of mass (GCoM, in the sequel) as the joint accelerations tend to zero. Namely indicating with r F RI and r GCoM the position of the FRI and of the ground projection of the center of mass respectively, the following holds: δ := r F RI r GCoM = lim a i, ω i δ = () being a i and ω i the linear and angular accelerations of each link. Notice that δ is a continuous function of the link accelerations and that if a j < g j, then δ is upper bounded. Decoupling the gait planning and dynamic stabilization tasks is particularly important for small size robots that have limited computational power. In order for such decoupling to be effective, the cycle time of the dynamic stabilization controller needs to suitably smaller than the gait period. Moreover the legs contribution to the FRI position will be regarded as a disturbance (namely a non manipulable input) by the upper body controller. Notice that this task division approach can be compared to (Khatib et al., ) with the difference that in (Khatib et al., ) the task division is implemented at an algorithmic level, while in the present case at a control architecture level.. IMPLEMENTATION ISSUES The dynamic stabilization feedback control loop described in section and in figure can be designed based upon a Lyapunov technique. Wanting the FRI point to converge on a target point r t within the support polygon, a quadratic Lyapunov candidate function may be defined as: V = (r t r F RI ) T R (r t r F RI ) () where R will be a symmetric positive defined matrix, and r F RI and r t are the positions of the FRI and of a target point inside the support polygon respectively. The time derivative of V will be given by: V = (ṙ t ṙ F RI ) T R (r t r F RI ) = () ( = ṙ GCoM ṙ t + δ ) T ( ) R r t r GCoM δ being δ defined in equation (). Calling q L, q UB the legs and upper body joint variables and J L (q), J UB (q) the legs and upper body Jacobian matrices such that ṙ GCoM = J L (q) q L + J UB (q) q UB, () equation () suggests to compute the reference value of the upper joint velocities as [ ] q UBd = J UB R (r t r GCoM ) J L q L + ṙ t () being J UB the Moore Penrose pseudo inverse of matrix J UB. Notice that the use of the ground

4 projection of the center of mass in place of the FRI in the control law makes V equal to V = (r t r GCoM ) R T R (r t r GCoM ) + + δ R δ ( δt δ T R T ) R (r t r GCoM ) that is negative definite only in the limit of vanishing δ and δ. Nevertheless the use of r GCoM in place of r F RI makes the control law computationally much simpler as according to the FRI definition (Goswami, 999), ṙ F RI will depend on the joint accelerations and jerks. As for the q L, q L and ṙ t in the upper body joint control law (), notice that q L and q L are known as they are generated by the legs gait controller and ṙ t is generated in such a way that r t is always within the support polygon. Generally ṙ t is designed such that during the single support phase r t moves within the support polygon in the same direction of the walking gait so that at the end of the single support phase, when the support polygon becomes the one of the double support phase, r t will be located approximately in its center. Considering only the sagittal plane, for the sake of simplicity, the robot model is represented in fig.. In this case the Jacobian matrices are : J L (q) = k s k s k s k s k c k c k c k c M and J UB (q) = = M k s k s k s k 7 s 7 k c + k c k c k 7 c 7 where M( is the total mass of the robot and k r m + m + m + m + m + m + ) ( m 7, k r m + m ) + m + m + m + m 7, ( k r m + m ) ( + m 7, k r m + m ), m k r, k m r, k m 7 r 7 7 and m i and r i are respectively the mass and the length of the i-th link as reported in Table.. SIMULATION AND EXPERIMENTAL RESULTS The presented control approach has been validated in the sagittal plane both in simulation and experimentally. The simulations have been performed in Matlab using the Robotics Toolbox realized by P. I. Corke (Corke, 99). The experimental implementation has been realized using The notations s i...j, c i...j represent, respectively, sin(q i q j ), cos(q i q j ) Fig.. Robot model in sagittal plane the Robovie-MS platform. In figure simulation results are displayed relative to a case where the robot executes a complete step in the positive x axis direction. Initially the two feet have a common x coordinate and the target point r t is at the center of the (initial) double support phase support polygon. While one of the two feet stays on the ground, the other one moves forward giving rise to the single support phase. During this phase, the target point velocity ṙ t is constant along the positive x axis direction until r t reaches the border of the single support phase support polygon where ṙ t is set to zero. As expected, figure () shows that the error r t r GCoM is driven to zero by the action of the upper body joints (torso and arms). The parameters used for simulations are reported in Table. N Link Length (cm) Mass (g) 9,,88,9 7,88 9,,. 7,. Table. Robovie-MS parameters used for the simulations. Experimental results relative to the implementation of the proposed control law for the sagittal plane of the Robovie-MS platform are reported in figure (). Notice that, during the experimental validation tests, the robot needs to perform a dorsal plane movement (figure () (d)) to prevent the GCoM point from falling out of the single support phase support polygon in the z direction. Such dorsal plane motion is commanded in open loop. Moreover, as the joints are actuated by position servo motors, the control law () has been integrated in order to compute position commands for the upper body joints. Given the limited communication bandwidth with the joint position servo controllers, during the experimental tests the position commands (labeled as viapoints in figure ()) were updated at very low frequency (approximately Hz). Nevertheless, as shown in

5 figure (), the sagittal plane component of the GCoM point converges to its target value. In particular, the experimental results reported in figure () refer to a situation where the robot starts from a double support phase: the right foot is moved upwards giving rise to a single support (on the left foot) phase during which the left knee is bend contributing to move the GCoM in the negative x direction. Such destabilizing x axis motion of the GCoM is automatically compensated for, in the sagittal plane, by the upper body joints controlled by the proposed law. Overall, the x coordinate of the GCoM converges to its constant target position approximately located at the center of the support polygon.. CONCLUSION A humanoid robot control architecture has been presented that allows to decouple the gait generation issue from the dynamic stabilization one. To the best of the author s knowledge, this approach appears to be novel. The proposed solution is particularly suited for small size, low cost humanoid systems having limited computational power. Although due to HW constraints the experimental validation was possible only at rather low control update frequencies (approximately Hz), extensive trials have shown that leg motions that would have caused the robot to fall in case the upper body joints were kept still did not cause the robot to fall when the upper body joints were controlled according to the presented strategy. Simulations performed at higher update frequencies and higher link velocities confirm the effectiveness of the presented solution. Several open issues need to be addressed in future work. These include handling of: (i) dynamic effects by estimating δ := r F RI r GCoM and its time derivative, (ii) possible link collisions and (iii) jacobian singularities. A possible strategy to handle link collisions and jacobian singularities is to replace the pseudo-inverse of J UB in equation () with a weighted pseudo-inverse such as ( ) W JUB T JUB W JUB T for some symmetric positive definite W of proper dimension. The extra degrees of freedom provided by W can be used to try avoiding collisions and kinematics singularities. st International Conference on Dextrous Autonomous Robots and Humanoids (darh) Yverdon-les-Bains - Switzerland. May. Corke, P.I. (99). A robotics toolbox for MAT- LAB. IEEE Robotics and Automation Magazine (),. Goswami, A. (999). Postural stability of biped robots and the foot-rotation indicator (fri) point. The International Journal of Robotic Research Vol. 8, No.,. Goswami, A., B. Espiau and A. Keramane (997). Limit cycles in a passive compass gait biped and passivity-mimicking control laws. Autonomous Robots, 7 8. Hoffman, A., M. Popovic, S. Massaquoi and H. Herr (). A sliding controller for bipedal balancing using integrated movement of contact and non-contact limbs. in Proceedings of the IEEE/RSJ International Conference on Intelligent Robots and System, (Sendal, Japan). Honda (Inc). Kagaku (Co. Ltd). Khatib, O., L. Sentis, J. Park and J. Warren (). Whole-body dynamic behavior and control of human-like robots. International Journal of Humanoid Robotics Vol., No., 9. Sciavicco, L. and B. Siciliano (). Modelling and Control of Robot Manipulators. Springer. Berlin. Sony (Global). Tsuji, T. and K. Ohnishi (). A control of biped robot which applies inverted pendolum mode with virtual supporting point. AMC, Maribor, Slovenia. Vstone (Co. Ltd). Vukobratović, M. and B. Borovac (). Zeromoment point - thirty five years of its life. International Journal of Humanoid Robotics Vol., No., 7 7. Wowwee (Robosapien). Zhou, C., P. K. Yue, J. Ni and S. B. Chan (). Dynamically stable gait planning for a humanoid robot to climb sloping surface. Proceedings of the IEEE Conference on Robotics, Automation and Mechatronics, Singapore. REFERENCES Behnke, S., J. Muller and M. Schreiber (July a). Playing soccer with robosapien. In: In Proceedings of The 9th RoboCup International Symposium, Osaka, Japan. July. Behnke, S., J. Muller and M. Schreiber (May b). Using handheld computers to control humanoid robots. In: In Proceedings of

6 . Upper body joints (deg) x coordinate of GCoM (cm)... θ θ θ7. x coordinate of Ground projection of Center of Mass Pos. target point. time (sec) (a) 8 7 time (sec) (b) 7 y (cm) Upper body joint velocities (deg/s) dθ/dt dθ/dt dθ7/dt time (sec) (c) 7 x (cm) (d) Fig.. Simulation : (a) position of the x coordinate of GCoM (solid line) and position of target point (dashed line); (b) θ, θ and θ7 position, (c) θ, θ and θ7 velocity, (d) stick diagram of start (solid line), middle (dashed line) and final (dotted line) configuration and position of the center of the support polygon ( ) and the position of the center of mass ( ) Fig.. Experimental results : (a) position of the x coordinate of GCoM (*) and position of target point (dashed line); (b) Robovie-MS initial position, (c) Robovie-MS middle position, (d) Robovie-MS final position

Upper Body Joints Control for the Quasi static Stabilization of a Small-Size Humanoid Robot

Upper Body Joints Control for the Quasi static Stabilization of a Small-Size Humanoid Robot Upper Body Joints Control for the Quasi static Stabilization of a Small-Size Humanoid Robot Andrea Manni, Angelo di Noi and Giovanni Indiveri Dipartimento Ingegneria dell Innovazione, Università di Lecce

More information

Autonomous and Mobile Robotics Prof. Giuseppe Oriolo. Humanoid Robots 2: Dynamic Modeling

Autonomous and Mobile Robotics Prof. Giuseppe Oriolo. Humanoid Robots 2: Dynamic Modeling Autonomous and Mobile Robotics rof. Giuseppe Oriolo Humanoid Robots 2: Dynamic Modeling modeling multi-body free floating complete model m j I j R j ω j f c j O z y x p ZM conceptual models for walking/balancing

More information

A NOUVELLE MOTION STATE-FEEDBACK CONTROL SCHEME FOR RIGID ROBOTIC MANIPULATORS

A NOUVELLE MOTION STATE-FEEDBACK CONTROL SCHEME FOR RIGID ROBOTIC MANIPULATORS A NOUVELLE MOTION STATE-FEEDBACK CONTROL SCHEME FOR RIGID ROBOTIC MANIPULATORS Ahmad Manasra, 135037@ppu.edu.ps Department of Mechanical Engineering, Palestine Polytechnic University, Hebron, Palestine

More information

Robust Control of Bipedal Humanoid (TPinokio)

Robust Control of Bipedal Humanoid (TPinokio) Available online at www.sciencedirect.com Procedia Engineering 41 (2012 ) 643 649 International Symposium on Robotics and Intelligent Sensors 2012 (IRIS 2012) Robust Control of Bipedal Humanoid (TPinokio)

More information

A sliding walk method for humanoid robots using ZMP feedback control

A sliding walk method for humanoid robots using ZMP feedback control A sliding walk method for humanoid robots using MP feedback control Satoki Tsuichihara, Masanao Koeda, Seiji Sugiyama, and Tsuneo oshikawa Abstract In this paper, we propose two methods for a highly stable

More information

Adaptive Motion Control: Dynamic Kick for a Humanoid Robot

Adaptive Motion Control: Dynamic Kick for a Humanoid Robot Adaptive Motion Control: Dynamic Kick for a Humanoid Robot Yuan Xu and Heinrich Mellmann Institut für Informatik, LFG Künstliche Intelligenz Humboldt-Universität zu Berlin, Germany {xu,mellmann}@informatik.hu-berlin.de

More information

Simplified Walking: A New Way to Generate Flexible Biped Patterns

Simplified Walking: A New Way to Generate Flexible Biped Patterns 1 Simplified Walking: A New Way to Generate Flexible Biped Patterns Jinsu Liu 1, Xiaoping Chen 1 and Manuela Veloso 2 1 Computer Science Department, University of Science and Technology of China, Hefei,

More information

Mobile Robots Locomotion

Mobile Robots Locomotion Mobile Robots Locomotion Institute for Software Technology 1 Course Outline 1. Introduction to Mobile Robots 2. Locomotion 3. Sensors 4. Localization 5. Environment Modelling 6. Reactive Navigation 2 Today

More information

Modeling of Humanoid Systems Using Deductive Approach

Modeling of Humanoid Systems Using Deductive Approach INFOTEH-JAHORINA Vol. 12, March 2013. Modeling of Humanoid Systems Using Deductive Approach Miloš D Jovanović Robotics laboratory Mihailo Pupin Institute Belgrade, Serbia milos.jovanovic@pupin.rs Veljko

More information

Design and Optimization of the Thigh for an Exoskeleton based on Parallel Mechanism

Design and Optimization of the Thigh for an Exoskeleton based on Parallel Mechanism Design and Optimization of the Thigh for an Exoskeleton based on Parallel Mechanism Konstantin Kondak, Bhaskar Dasgupta, Günter Hommel Technische Universität Berlin, Institut für Technische Informatik

More information

Mobile Robotics. Marcello Restelli. Dipartimento di Elettronica e Informazione Politecnico di Milano tel:

Mobile Robotics. Marcello Restelli. Dipartimento di Elettronica e Informazione Politecnico di Milano   tel: Marcello Restelli Dipartimento di Elettronica e Informazione Politecnico di Milano email: restelli@elet.polimi.it tel: 02-2399-3470 Mobile Robotics Robotica for Computer Engineering students A.A. 2006/2007

More information

EXPLOITING MOTION SYMMETRY IN CONTROL OF EXOSKELETON LIMBS

EXPLOITING MOTION SYMMETRY IN CONTROL OF EXOSKELETON LIMBS EXPLOITING MOTION SYMMETRY IN CONTROL OF EXOSKELETON LIMBS Christian Reinicke Institut für Technische Informatik und Mikroelektronik, Technische Universität Berlin Berlin, Germany email: reinicke@cs.tu-berlin.de

More information

A Cost Oriented Humanoid Robot Motion Control System

A Cost Oriented Humanoid Robot Motion Control System Preprints of the 19th World Congress The International Federation of Automatic Control A Cost Oriented Humanoid Robot Motion Control System J. Baltes*, P. Kopacek**,M. Schörghuber** *Department of Computer

More information

Self-Collision Detection and Prevention for Humanoid Robots. Talk Overview

Self-Collision Detection and Prevention for Humanoid Robots. Talk Overview Self-Collision Detection and Prevention for Humanoid Robots James Kuffner, Jr. Carnegie Mellon University Koichi Nishiwaki The University of Tokyo Satoshi Kagami Digital Human Lab (AIST) Masayuki Inaba

More information

Fuzzy Control for Bipedal Robot Considering Energy Balance

Fuzzy Control for Bipedal Robot Considering Energy Balance Contemporary Engineering Sciences, Vol., 28, no. 39, 945-952 HIKARI Ltd, www.m-hikari.com https://doi.org/.2988/ces.28.837 Fuzzy Control for Bipedal Robot Considering Energy Balance Jhonattan Gordillo

More information

Inverse Kinematics for Humanoid Robots using Artificial Neural Networks

Inverse Kinematics for Humanoid Robots using Artificial Neural Networks Inverse Kinematics for Humanoid Robots using Artificial Neural Networks Javier de Lope, Rafaela González-Careaga, Telmo Zarraonandia, and Darío Maravall Department of Artificial Intelligence Faculty of

More information

Humanoid Robotics. Path Planning and Walking. Maren Bennewitz

Humanoid Robotics. Path Planning and Walking. Maren Bennewitz Humanoid Robotics Path Planning and Walking Maren Bennewitz 1 Introduction Given the robot s pose in a model of the environment Compute a path to a target location First: 2D path in a 2D grid map representation

More information

Modeling and kinematics simulation of freestyle skiing robot

Modeling and kinematics simulation of freestyle skiing robot Acta Technica 62 No. 3A/2017, 321 334 c 2017 Institute of Thermomechanics CAS, v.v.i. Modeling and kinematics simulation of freestyle skiing robot Xiaohua Wu 1,3, Jian Yi 2 Abstract. Freestyle skiing robot

More information

1724. Mobile manipulators collision-free trajectory planning with regard to end-effector vibrations elimination

1724. Mobile manipulators collision-free trajectory planning with regard to end-effector vibrations elimination 1724. Mobile manipulators collision-free trajectory planning with regard to end-effector vibrations elimination Iwona Pajak 1, Grzegorz Pajak 2 University of Zielona Gora, Faculty of Mechanical Engineering,

More information

Inverse Kinematics for Humanoid Robots Using Artificial Neural Networks

Inverse Kinematics for Humanoid Robots Using Artificial Neural Networks Inverse Kinematics for Humanoid Robots Using Artificial Neural Networks Javier de Lope, Rafaela González-Careaga, Telmo Zarraonandia, and Darío Maravall Department of Artificial Intelligence Faculty of

More information

Serially-Linked Parallel Leg Design for Biped Robots

Serially-Linked Parallel Leg Design for Biped Robots December 13-15, 24 Palmerston North, New ealand Serially-Linked Parallel Leg Design for Biped Robots hung Kwon, Jung H. oon, Je S. eon, and Jong H. Park Dept. of Precision Mechanical Engineering, School

More information

Dynamically Balanced Omnidirectional Humanoid Robot Locomotion. An Honors Paper for the Department of Computer Science. By Johannes Heide Strom

Dynamically Balanced Omnidirectional Humanoid Robot Locomotion. An Honors Paper for the Department of Computer Science. By Johannes Heide Strom Dynamically Balanced Omnidirectional Humanoid Robot Locomotion An Honors Paper for the Department of Computer Science By Johannes Heide Strom Bowdoin College, 2009 c 2009 Johannes Heide Strom Contents

More information

Controlling Humanoid Robots with Human Motion Data: Experimental Validation

Controlling Humanoid Robots with Human Motion Data: Experimental Validation 21 IEEE-RAS International Conference on Humanoid Robots Nashville, TN, USA, December 6-8, 21 Controlling Humanoid Robots with Human Motion Data: Experimental Validation Katsu Yamane, Stuart O. Anderson,

More information

1498. End-effector vibrations reduction in trajectory tracking for mobile manipulator

1498. End-effector vibrations reduction in trajectory tracking for mobile manipulator 1498. End-effector vibrations reduction in trajectory tracking for mobile manipulator G. Pajak University of Zielona Gora, Faculty of Mechanical Engineering, Zielona Góra, Poland E-mail: g.pajak@iizp.uz.zgora.pl

More information

Modeling the manipulator and flipper pose effects on tip over stability of a tracked mobile manipulator

Modeling the manipulator and flipper pose effects on tip over stability of a tracked mobile manipulator Modeling the manipulator and flipper pose effects on tip over stability of a tracked mobile manipulator Chioniso Dube Mobile Intelligent Autonomous Systems Council for Scientific and Industrial Research,

More information

SYNTHESIS AND RAPID PROTOTYPING OF MOTION FOR A FOUR-LEGGED MAMMAL-STRUCTURED ROBOT

SYNTHESIS AND RAPID PROTOTYPING OF MOTION FOR A FOUR-LEGGED MAMMAL-STRUCTURED ROBOT SYNTHESIS AND RAPID PROTOTYPING OF MOTION FOR A FOUR-LEGGED MAMMAL-STRUCTURED ROBOT Macie Tronacki* Industrial Research Institute for Automation and Measurements, Warsaw, Poland Corresponding author (mtronacki@piap.pl)

More information

Modeling Physically Simulated Characters with Motion Networks

Modeling Physically Simulated Characters with Motion Networks In Proceedings of Motion In Games (MIG), Rennes, France, 2012 Modeling Physically Simulated Characters with Motion Networks Robert Backman and Marcelo Kallmann University of California Merced Abstract.

More information

Research Subject. Dynamics Computation and Behavior Capture of Human Figures (Nakamura Group)

Research Subject. Dynamics Computation and Behavior Capture of Human Figures (Nakamura Group) Research Subject Dynamics Computation and Behavior Capture of Human Figures (Nakamura Group) (1) Goal and summary Introduction Humanoid has less actuators than its movable degrees of freedom (DOF) which

More information

Motion Planning for Dynamic Knotting of a Flexible Rope with a High-speed Robot Arm

Motion Planning for Dynamic Knotting of a Flexible Rope with a High-speed Robot Arm The 2010 IEEE/RSJ International Conference on Intelligent Robots and Systems October 18-22, 2010, Taipei, Taiwan Motion Planning for Dynamic Knotting of a Flexible Rope with a High-speed Robot Arm Yuji

More information

Dynamic Analysis of Manipulator Arm for 6-legged Robot

Dynamic Analysis of Manipulator Arm for 6-legged Robot American Journal of Mechanical Engineering, 2013, Vol. 1, No. 7, 365-369 Available online at http://pubs.sciepub.com/ajme/1/7/42 Science and Education Publishing DOI:10.12691/ajme-1-7-42 Dynamic Analysis

More information

Control of Snake Like Robot for Locomotion and Manipulation

Control of Snake Like Robot for Locomotion and Manipulation Control of Snake Like Robot for Locomotion and Manipulation MYamakita 1,, Takeshi Yamada 1 and Kenta Tanaka 1 1 Tokyo Institute of Technology, -1-1 Ohokayama, Meguro-ku, Tokyo, Japan, yamakita@ctrltitechacjp

More information

Biologically Inspired Kinematic Synergies Provide a New Paradigm for Balance Control of Humanoid Robots

Biologically Inspired Kinematic Synergies Provide a New Paradigm for Balance Control of Humanoid Robots Biologically Inspired Kinematic Synergies Provide a New Paradigm for Balance Control of Humanoid Robots Helmut Hauser #1, Gerhard Neumann #2, Auke J. Ijspeert 3, Wolfgang Maass #4 # Institute for Theoretical

More information

Mithras3D Team Description Paper 2014 Soccer Simulation 3D League

Mithras3D Team Description Paper 2014 Soccer Simulation 3D League Mithras3D Team Description Paper 2014 Soccer Simulation 3D League Armita Sabeti Ashraf, Atieh Alsadat Moosavian, Fatemeh Gerami Gohar, Fatima Tafazzoli Shadpour, Romina Moradi, Sama Moayeri Farzanegan

More information

Manipulator trajectory planning

Manipulator trajectory planning Manipulator trajectory planning Václav Hlaváč Czech Technical University in Prague Faculty of Electrical Engineering Department of Cybernetics Czech Republic http://cmp.felk.cvut.cz/~hlavac Courtesy to

More information

A Model-Based Control Approach for Locomotion Control of Legged Robots

A Model-Based Control Approach for Locomotion Control of Legged Robots Biorobotics Laboratory A Model-Based Control Approach for Locomotion Control of Legged Robots Semester project Master Program: Robotics and Autonomous Systems Micro-Technique Department Student: Salman

More information

Development of an optomechanical measurement system for dynamic stability analysis

Development of an optomechanical measurement system for dynamic stability analysis Development of an optomechanical measurement system for dynamic stability analysis Simone Pasinetti Dept. of Information Engineering (DII) University of Brescia Brescia, Italy simone.pasinetti@unibs.it

More information

CS 231. Control for articulate rigid-body dynamic simulation. Articulated rigid-body dynamics

CS 231. Control for articulate rigid-body dynamic simulation. Articulated rigid-body dynamics CS 231 Control for articulate rigid-body dynamic simulation Articulated rigid-body dynamics F = ma No control 1 No control Ragdoll effects, joint limits RT Speed: many sims at real-time rates on today

More information

Simulation. x i. x i+1. degrees of freedom equations of motion. Newtonian laws gravity. ground contact forces

Simulation. x i. x i+1. degrees of freedom equations of motion. Newtonian laws gravity. ground contact forces Dynamic Controllers Simulation x i Newtonian laws gravity ground contact forces x i+1. x degrees of freedom equations of motion Simulation + Control x i Newtonian laws gravity ground contact forces internal

More information

Evolutionary approach for developing fast and stable offline humanoid walk

Evolutionary approach for developing fast and stable offline humanoid walk Evolutionary approach for developing fast and stable offline humanoid walk Hafez Farazi #*1, Farzad Ahmadinejad *2, Farhad Maleki #3, M.E Shiri #4 # Mathematics and Computer Science Department, Amirkabir

More information

Robots are built to accomplish complex and difficult tasks that require highly non-linear motions.

Robots are built to accomplish complex and difficult tasks that require highly non-linear motions. Path and Trajectory specification Robots are built to accomplish complex and difficult tasks that require highly non-linear motions. Specifying the desired motion to achieve a specified goal is often a

More information

Motion Planning of Emergency Stop for Humanoid Robot by State Space Approach

Motion Planning of Emergency Stop for Humanoid Robot by State Space Approach Motion Planning of Emergency Stop for Humanoid Robot by State Space Approach Mitsuharu Morisawa, Kenji Kaneko, Fumio Kanehiro, Shuuji Kajita, Kiyoshi Fujiwara, Kensuke Harada, Hirohisa Hirukawa National

More information

10/25/2018. Robotics and automation. Dr. Ibrahim Al-Naimi. Chapter two. Introduction To Robot Manipulators

10/25/2018. Robotics and automation. Dr. Ibrahim Al-Naimi. Chapter two. Introduction To Robot Manipulators Robotics and automation Dr. Ibrahim Al-Naimi Chapter two Introduction To Robot Manipulators 1 Robotic Industrial Manipulators A robot manipulator is an electronically controlled mechanism, consisting of

More information

ÉCOLE POLYTECHNIQUE DE MONTRÉAL

ÉCOLE POLYTECHNIQUE DE MONTRÉAL ÉCOLE POLYTECHNIQUE DE MONTRÉAL MODELIZATION OF A 3-PSP 3-DOF PARALLEL MANIPULATOR USED AS FLIGHT SIMULATOR MOVING SEAT. MASTER IN ENGINEERING PROJET III MEC693 SUBMITTED TO: Luc Baron Ph.D. Mechanical

More information

Key-Words: - seven-link human biped model, Lagrange s Equation, computed torque control

Key-Words: - seven-link human biped model, Lagrange s Equation, computed torque control Motion Control of Human Bipedal Model in Sagittal Plane NURFARAHIN ONN, MOHAMED HUSSEIN, COLLIN HOWE HING TANG, MOHD ZARHAMDY MD ZAIN, MAZIAH MOHAMAD and WEI YING LAI Faculty of Mechanical Engineering

More information

Open Access The Kinematics Analysis and Configuration Optimize of Quadruped Robot. Jinrong Zhang *, Chenxi Wang and Jianhua Zhang

Open Access The Kinematics Analysis and Configuration Optimize of Quadruped Robot. Jinrong Zhang *, Chenxi Wang and Jianhua Zhang Send Orders for Reprints to reprints@benthamscience.ae The Open Automation and Control Systems Journal, 014, 6, 1685-1690 1685 Open Access The Kinematics Analysis and Configuration Optimize of Quadruped

More information

Control of Walking Robot by Inverse Dynamics of Link Mechanisms Using FEM

Control of Walking Robot by Inverse Dynamics of Link Mechanisms Using FEM Copyright c 2007 ICCES ICCES, vol.2, no.4, pp.131-136, 2007 Control of Walking Robot by Inverse Dynamics of Link Mechanisms Using FEM S. Okamoto 1 and H. Noguchi 2 Summary This paper presents a control

More information

Smooth Transition Between Tasks on a Kinematic Control Level: Application to Self Collision Avoidance for Two Kuka LWR Robots

Smooth Transition Between Tasks on a Kinematic Control Level: Application to Self Collision Avoidance for Two Kuka LWR Robots Smooth Transition Between Tasks on a Kinematic Control Level: Application to Self Collision Avoidance for Two Kuka LWR Robots Tadej Petrič and Leon Žlajpah Abstract A common approach for kinematically

More information

Humanoid Robotics Modeling by Dynamic Fuzzy Neural Network

Humanoid Robotics Modeling by Dynamic Fuzzy Neural Network Proceedings of International Joint Conference on Neural Networks, Orlando, Florida, USA, August 1-17, 7 umanoid Robotics Modeling by Dynamic Fuzzy Neural Network Zhe Tang, Meng Joo Er, and Geok See Ng

More information

STUDY OF ZMP MEASUREMENT FOR BIPEDROBOT USING FSR SENSOR

STUDY OF ZMP MEASUREMENT FOR BIPEDROBOT USING FSR SENSOR STUDY OF ZMP MEASUREMENT FOR BIPEDROBOT USING FSR SENSOR Bong Gyou Shim, *Eung Hyuk Lee, **Hong Ki Min, Seung Hong Hong Department of Electronic Engineering, Inha University *Department of Electronic Engineering,

More information

Using the Generalized Inverted Pendulum to generate less energy-consuming trajectories for humanoid walking

Using the Generalized Inverted Pendulum to generate less energy-consuming trajectories for humanoid walking Using the Generalized Inverted Pendulum to generate less energy-consuming trajectories for humanoid walking Sahab Omran, Sophie Sakka, Yannick Aoustin To cite this version: Sahab Omran, Sophie Sakka, Yannick

More information

Biologically inspired kinematic synergies enable linear balance control of a humanoid robot

Biologically inspired kinematic synergies enable linear balance control of a humanoid robot Biol Cybern (211) 14:235 249 DOI 1.17/s422-11-43-1 ORIGINAL PAPER Biologically inspired kinematic synergies enable linear balance control of a humanoid robot Helmut Hauser Gerhard Neumann Auke J. Ijspeert

More information

Task selection for control of active vision systems

Task selection for control of active vision systems The 29 IEEE/RSJ International Conference on Intelligent Robots and Systems October -5, 29 St. Louis, USA Task selection for control of active vision systems Yasushi Iwatani Abstract This paper discusses

More information

CMPUT 412 Motion Control Wheeled robots. Csaba Szepesvári University of Alberta

CMPUT 412 Motion Control Wheeled robots. Csaba Szepesvári University of Alberta CMPUT 412 Motion Control Wheeled robots Csaba Szepesvári University of Alberta 1 Motion Control (wheeled robots) Requirements Kinematic/dynamic model of the robot Model of the interaction between the wheel

More information

Using Artificial Neural Networks for Prediction Of Dynamic Human Motion

Using Artificial Neural Networks for Prediction Of Dynamic Human Motion ABSTRACT Using Artificial Neural Networks for Prediction Of Dynamic Human Motion Researchers in robotics and other human-related fields have been studying human motion behaviors to understand and mimic

More information

Control Approaches for Walking and Running

Control Approaches for Walking and Running DLR.de Chart 1 > Humanoids 2015 > Christian Ott > 02.11.2015 Control Approaches for Walking and Running Christian Ott, Johannes Englsberger German Aerospace Center (DLR) DLR.de Chart 2 > Humanoids 2015

More information

Parallel Robots. Mechanics and Control H AMID D. TAG HI RAD. CRC Press. Taylor & Francis Group. Taylor & Francis Croup, Boca Raton London NewYoric

Parallel Robots. Mechanics and Control H AMID D. TAG HI RAD. CRC Press. Taylor & Francis Group. Taylor & Francis Croup, Boca Raton London NewYoric Parallel Robots Mechanics and Control H AMID D TAG HI RAD CRC Press Taylor & Francis Group Boca Raton London NewYoric CRC Press Is an Imprint of the Taylor & Francis Croup, an informs business Contents

More information

An Interactive Software Environment for Gait Generation and Control Design of Sony Legged Robots

An Interactive Software Environment for Gait Generation and Control Design of Sony Legged Robots An Interactive Software Environment for Gait Generation and Control Design of Sony Legged Robots Dragos Golubovic and Huosheng Hu Department of Computer Science, University of Essex, Colchester CO4 3SQ,

More information

David Galdeano. LIRMM-UM2, Montpellier, France. Members of CST: Philippe Fraisse, Ahmed Chemori, Sébatien Krut and André Crosnier

David Galdeano. LIRMM-UM2, Montpellier, France. Members of CST: Philippe Fraisse, Ahmed Chemori, Sébatien Krut and André Crosnier David Galdeano LIRMM-UM2, Montpellier, France Members of CST: Philippe Fraisse, Ahmed Chemori, Sébatien Krut and André Crosnier Montpellier, Thursday September 27, 2012 Outline of the presentation Context

More information

Research on time optimal trajectory planning of 7-DOF manipulator based on genetic algorithm

Research on time optimal trajectory planning of 7-DOF manipulator based on genetic algorithm Acta Technica 61, No. 4A/2016, 189 200 c 2017 Institute of Thermomechanics CAS, v.v.i. Research on time optimal trajectory planning of 7-DOF manipulator based on genetic algorithm Jianrong Bu 1, Junyan

More information

Kinematics and dynamics analysis of micro-robot for surgical applications

Kinematics and dynamics analysis of micro-robot for surgical applications ISSN 1 746-7233, England, UK World Journal of Modelling and Simulation Vol. 5 (2009) No. 1, pp. 22-29 Kinematics and dynamics analysis of micro-robot for surgical applications Khaled Tawfik 1, Atef A.

More information

Motion Planning for Whole Body Tasks by Humanoid Robots

Motion Planning for Whole Body Tasks by Humanoid Robots Proceedings of the IEEE International Conference on Mechatronics & Automation Niagara Falls, Canada July 5 Motion Planning for Whole Body Tasks by Humanoid Robots Eiichi Yoshida 1, Yisheng Guan 1, Neo

More information

Written exams of Robotics 2

Written exams of Robotics 2 Written exams of Robotics 2 http://www.diag.uniroma1.it/~deluca/rob2_en.html All materials are in English, unless indicated (oldies are in Year Date (mm.dd) Number of exercises Topics 2018 07.11 4 Inertia

More information

Torque-Position Transformer for Task Control of Position Controlled Robots

Torque-Position Transformer for Task Control of Position Controlled Robots 28 IEEE International Conference on Robotics and Automation Pasadena, CA, USA, May 19-23, 28 Torque-Position Transformer for Task Control of Position Controlled Robots Oussama Khatib, 1 Peter Thaulad,

More information

Generating Whole Body Motions for a Biped Humanoid Robot from Captured Human Dances

Generating Whole Body Motions for a Biped Humanoid Robot from Captured Human Dances Generating Whole Body Motions for a Biped Humanoid Robot from Captured Human Dances Shinichiro Nakaoka Atsushi Nakazawa Kazuhito Yokoi Hirohisa Hirukawa Katsushi Ikeuchi Institute of Industrial Science,

More information

MOTION TRAJECTORY PLANNING AND SIMULATION OF 6- DOF MANIPULATOR ARM ROBOT

MOTION TRAJECTORY PLANNING AND SIMULATION OF 6- DOF MANIPULATOR ARM ROBOT MOTION TRAJECTORY PLANNING AND SIMULATION OF 6- DOF MANIPULATOR ARM ROBOT Hongjun ZHU ABSTRACT:In order to better study the trajectory of robot motion, a motion trajectory planning and simulation based

More information

Automatic Control Industrial robotics

Automatic Control Industrial robotics Automatic Control Industrial robotics Prof. Luca Bascetta (luca.bascetta@polimi.it) Politecnico di Milano Dipartimento di Elettronica, Informazione e Bioingegneria Prof. Luca Bascetta Industrial robots

More information

Inverse Kinematics of Robot Manipulators with Multiple Moving Control Points

Inverse Kinematics of Robot Manipulators with Multiple Moving Control Points Inverse Kinematics of Robot Manipulators with Multiple Moving Control Points Agostino De Santis and Bruno Siciliano PRISMA Lab, Dipartimento di Informatica e Sistemistica, Università degli Studi di Napoli

More information

PPGEE Robot Dynamics I

PPGEE Robot Dynamics I PPGEE Electrical Engineering Graduate Program UFMG April 2014 1 Introduction to Robotics 2 3 4 5 What is a Robot? According to RIA Robot Institute of America A Robot is a reprogrammable multifunctional

More information

Cerebellar Augmented Joint Control for a Humanoid Robot

Cerebellar Augmented Joint Control for a Humanoid Robot Cerebellar Augmented Joint Control for a Humanoid Robot Damien Kee and Gordon Wyeth School of Information Technology and Electrical Engineering University of Queensland, Australia Abstract. The joints

More information

Experimental study of Redundant Snake Robot Based on Kinematic Model

Experimental study of Redundant Snake Robot Based on Kinematic Model 2007 IEEE International Conference on Robotics and Automation Roma, Italy, 10-14 April 2007 ThD7.5 Experimental study of Redundant Snake Robot Based on Kinematic Model Motoyasu Tanaka and Fumitoshi Matsuno

More information

10/11/07 1. Motion Control (wheeled robots) Representing Robot Position ( ) ( ) [ ] T

10/11/07 1. Motion Control (wheeled robots) Representing Robot Position ( ) ( ) [ ] T 3 3 Motion Control (wheeled robots) Introduction: Mobile Robot Kinematics Requirements for Motion Control Kinematic / dynamic model of the robot Model of the interaction between the wheel and the ground

More information

HUMANOID robots have recently attracted growing social

HUMANOID robots have recently attracted growing social IEEE TRANSACTIONS ON ROBOTICS 1 Motion Retargeting for Humanoid Robots Based on Simultaneous Morphing Parameter Identification and Motion Optimization Ko Ayusawa, Member, IEEE, and Eiichi Yoshida, Senior

More information

PSO based Adaptive Force Controller for 6 DOF Robot Manipulators

PSO based Adaptive Force Controller for 6 DOF Robot Manipulators , October 25-27, 2017, San Francisco, USA PSO based Adaptive Force Controller for 6 DOF Robot Manipulators Sutthipong Thunyajarern, Uma Seeboonruang and Somyot Kaitwanidvilai Abstract Force control in

More information

Self-Collision Detection. Planning for Humanoid Robots. Digital Human Research Center. Talk Overview

Self-Collision Detection. Planning for Humanoid Robots. Digital Human Research Center. Talk Overview Self-Collision Detection and Motion Planning for Humanoid Robots James Kuffner (CMU & AIST Japan) Digital Human Research Center Self-Collision Detection Feature-based Minimum Distance Computation: Approximate

More information

MBS MODELLING WITH SIMMECHANICS: CASE STUDIES IN RESEARCH AND EDUCATION

MBS MODELLING WITH SIMMECHANICS: CASE STUDIES IN RESEARCH AND EDUCATION MBS MODELLING WITH SIMMECHANICS: CASE STUDIES IN RESEARCH AND EDUCATION Grepl, R., Lee, B., Singule, V., Švejda, P., Vlachý, D., Zezula, P. Laboratory of mechatronics, FME, Brno University of Technology

More information

Singularity Handling on Puma in Operational Space Formulation

Singularity Handling on Puma in Operational Space Formulation Singularity Handling on Puma in Operational Space Formulation Denny Oetomo, Marcelo Ang Jr. National University of Singapore Singapore d oetomo@yahoo.com mpeangh@nus.edu.sg Ser Yong Lim Gintic Institute

More information

Nao Devils Dortmund. Team Description Paper for RoboCup Matthias Hofmann, Ingmar Schwarz, and Oliver Urbann

Nao Devils Dortmund. Team Description Paper for RoboCup Matthias Hofmann, Ingmar Schwarz, and Oliver Urbann Nao Devils Dortmund Team Description Paper for RoboCup 2017 Matthias Hofmann, Ingmar Schwarz, and Oliver Urbann Robotics Research Institute Section Information Technology TU Dortmund University 44221 Dortmund,

More information

Motion Control of Wearable Walking Support System with Accelerometer Considering Swing Phase Support

Motion Control of Wearable Walking Support System with Accelerometer Considering Swing Phase Support Proceedings of the 17th IEEE International Symposium on Robot and Human Interactive Communication, Technische Universität München, Munich, Germany, August 1-3, Motion Control of Wearable Walking Support

More information

Constrained Analytical Trajectory Filter for stabilizing humanoid robot motions

Constrained Analytical Trajectory Filter for stabilizing humanoid robot motions Intel Serv Robotics (2011) 4:203 218 DOI 10.1007/s11370-011-0094-7 ORIGINAL RESEARCH PAPER Constrained Analytical Trajectory Filter for stabilizing humanoid robot motions Karl Muecke Dennis Hong Received:

More information

Online Gain Switching Algorithm for Joint Position Control of a Hydraulic Humanoid Robot

Online Gain Switching Algorithm for Joint Position Control of a Hydraulic Humanoid Robot Online Gain Switching Algorithm for Joint Position Control of a Hydraulic Humanoid Robot Jung-Yup Kim *, Christopher G. Atkeson *, Jessica K. Hodgins *, Darrin C. Bentivegna *,** and Sung Ju Cho * * Robotics

More information

Robotics I. March 27, 2018

Robotics I. March 27, 2018 Robotics I March 27, 28 Exercise Consider the 5-dof spatial robot in Fig., having the third and fifth joints of the prismatic type while the others are revolute. z O x Figure : A 5-dof robot, with a RRPRP

More information

Using torque redundancy to optimize contact forces in legged robots

Using torque redundancy to optimize contact forces in legged robots Using torque redundancy to optimize contact forces in legged robots Ludovic Righetti, Jonas Buchli, Michael Mistry, Mrinal Kalakrishnan and Stefan Schaal Abstract The development of legged robots for complex

More information

Linear Quadratic Regulator Control of an Under Actuated Five-Degree-of-Freedom Planar Biped Walking Robot

Linear Quadratic Regulator Control of an Under Actuated Five-Degree-of-Freedom Planar Biped Walking Robot Linear Quadratic Regulator Control of an Under Actuated Five-Degree-of-Freedom Planar Biped Walking Robot A THESIS SUBMITTED TO THE FACULTY OF GRADUATE SCHOOL OF THE UNIVERSITY OF MINNESOTA BY Matthew

More information

Experimental Verification of Stability Region of Balancing a Single-wheel Robot: an Inverted Stick Model Approach

Experimental Verification of Stability Region of Balancing a Single-wheel Robot: an Inverted Stick Model Approach IECON-Yokohama November 9-, Experimental Verification of Stability Region of Balancing a Single-wheel Robot: an Inverted Stick Model Approach S. D. Lee Department of Mechatronics Engineering Chungnam National

More information

Design & Kinematic Analysis of an Articulated Robotic Manipulator

Design & Kinematic Analysis of an Articulated Robotic Manipulator Design & Kinematic Analysis of an Articulated Robotic Manipulator Elias Eliot 1, B.B.V.L. Deepak 1*, D.R. Parhi 2, and J. Srinivas 2 1 Department of Industrial Design, National Institute of Technology-Rourkela

More information

Neural Network model for a biped robot

Neural Network model for a biped robot Neural Network model for a biped robot Daniel Zaldívar 1,2, Erik Cuevas 1,2, Raúl Rojas 1. 1 Freie Universität Berlin, Institüt für Informatik, Takustr. 9, D-14195 Berlin, Germany {zaldivar, cuevas, rojas}@inf.fu-berlin.de

More information

Automatic generation of humanoid s geometric model parameters

Automatic generation of humanoid s geometric model parameters Automatic generation of humanoid s geometric model parameters Vincent Hugel and Nicolas Jouandeau LISV, University of Versailles and LIASD, University of Paris 8 Abstract. This paper describes a procedure

More information

Study on Dynamics Identification of the Foot Viscoelasticity of a Humanoid Robot

Study on Dynamics Identification of the Foot Viscoelasticity of a Humanoid Robot Preprints of the 19th World Congress The International Federation of Automatic Control Cape Town, South Africa. August 24-29, 214 Study on Dynamics Identification of the Foot Viscoelasticity of a Humanoid

More information

MCE/EEC 647/747: Robot Dynamics and Control. Lecture 1: Introduction

MCE/EEC 647/747: Robot Dynamics and Control. Lecture 1: Introduction MCE/EEC 647/747: Robot Dynamics and Control Lecture 1: Introduction Reading: SHV Chapter 1 Robotics and Automation Handbook, Chapter 1 Assigned readings from several articles. Cleveland State University

More information

Master of Science (MSc) MASTER THESIS. Concise Modeling of Humanoid Dynamics. Florian Joachimbauer. Embedded and Communication Systems, 30 credit

Master of Science (MSc) MASTER THESIS. Concise Modeling of Humanoid Dynamics. Florian Joachimbauer. Embedded and Communication Systems, 30 credit Master of Science (MSc) MASTER THESIS Concise Modeling of Humanoid Dynamics Florian Joachimbauer Embedded and Communication Systems, 30 credit Halmstad University, June 26, 2017 Florian Joachimbauer: Concise

More information

Towards a multi-segment ambulatory microrobot

Towards a multi-segment ambulatory microrobot 2 IEEE International Conference on Robotics and Automation Anchorage Convention District May 3-8, 2, Anchorage, Alaska, USA Towards a multi-segment ambulatory microrobot Katie L. Hoffman and Robert J.

More information

Balanced Walking with Capture Steps

Balanced Walking with Capture Steps Balanced Walking with Capture Steps Marcell Missura and Sven Behnke Autonomous Intelligent Systems, Computer Science, Univ. of Bonn, Germany {missura,behnke}@cs.uni-bonn.de http://ais.uni-bonn.de Abstract.

More information

Motion Simulation of a Modular Robotic System

Motion Simulation of a Modular Robotic System Motion Simulation of a Modular Robotic System Haruhisa KUROKAWA, Kohji TOMITA, Eiichi YOSHIDA, Satoshi MURATA and Shigeru KOKAJI Mechanical Engineering Laboratory, AIST, MITI Namiki 1-2, Tsukuba, Ibaraki

More information

Inverse Kinematics. Given a desired position (p) & orientation (R) of the end-effector

Inverse Kinematics. Given a desired position (p) & orientation (R) of the end-effector Inverse Kinematics Given a desired position (p) & orientation (R) of the end-effector q ( q, q, q ) 1 2 n Find the joint variables which can bring the robot the desired configuration z y x 1 The Inverse

More information

6-dof Eye-vergence visual servoing by 1-step GA pose tracking

6-dof Eye-vergence visual servoing by 1-step GA pose tracking International Journal of Applied Electromagnetics and Mechanics 52 (216) 867 873 867 DOI 1.3233/JAE-16225 IOS Press 6-dof Eye-vergence visual servoing by 1-step GA pose tracking Yu Cui, Kenta Nishimura,

More information

Cecilia Laschi The BioRobotics Institute Scuola Superiore Sant Anna, Pisa

Cecilia Laschi The BioRobotics Institute Scuola Superiore Sant Anna, Pisa University of Pisa Master of Science in Computer Science Course of Robotics (ROB) A.Y. 2016/17 cecilia.laschi@santannapisa.it http://didawiki.cli.di.unipi.it/doku.php/magistraleinformatica/rob/start Robot

More information

Properties of Hyper-Redundant Manipulators

Properties of Hyper-Redundant Manipulators Properties of Hyper-Redundant Manipulators A hyper-redundant manipulator has unconventional features such as the ability to enter a narrow space while avoiding obstacles. Thus, it is suitable for applications:

More information

Approximate Policy Transfer applied to Simulated. Bongo Board balance toy

Approximate Policy Transfer applied to Simulated. Bongo Board balance toy Approximate Policy Transfer applied to Simulated Bongo Board Balance Stuart O. Anderson, Jessica K. Hodgins, Christopher G. Atkeson Robotics Institute Carnegie Mellon University soa,jkh,cga@ri.cmu.edu

More information

Table of Contents. Chapter 1. Modeling and Identification of Serial Robots... 1 Wisama KHALIL and Etienne DOMBRE

Table of Contents. Chapter 1. Modeling and Identification of Serial Robots... 1 Wisama KHALIL and Etienne DOMBRE Chapter 1. Modeling and Identification of Serial Robots.... 1 Wisama KHALIL and Etienne DOMBRE 1.1. Introduction... 1 1.2. Geometric modeling... 2 1.2.1. Geometric description... 2 1.2.2. Direct geometric

More information

Chapter 1: Introduction

Chapter 1: Introduction Chapter 1: Introduction This dissertation will describe the mathematical modeling and development of an innovative, three degree-of-freedom robotic manipulator. The new device, which has been named the

More information