Optimal Gait Primitives for Dynamic Bipedal Locomotion

Size: px
Start display at page:

Download "Optimal Gait Primitives for Dynamic Bipedal Locomotion"

Transcription

1 2012 IEEE/RSJ International Conference on Intelligent Robots and Systems October 7-12, Vilamoura, Algarve, Portugal Optimal Gait Primitives for Dynamic Bipedal Locomotion Bokman Lim, Jusuk Lee, Joohyung Kim, Minhyung Lee, Hoseong Kwak, Sunggu Kwon, Heekuk Lee, Woong Kwon, and Kyungshik Roh Abstract This paper presents a framework to generate dynamic walking for biped robots. A set of self-stable gait primitives is first constructed. It is done by 1) representing parametric gait primitives, 2) utilizing state-dependent torque control, and 3) doing numerical optimization that takes into account the complex multi-body dynamics with frictional contact forces. Dynamic walking to follow the arbitrary path including a curve is then generated online via sequentially composing primitive motions. Results show that dynamic gaits are humanlike and efficient compared to the conventional knee bent walkers. Our proposed method is applied to a torque-controlled, human-sized biped robot platform, Roboray which is cabledriven partially for joint compliance. Following a discussion on robot design and control, experimental results are also reported. I. INTRODUCTION Current walking robots are highly energy inefficient except recent passive walkers. Humanoid robots usually consume 10 times more energy than human while walking [1]. Generating energy efficient walking based on the dynamics models has received attention in robotics [2], [3]. We first briefly review two main approaches in research of biped locomotion: the zero moment point (ZMP) based walking and the dynamic (limit cycle) walking. The ZMP based walkers have the following common features [4]: 1) the stiff joints are position controlled with high gains, 2) ZMP criterion is used to guarantee biped walkers to not fall over. On the other hand, the dynamic walking (also known as energy efficient gait) has the following features 1) the compliant joints are force (torque) controlled, 2) stable walking is achieved by finding attractive stable orbits called limit cycles. In dynamic walking, we can also observe the periodic controlled falling motions like inverted pendulum [5] (notice that the force controlled compliant joints allow the inertial motion of the walker to be exploited rather than opposed). The ZMP based methods have disadvantages in energy efficiency. However, many ZMP based walkers [6], [7] have shown excellent performance in motion planning studies involving interaction with environment e.g., collision avoidance in 3-D space. On the contrary, most dynamic walking studies have been limited to straight walking [8]. Gregg et al. [5] showed curve walking but they used a simple model (4DOF and point feet). This is due to the difficulty in finding stable dynamic gaits for 3-D biped robots. In other Bokman Lim, Jusuk Lee, Joohyung Kim, Minhyung Lee, Hoseong Kwak, Sunggu Kwon, Heekuk Lee, Woong Kwon and Kyungshik Roh are with the Samsung Advanced Institute of Technology, Nongseo-dong, Giheung-gu, Yongin-si Gyeonggi-do, Korea bokman.lim@samsung.com Fig. 1. Dynamic bipedal walking robot system (Roboray) words, the complex dynamics must be used to produce stable limit cycles. For example, curve walking has an asymmetric property compared to the straight walking which makes the problem much more difficult. Our main contribution is a development of a systematic framework for generating dynamic locomotion for humanoid robots. Various dynamic gait primitives as parametric forms (straight walking, in-place walking, backward walking, and curve walking) are first constructed off-line using optimization based method. Online motion is then generated by sequentially composing primitive motions. First of all, we choose dynamic walking scheme and generate also minimum torque motion for energy efficiency. To find stable limit cycles during walking, we minimize walking periodical errors using landing forces (i.e., minimizing the difference of stepto-step landing forces). A desired walking style is achieved by a constant step length, step velocity, and turning angle. For the optimal walking, a development of a reliable and practical dynamics-based movement optimization algorithm should be emphasized. For these problems, dynamics should be considered during optimization procedures. The complexities of the dynamic equations, however, often lead to intractable constrained nonlinear optimization problems, especially for high degree-of-freedom systems such as a humanoid type model. Previously many dynamics-based algorithms need super-computing power [9], [10], or are not applicable to a real system because of hardware limitations [11]. Based on our dynamics-based optimization algorithms for different types of motion [12], [13], [14], we developed a robust and optimal walking controller. This paper is organized as follows. In Section II we explain the dynamic walking generation framework, and describe movement optimization algorithms and balance control meth /12/S IEEE 4013

2 ods. Section III provides case studies of various walking motions using a humanoid robot, Roboray, and also includes simulation studies and hardware experiments. II. FRAMEWORK AND ALGORITHM Our general framework for dynamic biped walking generation is shown in Fig. 2. Given a high-level description for a desired gait, the task parser interprets each task, simultaneously sensing environment information (to avoid obstacles) and generates a corresponding sequence of desired walking motions in parametric forms. The motion generation then takes the sequence as input, draws upon the database of walking primitives, and plans an appropriate gait sequence. Walking styles are represented by step length, step velocity, and turning angle. By sequentially composing primitive walking motions we determine how to follow the given target path. Gait motion sequence is replanned periodically to avoid moving obstacles. Our framework is composed of three main modules: a finite state machine for control torque generation, a gait primitive database for various styled walking, and a real-time motion planner for interacting with environment. Each part is designed by systematic procedures as shown in Fig. 6. Fig. 3. Robot joint coordination in lateral (left) and frontal plane (right). Left leg is stance state and right leg is swing state. Stance and swing leg are alternatively changed. Fig. 4. Robot joint coordination in axial plane (Rectangles imply robot footprints). Hip yawing strategy for turning for curve walking. p 2 in Table 1 means a half turning angle. properties, we plan the next step by switching swing and stance leg motions. This strategy is applied to all pitch, roll, and yaw joints (motions in lateral, frontal, and axial plane). Therefore control parameters are k p, k d, and via points for target trajectory. Fig. 2. Walking motion generation framework A. Generation of State-dependent Control Torque The control torque is generated by simple spring-damper couples as in (1) and the desired target trajectory q d is planned by sensing current robot state i.e., left stance or right stance. Fig. 3 shows the robot joint coordination in lateral and frontal planes for the left stance state. τ = k p (q d q) k d q (1) Fig. 4 shows the robot joint coordination in axial plane and the hip yawing strategy for curve walking. If the robot s state is just changed from right stance to left stance, the q d for the current state is planned by interpolating via points using quintic spline with zero velocity and acceleration boundary conditions. The via points represent the predefined finite robot states (cyclic gait postures). For example we can obtain a hip pitch joint target trajectory as shown in Fig. 5. By using periodic and symmetric Fig. 5. Example of target trajectory for right hip joint. Table I shows all the parameters of the target trajectory for the leg and torso motions. Initial posture q 0 is determined by the last state joint information of the previous step including posture, velocity, and acceleration (i th step q 0 is equal to i-1 th step q f ). By adjusting q m and q f we determine current target joint trajectory. State changes from left to right stance occur by sensing normal contact forces. The contact forces are measured by FT sensor attached on the foot. We use 200N as the threshold value for the state change condition. 4014

3 TABLE I TARGET TRAJECTORY PARAMETERIZATION WITH VIA POINTS Description of joint motion q m q f torso pitch inclination p 1 p 1 swing hip yaw for turning p 2 p 2 swing hip roll p 3 0 swing hip pitch p 4 2deg p 4 swing knee pitch p 5 0 swing ankle pitch p 6 p 7 + p 4 swing ankle roll p 3 0 stance hip yaw for turning p 2 p 2 stance hip roll p 3 0 stance hip pitch N/A p 4 stance knee pitch 0 0 stance ankle pitch p 7 p 7 p 4 stance ankle roll p 3 0 Target arm swing trajectories are also parameterized with a similar method (using 1 or 2 via points). To reduce the parametric space of control, we minimize control parameters P = {p i }. As shown in Fig. 6, this iterative procedure includes experimental sensitivity analysis of the parameters. The six parameters below are sufficient to represent various straight walking with stable limit cycle for the given system. p r1 = p 3 = rolling angle of hip roll joint p r2 = p 1 = torso inclination angle p r3 = p 4 = sweeping angle of swing hip pitch (2) p r4 = p 5 = maximum bending angle of swing knee p r5 = p 7 = bending angle of stance ankle pitch p r6 = t f = step time By adding three additional parameters p r7 = p 3,asym, p r8 = p 4,asym, and p r9 = p 7,asym for asymmetric left/right hip rolling/sweeping and ankle bending motion, curve walking can be produced. B. Dynamics-based Motion Optimization Algorithm We first reduce the optimization search space by selecting optimal key coordinates as optimization variables. Upper body motions are not independent during optimization procedures. Both arm motions are generated synchronously by lower body motion. Optimization variables are equal to the reduced control parameters in (2) involving transition parameters from the initial posture to the steady-state walking. In dynamic walking, initial motion is very important to achieve stable limit cycle quickly. To determine the initial half step motion, we add transitional control parameters p r0,roll, p r0,sweep for initial hip rolling and pitching motion. The overall flow chart for the motion optimization algorithm is shown in Fig. 8. 1) Dynamic Modeling: To plan a dynamically welldefined gait, or a gait that is energy efficient and stable in motion, we should perform accurate dynamic modeling and analysis. Our biped robot is a floating-base system where Fig. 7. Hardware prototype, cad model and kinematic diagram of Roboray. Six virtual passive joints (three prismatic and three revolute) connect between the robot base and the fixed world frame. the base link is not fixed, and includes dynamically different contact phases depending on the number of supporting legs as shown in Fig. 7. Let {q, q base } be a set of coordinates describing the kinematic configuration of the robot, where q denotes the vector of actuated joints and q base denotes both the six virtual passive joints used to parameterize the position and orientation of the moving base link of the robot. Denote τ by the torque (or force) vectors associated with q. The floating base has no constraints in moving (applied force should be set zero). Accounting for contact forces, the equations of motion then assume the form M(q) ( qbase q ) + b(q, q) + J T c F c = ( 0 τ where M is the mass matrix, b represents Coriolis, centrifugal, and gravity terms, F c is the wrench corresponding to the contact force, and J c is the constraint Jacobians associated with the contact wrench. In the forward dynamics problem with floating base and frictional contact, the objective is to determine the output values { q base, q} with a prescribed command input torque of the system in the form of inputs {q, q, τ}. For this purpose, we use the Open Dynamics Engine (for general discussions of ODE algorithm and contact dynamics see [15]). 2) Objective Function and Constraints: Given the fixed gains k p, k d and the above governing equation of motion, our goal is to optimize the objective functions of the form min P w 1J 1 + w 2 J 2 + w 3 J 3 + w 4 J 4 + w 5 J 5 J 1 = t f t=0 τ(t) 2 J 2 = n i=1 x i x d i 2 J 3 = n i=1 F i 2 + n 3 i=3 ( F i 2 F i F i F i F i F i+3 2 ) J 4 = v v d 2 J 5 = (P P pred ) T W (P P pred ) where J 1 represents an applied torque summation to be minimized, J 2 is a foot position and orientation error for n-step, J 3 represent a summation of normal landing force ) (3) (4) 4015

4 Fig. 6. Development procedures for finite state machine, walking motion primitives, and realtime motion planner and periodicity error, J 4 is a walking velocity error, J 5 is a walking style difference comparing the predefined initial motion P pred, i means i th step, and w is a weighting factor. motions. Stable transition between two primitive motions is possible in bounded variation. Fig. 9. Target trajectory tracking performance (blue: desired target trajectory, green: measured joint trajectory, left: simulation, right: experiment). III. EXPERIMENT Fig. 8. Algorithm flowchart for optimizing walking controller. Fig. 10. Dynamic waking with our proposed method (walking speed = 2.1 km/h) C. Parametric Representation of Cyclic Gait Primitives We represent cyclic gait primitives as reduced control parameters p ri in (2). Dynamic walking for following given path is generated by sequentially composing primitive walking database. In Equation (4) J 5 is also used as a measure comparing the similarity between two primitive walking To validate the computational feasibility of our approach, we perform numerical and real experiments with a hardware prototype, Roboray. Roboray is a biped humanoid robot platform which is composed of 32 joints (except 40 finger joints). The robot itself is 1.5 meters tall and has a mass of about 62 kg. To find optimal control parameters, we use 4016

5 the Powell s conjugate gradient decent method which is an optimization algorithm for finding the local minimum of a function which may be not differentiable. The ODE (open dynamic engine [15]) library is used to calculate forward dynamics of a multi-body system with a floating base and frictional contact forces. As shown in Fig. 8, our optimization algorithm includes a procedure of learning by dynamics simulation. The motion optimization algorithm is developed with C++ language and executed on a Core 2 (2.5 GHz) personal computer. Each optimization problem took about three hour with iteration. A. Design and Control of the Hardware Prototype Fig. 7 shows our biped humanoid robot system. Each leg has six joints where the three pitch joints (hip, knee, and ankle pitch) are actuated by cable-driven modules and the remaining three joints (hip roll/yaw, ankle roll) are actuated by harmonic drive modules. The cable-driven modules are ball screw mechanisms which take up more space then the harmonic drive modules but they provide better joint compliance and back-drivability. In dynamic walking, this compliant joint with elastic elements is important to achieve energy efficient walking. Arm joints are actuated with gear driven modules. For the detailed specification for Roboray see [16]. The state dependent control torque in (1) is generated with low PD gains resulting in a poor tracking performance of the desired joint angular position (see Fig. 9). However, tracking performance of the desired torque is good except for the swing phase of each leg; during the swing phase, damping term prevents system oscillation at high speeds. As discussed in Section I, the accurate trajectory tracking performance in the ZMP based method leads to the energy inefficiency due to opposing (gravity-powered) natural dynamics. In our dynamic walking, we also observe the controlled falling motion like that of inverted pendulum. We can also observe periodic hip rising and falling motion like a natural human walking. B. Straight Walking Optimization with Target Step Length TABLE II OPTIMIZATION RESULT FOR A STRAIGHT WALKING (STEP LENGTH = 35CM) Initial motion Optimized motion J J J J J Total Straight walk is characterized with a zero turning angle (also involving in-place walk with zero step length and backward walk with opposite directional step length). Using our proposed movement optimization algorithm we can find stable straight walking primitives. Fig. 11. Changes in parameters with varying step lengths. We use different weighting factors for the cost functions. Listing the priority from the highest: J 2 (representing foot position error), J 1 (applied torque summation), J 3, J 4, and then lastly J 5. We set the weighting factor for J 2 the highest because we want to achieve a constant step length. As shown in Table II, J 2 is highly minimized and J 1 is minimized by 88%. Fig. 11 shows the results of the straight walk optimization with selected step lengths. We observe that p r3, p r0,sweep related to hip pitch sweeping are monotonically increasing with longer step lengths, indicating that these parameters are highly related to the step length. Our optimization problem is so highly nonlinear that we could not observe any other distinct parameter relations. C. Curve Walking Optimization with Target Turning Angle Unlike straight walking, curve walking has asymmetric motion in left and right swing. We can observe a limit cycle which repeats itself every two cycles as shown in Fig. 12(b). This means two successive stepping motions are not identical and two periodic gaits are stable. In straight walking, we can observe a limit cycle which repeats on every cycle as shown in Fig. 12(a).We accomplished turning walk with constant curvatures as shown in Fig. 13. D. Balance Control By using optimal control parameter values, we achieve self-stable walking with only torso balance control at the level ground. To handle the internal and external disturbances (e.g., gait transition, terrain unevenness), we use the gravity compensation control and the center of pressure control with virtual model. For the detailed explanations of the control algorithms see [17]. E. Gait Planning with Primitive Walking Motions To follow a given path, we first search the appropriate primitive motion as finding the closest primitive motion with desired step length, velocity and turning angle. We then globally plan by ordering primitives (also checking stable 4017

6 (a) Fig. 14. Gait planning experiment with primitive walking motions (b) Fig. 12. Phase portraits for (a) stable symmetric walk (straight walk with step length = 33cm, step time = 0.85s), (b) stable asymmetric walk (curve walk with turning angle = 20deg, step time = 9.5s) (a few orbital trajectories moves away from the limit cycle due to transition motions from starting posture to steady state walk or vice versa). Fig. 13. Curve walking experiment transition) with a number of steps. Using local planner, gait motion is replanned periodically to avoid moving obstacles. IV. CONCLUSION We proposed a framework to generate dynamic walking for biped robots. A set of self-stable gait primitives is constructed by dynamics-based movement optimization algorithm. Dynamic walking for following a given path involving curves is then generated online via sequentially composing primitive motions. Resulting dynamic gaits show natural walking motion compared to the conventional knee bent walkers. Although we exclusively dealt with the humanoid type robot, our framework is easily extendable to other robot mechanisms (e.g., industrial manipulators) for energy efficient and fast motions. [2] L. Roussel, C. Canudas de Wit, and A. Goswami, Generation of energy optimal complete gait cycles for biped robots, Proc. IEEE Int. Conf. Robotics and Automation, pp , [3] G. Bessonnet, P. Seguin, and P. Sardain, A parametric optimization approach to walking pattern synthesis, Int. J. Robotics Research, vol. 24, no. 7, pp , [4] B. Siciliano and K. Oussama, eds., Handbook of Robotics, Springer Verlag, Heidelberg, [5] R. D. Gregg, T. Bretl, and M. W. Spong, Asymptotically stable gait primitives for planning dynamic bipedal locomotion in three dimensions, Proc. IEEE Int. Conf. Robotics and Automation, pp , [6] T. Takenaka, T. Matsumoto, and T. Yoshiike, Real time motion generation and control for biped robot - 1st report: walking gait pattern generation, Proc. IEEE Int. Conf. Robots and Systems, pp , [7] [8] D.J. Braun and M. Goldfarb, Control approach for actuated dynamic walking in biped robots, IEEE Transactions on Robotics, vol. 25, No. 6, pp , [9] J. M. Wang, D.J. Fleet, A. Hertzmann, Optimizing walking controllers, ACM Transactions on Graphics, vol.28, No. 5, [10] K. Harada, K. Hauser, T. Bretl, J.-C. Latombe, Natural motion generation for humanoid robots, Proc. IEEE Int. Conf. Robots and Systems, pp , [11] J. Laszlo, M. Panne, and E. Fiume, Limit cycle control and its application to the animation of balancing and walking, Proc. Int. Conf. on Computer Graphics and Interactive Techniques, pp , [12] B. Lim, J. Babic, and F.C. Park, Optimal jumps for biarticular legged robots, Proc. IEEE Int. Conf. Robotics and Automation, pp , [13] B. Lim, B. Kim, F.C. Park, and D.W. Hong, Movement primitives for three-legged locomotion over uneven terrain, Proc. IEEE Int. Conf. Robotics and Automation, pp , [14] S. Yoo, C. Park, S. You, and B. Lim, A dynamics-based optimal trajectory generation for controlling an automated excavator, J. Mech. Eng. Sci., Vol. 224, Part C, pp , [15] ODE. Open dynamics engine. [16] J. Kim, Y. Lee, S. Kwon, K. Seo, H. Lee, H. Kwak, and K. Roh, Development of the lower limbs of a humanoid robot, Proc. IEEE Int. Conf. Robots and Systems, [17] B. Lim, M. Lee, J. Kim, J. Lee, J. Park, K. Seo, and K. Roh, Control Design to Achieve Dynamic Walking on a Bipedal Robot with Compliance, Proc. IEEE Int. Conf. Robotics and Automation, pp , REFERENCES [1] S.H. Collins, A. Ruina, R. Tedrake, and M. Wisse, Efficient bipedal robots based on passive dynamic walkers, Science Magazine, vol. 307, pp ,

OPTIMAL TRAJECTORY GENERATION OF COMPASS-GAIT BIPED BASED ON PASSIVE DYNAMIC WALKING

OPTIMAL TRAJECTORY GENERATION OF COMPASS-GAIT BIPED BASED ON PASSIVE DYNAMIC WALKING OPTIMAL TRAJECTORY GENERATION OF COMPASS-GAIT BIPED BASED ON PASSIVE DYNAMIC WALKING Minseung Kim Dept. of Computer Science Illinois Institute of Technology 3201 S. State St. Box 2082 Chicago IL 60616

More information

Body Stabilization of PDW toward Humanoid Walking

Body Stabilization of PDW toward Humanoid Walking Body Stabilization of PDW toward Humanoid Walking Masaki Haruna, Masaki Ogino, Koh Hosoda, Minoru Asada Dept. of Adaptive Machine Systems, Osaka University, Suita, Osaka, 565-0871, Japan ABSTRACT Passive

More information

ZMP Trajectory Generation for Reduced Trunk Motions of Biped Robots

ZMP Trajectory Generation for Reduced Trunk Motions of Biped Robots ZMP Trajectory Generation for Reduced Trunk Motions of Biped Robots Jong H. Park School of Mechanical Engineering Hanyang University Seoul, 33-79, Korea email:jong.park@ieee.org Yong K. Rhee School of

More information

YAN GU. Assistant Professor, University of Massachusetts Lowell. Frederick N. Andrews Fellowship, Graduate School, Purdue University ( )

YAN GU. Assistant Professor, University of Massachusetts Lowell. Frederick N. Andrews Fellowship, Graduate School, Purdue University ( ) YAN GU Assistant Professor, University of Massachusetts Lowell CONTACT INFORMATION 31 University Avenue Cumnock 4E Lowell, MA 01854 yan_gu@uml.edu 765-421-5092 http://www.locomotionandcontrolslab.com RESEARCH

More information

Biomechanics and Models of Locomotion

Biomechanics and Models of Locomotion Physics-Based Models for People Tracking: Biomechanics and Models of Locomotion Marcus Brubaker 1 Leonid Sigal 1,2 David J Fleet 1 1 University of Toronto 2 Disney Research, Pittsburgh Biomechanics Biomechanics

More information

Dynamically stepping over large obstacle utilizing PSO optimization in the B4LC system

Dynamically stepping over large obstacle utilizing PSO optimization in the B4LC system 1 Dynamically stepping over large obstacle utilizing PSO optimization in the B4LC system QI LIU, JIE ZHAO, KARSTEN BERNS Robotics Research Lab, University of Kaiserslautern, Kaiserslautern, 67655, Germany

More information

Motion Control of a Bipedal Walking Robot

Motion Control of a Bipedal Walking Robot Motion Control of a Bipedal Walking Robot Lai Wei Ying, Tang Howe Hing, Mohamed bin Hussein Faculty of Mechanical Engineering Universiti Teknologi Malaysia, 81310 UTM Skudai, Johor, Malaysia. Wylai2@live.my

More information

Stable Upright Walking and Running using a simple Pendulum based Control Scheme

Stable Upright Walking and Running using a simple Pendulum based Control Scheme 1 Stable Upright Walking and Running using a simple Pendulum based Control Scheme H.-M. MAUS, J. RUMMEL and A. SEYFARTH Lauflabor Locomotion Laboratory, University of Jena, Germany E-mail: moritz.maus@uni-jena.de

More information

Controlling Walking Behavior of Passive Dynamic Walker utilizing Passive Joint Compliance

Controlling Walking Behavior of Passive Dynamic Walker utilizing Passive Joint Compliance Controlling Walking Behavior of Passive Dynamic Walker utilizing Passive Joint Compliance Takashi TAKUMA, Koh HOSODA Department of Adaptive Machine Systems, Graduate School of Engineering Osaka University

More information

Emergent walking stop using 3-D ZMP modification criteria map for humanoid robot

Emergent walking stop using 3-D ZMP modification criteria map for humanoid robot 2007 IEEE International Conference on Robotics and Automation Roma, Italy, 10-14 April 2007 ThC9.3 Emergent walking stop using 3-D ZMP modification criteria map for humanoid robot Tomohito Takubo, Takeshi

More information

Human Pose Tracking III: Dynamics. David Fleet University of Toronto

Human Pose Tracking III: Dynamics. David Fleet University of Toronto Human Pose Tracking III: Dynamics David Fleet University of Toronto CIFAR Summer School, 2009 Interactions with the world are fundamental Implausible motions [Poon and Fleet, 01] Kinematic Model: damped

More information

Humanoid Robots and biped locomotion. Contact: Egidio Falotico

Humanoid Robots and biped locomotion. Contact: Egidio Falotico Humanoid Robots and biped locomotion Contact: Egidio Falotico e.falotico@sssup.it Outline What is a Humanoid? Why Develop Humanoids? Challenges in Humanoid robotics Active vs Passive Locomotion Active

More information

Decentralized Autonomous Control of a Myriapod Locomotion Robot

Decentralized Autonomous Control of a Myriapod Locomotion Robot Decentralized utonomous Control of a Myriapod Locomotion Robot hmet Onat Sabanci University, Turkey onat@sabanciuniv.edu Kazuo Tsuchiya Kyoto University, Japan tsuchiya@kuaero.kyoto-u.ac.jp Katsuyoshi

More information

Trajectory Planning for Smooth Transition of a Biped Robot

Trajectory Planning for Smooth Transition of a Biped Robot Proceedings of the 003 IEEE International Conference on Robotics & Automation Taipei, Taiwan, September 14-19, 003 Trajectory Planning for Smooth Transition of a Biped Robot Zhe Tang 1,, Changjiu Zhou,

More information

Walking Experiment of Biped Robot with Antagonistic Actuation Using Non-Linear Spring

Walking Experiment of Biped Robot with Antagonistic Actuation Using Non-Linear Spring , March 16-18, 2016, Hong Kong Walking Experiment of Biped Robot with Antagonistic Actuation Using Non-Linear Spring Takashige Yano, Jae Hoon Lee, Member, IAENG and Shingo Okamoto 1 Abstract The purpose

More information

Faster and Smoother Walking of Humanoid HRP-2 with Passive Toe Joints *

Faster and Smoother Walking of Humanoid HRP-2 with Passive Toe Joints * Faster and Smoother Walking of Humanoid HRP-2 with Passive Toe Joints * Ramzi Sellaouti *1, Olivier Stasse *2, Shuuji Kajita *3, Kazuhito Yokoi *1 and Abderrahmane Kheddar *2 *1 JRL, AIST *2 JRL, CNRS

More information

Effects of Ankle Stiffness on Gait Selection of Dynamic Bipedal Walking with Flat Feet

Effects of Ankle Stiffness on Gait Selection of Dynamic Bipedal Walking with Flat Feet 2 IEEE International Conference on Rehabilitation Robotics Rehab Week Zurich, ETH Zurich Science City, Switzerland, June 29 - July, 2 Effects of Ankle Stiffness on Gait Selection of Dynamic Bipedal Walking

More information

Robot motion by simultaneously wheel and leg propulsion

Robot motion by simultaneously wheel and leg propulsion Robot motion by simultaneously wheel and leg propulsion Aarne Halme, Ilkka Leppänen, Miso Montonen, Sami Ylönen Automation Technology Laboratory Helsinki University of Technology PL 5400, 02015 HUT, Finland

More information

Kungl Tekniska Högskolan

Kungl Tekniska Högskolan Centre for Autonomous Systems Kungl Tekniska Högskolan hic@kth.se March 22, 2006 Outline Wheel The overall system layout : those found in nature found in nature Difficult to imitate technically Technical

More information

Centre for Autonomous Systems

Centre for Autonomous Systems Centre for Autonomous Systems Kungl Tekniska Högskolan hic@kth.se March 22, 2006 Outline Wheel The overall system layout : those found in nature found in nature Difficult to imitate technically Technical

More information

A Bio-inspired Behavior Based Bipedal Locomotion Control B4LC Method for Bipedal Upslope Walking

A Bio-inspired Behavior Based Bipedal Locomotion Control B4LC Method for Bipedal Upslope Walking 1 A Bio-inspired Behavior Based Bipedal Locomotion Control B4LC Method for Bipedal Upslope Walking JIE ZHAO, QI LIU, STEFFEN SCHUETZ, and KARSTEN BERNS Robotics Research Lab, University of Kaiserslautern,

More information

INSTANTANEOUS ON-LINE MODIFICATION OF BIPED WALK COMPOSED FROM RECONFIGURABLE ADAPTIVE MOTION PRIMITIVES

INSTANTANEOUS ON-LINE MODIFICATION OF BIPED WALK COMPOSED FROM RECONFIGURABLE ADAPTIVE MOTION PRIMITIVES THERMAL SCIENCE: Year 26, Vol. 2, Suppl. 2, pp. S53-S523 S53 INSTANTANEOUS ON-LINE MODIFICATION OF BIPED WALK COMPOSED FROM RECONFIGURABLE ADAPTIVE MOTION PRIMITIVES Introduction by Branislav A. BOROVAC

More information

Proof Copy. Controlling the Walking Period of a Pneumatic Muscle Walker. Takashi Takuma Koh Hosoda. Abstract. 1. Introduction

Proof Copy. Controlling the Walking Period of a Pneumatic Muscle Walker. Takashi Takuma Koh Hosoda. Abstract. 1. Introduction Takashi Takuma Koh Hosoda Department of Adaptive Machine Systems Graduate School of Engineering, Osaka University Yamadaoka 2 1, Suita, Osaka 565 0871, Japan {takuma,hosoda}@ams.eng.osaka-u.ac.jp Controlling

More information

Toward a Human-like Biped Robot with Compliant Legs

Toward a Human-like Biped Robot with Compliant Legs Book Title Book Editors IOS Press, 2003 1 Toward a Human-like Biped Robot with Compliant Legs Fumiya Iida a,b,1, Yohei Minekawa a Juergen Rummel a and Andre Seyfarth a a Locomotion Laboratory, University

More information

In memory of Dr. Kevin P. Granata, my graduate advisor, who was killed protecting others on the morning of April 16, 2007.

In memory of Dr. Kevin P. Granata, my graduate advisor, who was killed protecting others on the morning of April 16, 2007. Acknowledgement In memory of Dr. Kevin P. Granata, my graduate advisor, who was killed protecting others on the morning of April 16, 2007. There are many others without whom I could not have completed

More information

ZSTT Team Description Paper for Humanoid size League of Robocup 2017

ZSTT Team Description Paper for Humanoid size League of Robocup 2017 Adult- ZSTT Team Description Paper for Humanoid size League of Robocup 2017 Jaesik Jeong, Youngsup Oh and Jeehyun Yang ZSTT E-mail: soulmatree@gmail.com Web: www.soulmatree.com Abstract. This paper describes

More information

Learning Energy Efficient Walking Based on Ballistics

Learning Energy Efficient Walking Based on Ballistics Learning Energy Efficient Walking Based on Ballistics Masaki Ogino, Koh Hosoda and Minoru Asada Dept. of Adaptive Machine Systems, Graduate School of Engineering,, HANDAI Frontier Research Center ogino@er.ams.eng.osaka-u.ac.jp,

More information

Compliance Control for Biped Walking on Rough Terrain

Compliance Control for Biped Walking on Rough Terrain Compliance Control for Biped Walking on Rough Terrain Masaki Ogino 1,2, Hiroyuki Toyama 2 Sawa Fuke 1,2, Norbert Michael Mayer 1,2, Ayako Watanabe 2, and Minoru Asada 1,2 1 JST ERATO Asada Project, Yamada-oka

More information

PERCEPTIVE ROBOT MOVING IN 3D WORLD. D.E- Okhotsimsky, A.K. Platonov USSR

PERCEPTIVE ROBOT MOVING IN 3D WORLD. D.E- Okhotsimsky, A.K. Platonov USSR PERCEPTIVE ROBOT MOVING IN 3D WORLD D.E- Okhotsimsky, A.K. Platonov USSR Abstract. This paper reflects the state of development of multilevel control algorithms for a six-legged mobile robot. The robot

More information

An Energy Efficient Dynamic Gait for a Nao Robot

An Energy Efficient Dynamic Gait for a Nao Robot An Energy Efficient Dynamic Gait for a Nao Robot Zhenglong Sun, Nico Roos Department of Knowledge Engineering, Maastricht University P.O. Box 66, 62 MD Maastricht, The Netherlands Abstract This paper presents

More information

Using GPOPS-II to optimize sum of squared torques of a double pendulum as a prosthesis leg. Abstract

Using GPOPS-II to optimize sum of squared torques of a double pendulum as a prosthesis leg. Abstract Using GPOPS-II to optimize sum of squared torques of a double pendulum as a prosthesis leg Abstract Milad Zarei MCE 593 Prosthesis Design & Control A two-dimensional, two links pendulum is developed to

More information

A Walking Pattern Generation Method for Humanoid robots using Least square method and Quartic polynomial

A Walking Pattern Generation Method for Humanoid robots using Least square method and Quartic polynomial 7 A Walking Pattern Generation Method for Humanoid robots using Least square method and Quartic polynomial Seokmin Hong *,,Yonghwan Oh Young-Hwan Chang and Bum-Jae You * University of Science and Technology(UST),

More information

3D Limit Cycle Walking of Musculoskeletal Humanoid Robot with Flat Feet

3D Limit Cycle Walking of Musculoskeletal Humanoid Robot with Flat Feet The 2009 IEEE/RSJ International Conference on Intelligent Robots and Systems October 11-15, 2009 St. Louis, USA 3D Limit Cycle Walking of Musculoskeletal Humanoid Robot with Flat Feet Kenichi Narioka,

More information

Effects of a Passive Dynamic Walker s Mechanical Parameters on Foot- Ground Clearance

Effects of a Passive Dynamic Walker s Mechanical Parameters on Foot- Ground Clearance Applied Mechanics and Materials Submitted: 204-09-9 ISSN: 662-7482, Vols. 687-69, pp 279-284 Accepted: 204-09-27 doi:0.4028/www.scientific.net/amm.687-69.279 Online: 204--27 204 Trans Tech Publications,

More information

Stabilization of a Three-Dimensional Limit Cycle Walking Model through Step-to-Step Ankle Control

Stabilization of a Three-Dimensional Limit Cycle Walking Model through Step-to-Step Ankle Control 2013 IEEE International Conference on Rehabilitation Robotics June 24-26, 2013 Seattle, Washington USA Stabilization of a Three-Dimensional Limit Cycle Walking Model through Step-to-Step Ankle Control

More information

Neuro-Fuzzy ZMP Control of a Biped Robot

Neuro-Fuzzy ZMP Control of a Biped Robot Proceedings of the 6th WSEAS International Conference on Simulation, Modelling and Optimization, Lisbon, Portugal, September 22-24, 26 331 Neuro-Fuzzy ZMP Control of a Biped Robot JOÃO PAULO FERREIRA (1)

More information

Emergency Stop Algorithm for Walking Humanoid Robots

Emergency Stop Algorithm for Walking Humanoid Robots Emergency Stop Algorithm for Walking Humanoid Robots Mitsuharu Morisawa, Shuuji Kajita, Kensuke Harada, Kiyoshi Fujiwara Fumio Kanehiro, Kenji Kaneko, Hirohisa Hirukawa National Institute of Advanced Industrial

More information

Spring Locomotion Concepts. Roland Siegwart, Margarita Chli, Martin Rufli. ASL Autonomous Systems Lab. Autonomous Mobile Robots

Spring Locomotion Concepts. Roland Siegwart, Margarita Chli, Martin Rufli. ASL Autonomous Systems Lab. Autonomous Mobile Robots Spring 2016 Locomotion Concepts Locomotion Concepts 01.03.2016 1 Locomotion Concepts: Principles Found in Nature ASL Autonomous Systems Lab On ground Locomotion Concepts 01.03.2016 2 Locomotion Concepts

More information

Sample Solution for Problem 1.a

Sample Solution for Problem 1.a Sample Solution for Problem 1.a 1 Inverted Pendulum Model (IPM) 1.1 Equations of Motion and Ground Reaction Forces Figure 1: Scheme of the Inverted Pendulum Model (IPM). The equations of motion of this

More information

Simulation of the Hybtor Robot

Simulation of the Hybtor Robot Simulation of the Hybtor Robot Pekka Aarnio, Kari Koskinen and Sami Salmi Information and Computer Systems in Automation Helsinki University of Technology ABSTRACT A dynamic rigid body simulation model

More information

Stability Control of Bipedal Walking Robot

Stability Control of Bipedal Walking Robot Stability Control of Bipedal Walking Robot V.Mastanaiah Assistant Professor, Department of Mechanical Engineering, KG Reddy College of Engineering and Technology, Moinabad, Telangana, India. ABSTRACT:

More information

Bio-Inspired Optimal Control Framework to Generate Walking Motions for the Humanoid Robot icub Using Whole Body Models

Bio-Inspired Optimal Control Framework to Generate Walking Motions for the Humanoid Robot icub Using Whole Body Models applied sciences Article Bio-Inspired Optimal Control Framework to Generate Walking Motions for the Humanoid Robot icub Using Whole Body Models Yue Hu 1,2 * ID and Katja Mombaur1,2 ID 1 Optimization, Robotics

More information

Controlling Velocity In Bipedal Walking: A Dynamic Programming Approach

Controlling Velocity In Bipedal Walking: A Dynamic Programming Approach Controlling Velocity In Bipedal Walking: A Dynamic Programming Approach Thijs Mandersloot and Martijn Wisse Delft University of Technology Delft, Netherlands thijs.mandersloot@gmail.com, m.wisse@tudelft.nl

More information

Walking Gait Generation with Foot Placement Control for the HOAP-3 Humanoid Robot

Walking Gait Generation with Foot Placement Control for the HOAP-3 Humanoid Robot Walking Gait Generation with Foot Placement Control for the HOAP-3 Humanoid Robot Yazhou Huang, Robert Backman and Marcelo Kallmann UCM School of Engineering Technical Report TR-2011-002 University of

More information

Learning Energy Efficient Walking with Ballistic Walking

Learning Energy Efficient Walking with Ballistic Walking Learning Energy Efficient Walking with Ballistic Walking Masaki Ogino, Koh Hosoda and Minoru Asada Dept. of Adaptive Machine Systems, Graduate School of Engineering,, HANDAI Frontier Research Center, Osaka

More information

IMPLEMENTATION AND ANALYSIS OF FUZZY-ZMP-WALKING CONTROL IN THE GIMBIPED

IMPLEMENTATION AND ANALYSIS OF FUZZY-ZMP-WALKING CONTROL IN THE GIMBIPED 1 IMPLEMENTATION AND ANALYSIS OF FUZZY-ZMP-WALKING CONTROL IN THE GIMBIPED FERDI PERDANA-KUSUMAH, JOSÉ-LUIS PERALTA-CABEZAS, TOMI YLIKORPI and AARNE HALME Department of Automation and Systems Technology,

More information

Powered Bipeds Based on Passive Dynamic Principles

Powered Bipeds Based on Passive Dynamic Principles Proceedings of 25 5th IEEE-RAS International Conference on Humanoid Robots Powered Bipeds Based on Passive Dynamic Principles S. O. Anderson,M.Wisse,C.G.Atkeson, J.K. Hodgins,G.J.Zeglin,B.Moyer Carnegie

More information

Generation of Robot Motion Based on Measurement of Human Movement. Susumu Sakano 1, Satoru Shoji 1

Generation of Robot Motion Based on Measurement of Human Movement. Susumu Sakano 1, Satoru Shoji 1 Generation of Robot Motion Based on Measurement of Human Movement Susumu Sakano 1, Satoru Shoji 1 1College of Engineering, Nihon University 1 Nakagawara Tokusada Tamura-machi Koriyama 963-8642 Japan Tel;

More information

Dynamic Lateral Stability for an Energy Efficient Gait

Dynamic Lateral Stability for an Energy Efficient Gait Dynamic Lateral Stability for an Energy Efficient Gait Zhenglong Sun a Nico Roos a a Department of Knowledge Engineering, Maastricht University P.O. Box 616, 6200 MD Maastricht, The Netherlands Abstract

More information

Limit Cycle Walking and Running of Biped Robots

Limit Cycle Walking and Running of Biped Robots Tokyo Institute of Technology Yamakita Lab. Limit Cycle Walking and Running of Biped Robots Masaki Yamakita Tokyo Institute of Technology Introduction of Yamakita Lab. 1/14 Other Research Topics State

More information

Truba college of Engineering & Technology, Indore, India. Truba college of Engineering & Technology, Indore, India.

Truba college of Engineering & Technology, Indore, India. Truba college of Engineering & Technology, Indore, India. IJESRT INTERNATIONAL JOURNAL OF ENGINEERING SCIENCES & RESEARCH TECHNOLOGY DESIGN AND DEVELOPMENT OF WALKING BIPEDAL ROBOT WITH THE HELP OF ARDUINO CONTROLLER Deepti Malviya*, Suman Sharma * Truba college

More information

ON PASSIVE MOTION OF THE ARMS FOR A WALKING PLANAR BIPED

ON PASSIVE MOTION OF THE ARMS FOR A WALKING PLANAR BIPED ON PASSIVE MOTION OF THE ARMS FOR A WALKING PLANAR BIPED Bassel Kaddar, Yannick Aoustin, Christine Chevallereau To cite this version: Bassel Kaddar, Yannick Aoustin, Christine Chevallereau. ON PASSIVE

More information

Generalized Biped Walking Control

Generalized Biped Walking Control Generalized Biped Walking Control Stelian Coros Philippe Beaudoin Michiel van de Panne University of British Columbia Figure 1: Real-time physics-based simulation of walking. The method provides robust

More information

DEVELOPMENT OF A FULL-SIZED BIPEDAL HUMANOID ROBOT UTILIZING SPRING ASSISTED PARALLEL FOUR-BAR LINKAGES WITH SYNCHRONIZED ACTUATION

DEVELOPMENT OF A FULL-SIZED BIPEDAL HUMANOID ROBOT UTILIZING SPRING ASSISTED PARALLEL FOUR-BAR LINKAGES WITH SYNCHRONIZED ACTUATION Proceedings of the ASME 2011 International Design Engineering Technical Conferences & Computers and Information in Engineering Conference IDETC/CIE 2011 August 28-31, 2011, Washington, DC, USA DETC2011-4

More information

Improvement of Humanoid Walking Control by Compensating Actuator Elasticity

Improvement of Humanoid Walking Control by Compensating Actuator Elasticity 216 IEEE-RAS 16th International Conference on Humanoid Robots (Humanoids) Cancun, Mexico, Nov 15-17, 216 Improvement of Humanoid Walking Control by Compensating Actuator Elasticity Jeeseop Kim 1, Mingon

More information

Book Review. I. Background

Book Review. I. Background Book Review 1 Delft Pneumatic Bipeds by Martijn Wisse and Richard Q. van der Linde, Springer Tracts in Advanced Robotics, Vol. 34, 2007, ISBN 978-3-540-72807-8, 136 pages, US$109, Reviewed by J.W. Grizzle

More information

A NEW GOLF-SWING ROBOT MODEL UTILIZING SHAFT ELASTICITY

A NEW GOLF-SWING ROBOT MODEL UTILIZING SHAFT ELASTICITY Journal of Sound and Vibration (1998) 17(1), 17 31 Article No. sv981733 A NEW GOLF-SWING ROBOT MODEL UTILIZING SHAFT ELASTICITY S. SUZUKI Department of Mechanical System Engineering, Kitami Institute of

More information

DETC DESIGN OPTIMIZATION OF A NOVEL TRIPEDAL LOCOMOTION ROBOT THROUGH SIMULATION AND EXPERIMENTS FOR A SINGLE STEP DYNAMIC GAIT

DETC DESIGN OPTIMIZATION OF A NOVEL TRIPEDAL LOCOMOTION ROBOT THROUGH SIMULATION AND EXPERIMENTS FOR A SINGLE STEP DYNAMIC GAIT Proceedings of the ASME 27 International Design Engineering Technical Conferences & Computers and Information in Engineering Conference IDETC/CIE 27 September 4-7, 27, Las Vegas, Nevada, USA DETC27-34472

More information

HYBRID POSITION/FORCE ALGORITHMS FOR BIPED LOCOMOTION

HYBRID POSITION/FORCE ALGORITHMS FOR BIPED LOCOMOTION HYBRID POSIION/FORCE ALGORIHMS FOR BIPED LOCOMOION Filipe M. Silva * and J.A. enreiro Machado ** * Dept. of Mechanical Engineering, University of Aveiro, Portugal ** Dept. of Electrical Engineering, Polytechnic

More information

Toward a Human-like Biped Robot with Compliant Legs

Toward a Human-like Biped Robot with Compliant Legs Book Title Book Editors IOS Press, 23 1 Toward a Human-like Biped Robot with Compliant Legs Fumiya Iida a,b,1, Yohei Minekawa a Juergen Rummel a and Andre Seyfarth a a Locomotion Laboratory, University

More information

Novel Tripedal Mobile Robot and Considerations for Gait Planning Strategies Based on Kinematics

Novel Tripedal Mobile Robot and Considerations for Gait Planning Strategies Based on Kinematics Novel Tripedal Mobile Robot and Considerations for Gait lanning Strategies Based on Kinematics Ivette Morazzani, Dennis Hong, Derek Lahr, and ing Ren RoMeLa: Robotics and Mechanisms Laboratory, Virginia

More information

SHUFFLE TURN OF HUMANOID ROBOT SIMULATION BASED ON EMG MEASUREMENT

SHUFFLE TURN OF HUMANOID ROBOT SIMULATION BASED ON EMG MEASUREMENT SHUFFLE TURN OF HUMANOID ROBOT SIMULATION BASED ON EMG MEASUREMENT MASANAO KOEDA, TAKAYUKI SERIZAWA, AND YUTA MATSUI Osaka Electro-Communication University, Faculty of Information Science and Arts, Department

More information

Design, Fabrication and Analysis of Microcontroller Based Bipedal Walking Robot Vaidyanathan.V.T 1 and Sivaramakrishnan.R 2

Design, Fabrication and Analysis of Microcontroller Based Bipedal Walking Robot Vaidyanathan.V.T 1 and Sivaramakrishnan.R 2 Design, Fabrication and Analysis of Microcontroller Based Bipedal Walking Robot Vaidyanathan.V.T 1 and Sivaramakrishnan.R 2 1, 2 Mechatronics, Department of Production Technology, Madras Institute of Technology,

More information

Planning energy-efficient bipedal locomotion on patterned terrain

Planning energy-efficient bipedal locomotion on patterned terrain Planning energy-efficient bipedal locomotion on patterned terrain Ali Zamani 1, Pranav A. Bhounsule 1, Ahmad Taha 2 corresponding author: pranav.bhounsule@utsa.edu 1 Dept. of Mechanical Engineering, 2

More information

From Passive to Active Dynamic 3D Bipedal Walking - An Evolutionary Approach -

From Passive to Active Dynamic 3D Bipedal Walking - An Evolutionary Approach - From Passive to Active Dynamic 3D Bipedal Walking - An Evolutionary Approach - Steffen Wischmann and Frank Pasemann Fraunhofer Institute for Autonomous Intelligent Systems (AiS) Schloss Birlinghoven, 53754

More information

REPORT DOCUMENTATION PAGE

REPORT DOCUMENTATION PAGE REPORT DOCUMENTATION PAGE Form Approved OMB NO. 0704-0188 The public reporting burden for this collection of information is estimated to average 1 hour per response, including the time for reviewing instructions,

More information

Robots With Legs. Helge Wrede

Robots With Legs. Helge Wrede Robots With Legs Helge Wrede 27.11.2017 Outline Motivation Overview Properties Number of legs Balance Walking Basic Bipedal Implementation Dynamic Balancing Concepts 3D-LIPM 2 Motivation Figure: Side view

More information

Quadratic Encoding of Optimized Humanoid Walking

Quadratic Encoding of Optimized Humanoid Walking Quadratic Encoding of Optimized Humanoid Walking Junggon Kim, Nancy S. Pollard and Christopher G. Atkeson Abstract In this paper we show that optimal stepping trajectories and trajectory cost for a walking

More information

Using sensory feedback to improve locomotion performance of the salamander robot in different environments

Using sensory feedback to improve locomotion performance of the salamander robot in different environments Using sensory feedback to improve locomotion performance of the salamander robot in different environments João Lourenço Silvério Assistant: Jérémie Knüsel Structure of the presentation: I. Overview II.

More information

RUNNING ON SOFT GROUND: SIMPLE, ENERGY-OPTIMAL DISTURBANCE REJECTION

RUNNING ON SOFT GROUND: SIMPLE, ENERGY-OPTIMAL DISTURBANCE REJECTION CLAWAR 2012 Proceedings of the Fifteenth International Conference on Climbing and Walking Robots and the Support Technologies for Mobile Machines, Baltimore, MD, USA, 23 26 July 2012 543 RUNNING ON SOFT

More information

Journal of Chemical and Pharmaceutical Research, 2016, 8(6): Research Article. Walking Robot Stability Based on Inverted Pendulum Model

Journal of Chemical and Pharmaceutical Research, 2016, 8(6): Research Article. Walking Robot Stability Based on Inverted Pendulum Model Available online www.jocpr.com Journal of Chemical and Pharmaceutical Research, 2016, 8(6):463-467 Research Article ISSN : 0975-7384 CODEN(USA) : JCPRC5 Walking Robot Stability Based on Inverted Pendulum

More information

Swing leg retraction helps biped walking stability

Swing leg retraction helps biped walking stability Proceedings of 25 5th IEEE-RAS International Conference on Humanoid Robots Swing leg retraction helps biped walking stability M Wisse*, C G Atkeson,DKKloimwieder * Delft University of Technology, wwwdbltudelftnl,

More information

Gait Analysis of a Little Biped Robot. Received May 2015; accepted July 2015

Gait Analysis of a Little Biped Robot. Received May 2015; accepted July 2015 ICIC Express Letters Part B: Applications ICIC International c216 ISSN 2185-2766 Volume 7, Number 5, May 216 pp. 1 6 Gait Analysis of a Little Biped Robot Chi-Sheng Tsai 1, Chen-Huei Hsieh 1, Wenning QIU

More information

Programming Self-Recovery in the humanoid Leong Ti Xean 1 Yap Kian Tiong 2

Programming Self-Recovery in the humanoid Leong Ti Xean 1 Yap Kian Tiong 2 Programming Self-Recovery in the humanoid Leong Ti Xean 1 Yap Kian Tiong 2 1. INTRODUCTION 1.1 Background In October 2000, Honda announced the ASIMO humanoid robot, capable of interpreting the postures

More information

CS 4649/7649 Robot Intelligence: Planning

CS 4649/7649 Robot Intelligence: Planning CS 4649/7649 Robot Intelligence: Planning Differential Kinematics, Probabilistic Roadmaps Sungmoon Joo School of Interactive Computing College of Computing Georgia Institute of Technology S. Joo (sungmoon.joo@cc.gatech.edu)

More information

beestanbul RoboCup 3D Simulation League Team Description Paper 2012

beestanbul RoboCup 3D Simulation League Team Description Paper 2012 beestanbul RoboCup 3D Simulation League Team Description Paper 2012 Baris Demirdelen, Berkay Toku, Onuralp Ulusoy, Tuna Sonmez, Kubra Ayvaz, Elif Senyurek, and Sanem Sariel-Talay Artificial Intelligence

More information

Compliance for a cross four-bar knee joint

Compliance for a cross four-bar knee joint Compliance for a cross four-bar knee joint Arnaud Hamon, Yannick Aoustin To cite this version: Arnaud Hamon, Yannick Aoustin. Compliance for a cross four-bar knee joint. The 14th International Conference

More information

Gait Pattern Generation and Stabilization for Humanoid Robot Based on Coupled Oscillators

Gait Pattern Generation and Stabilization for Humanoid Robot Based on Coupled Oscillators 2011 IEEE/RSJ International Conference on Intelligent Robots and Systems September 25-30, 2011. San Francisco, CA, USA Gait Pattern Generation and Stabilization for Humanoid Robot Based on Coupled Oscillators

More information

Gait planning for biped locomotion on slippery terrain

Gait planning for biped locomotion on slippery terrain Gait planning for biped locomotion on slippery terrain Martim Brandão, Kenji Hashimoto, José Santos-Victor and Atsuo Takanishi Abstract We propose a new biped locomotion planning method that optimizes

More information

Sensing and Modeling of Terrain Features using Crawling Robots

Sensing and Modeling of Terrain Features using Crawling Robots Czech Technical University in Prague Sensing and Modeling of Terrain Features using Crawling Robots Jakub Mrva 1 Faculty of Electrical Engineering Agent Technology Center Computational Robotics Laboratory

More information

HUMANOID robots involve many technical issues to be

HUMANOID robots involve many technical issues to be IEEE TRANSACTIONS ON ROBOTICS, VOL. 21, NO. 5, OCTOBER 2005 977 Sensory Reflex Control for Humanoid Walking Qiang Huang and Yoshihiko Nakamura, Member, IEEE Abstract Since a biped humanoid inherently suffers

More information

Slip Observer for Walking on a Low Friction Floor

Slip Observer for Walking on a Low Friction Floor Slip Observer for Walking on a Low Friction Floor Kenji KANEKO, Fumio KANEHIRO, Shuuji KAJITA, Mitsuharu MORISAWA Kiyoshi FUJIWARA, Kensuke HARADA, and Hirohisa HIRUKAWA National Institute of Advanced

More information

Study of Dynamic Biped Locomotion on Rugged Terrain - Derivation and Application of the Linear Inverted Pendulum Mode -

Study of Dynamic Biped Locomotion on Rugged Terrain - Derivation and Application of the Linear Inverted Pendulum Mode - Proceedings of the 1991 IEEE Intemational Conference on Robotics and Automation Sacramento, California - April 1991 Study of Dynamic Biped Locomotion on Rugged Terrain - Derivation and Application of the

More information

Omnidirectional Humanoid Balance Control: Multiple Strategies for Reacting to a Push

Omnidirectional Humanoid Balance Control: Multiple Strategies for Reacting to a Push UBC CS TECHNICAL REPORT TR-2006-11 1 Omnidirectional Humanoid Balance Control: Multiple Strategies for Reacting to a Push KangKang Yin, Department of Computer Science University of British Columbia, Canada

More information

CONFIRMATION OF PHD CANDIDATURE DAMIEN KEE 2003

CONFIRMATION OF PHD CANDIDATURE DAMIEN KEE 2003 CONFIRMATION OF PHD CANDIDATURE DAMIEN KEE 2003 List of Publications: Wyeth G, Kee D, Yik T, Evolving a Locus based Gait for a Humanoid Robot, Proceedings of the International Conference on Intelligent

More information

Locomotion Concepts. Autonomous Mobile Robots. Concepts Legged Locomotion Wheeled Locomotion. Autonomous Systems Lab. Zürich. Localization.

Locomotion Concepts. Autonomous Mobile Robots. Concepts Legged Locomotion Wheeled Locomotion. Autonomous Systems Lab. Zürich. Localization. Autonomous Mobile Robots Localization "Position" Global Map Cognition Environment Model Local Map Path Perception Real World Environment Motion Control Locomotion Concepts Concepts Legged Locomotion Wheeled

More information

Robotics and Autonomous Systems

Robotics and Autonomous Systems Robotics and Autonomous Systems Lecture 4: Locomotion Richard Williams Department of Computer Science University of Liverpool 1 / 57 Today 2 / 57 Motion Two aspects: Locomotion Kinematics Locomotion: What

More information

Experimental Realization of Dynamic Walking for a Human-Riding Biped Robot, HUBO FX-1

Experimental Realization of Dynamic Walking for a Human-Riding Biped Robot, HUBO FX-1 Experimental Realization of Dynamic Walking for a Human-Riding Biped Robot, HUBO FX-1 JUNG-YUP KIM, JUNGHO LEE and JUN-HO OH HUBO Laboratory, Humanoid Robot Research Center Department of Mechanical Engineering,

More information

Velocity Based Stability Margins for Fast Bipedal Walking

Velocity Based Stability Margins for Fast Bipedal Walking Velocity Based Stability Margins for Fast Bipedal Walking Jerry E. Pratt 1 and Russ Tedrake 2 1 Florida Institute for Human and Machine Cognition jpratt@ihmc.us 2 Massachusettes Institute of Technology

More information

Robotics and Autonomous Systems

Robotics and Autonomous Systems Robotics and Autonomous Systems Lecture 4: Locomotion Simon Parsons Department of Computer Science University of Liverpool 1 / 57 Today 2 / 57 Motion Two aspects: Locomotion Kinematics Locomotion: What

More information

Walking Control Algorithm of Biped Humanoid Robot on Uneven and Inclined Floor

Walking Control Algorithm of Biped Humanoid Robot on Uneven and Inclined Floor J Intell Robot Syst (27) 48:457 484 DOI 1.17/s1846-6-917-8 Walking Control Algorithm of Biped Humanoid Robot on Uneven and Inclined Floor Jung-Yup Kim & Ill-Woo Park & Jun-Ho Oh Received: 31 July 26 /

More information

Mobile Robots (Legged) (Take class notes)

Mobile Robots (Legged) (Take class notes) Mobile Robots (Legged) (Take class notes) Legged mobile robots Mobile robots are robots which can move There are two types of mobile robots - Legged two, four, six and eight legs - Wheeled one, two, three

More information

An investigation of kinematic and kinetic variables for the description of prosthetic gait using the ENOCH system

An investigation of kinematic and kinetic variables for the description of prosthetic gait using the ENOCH system An investigation of kinematic and kinetic variables for the description of prosthetic gait using the ENOCH system K. OBERG and H. LANSHAMMAR* Amputee Training and Research Unit, University Hospital, Fack,

More information

Mecánica de Sistemas Multicuerpo:

Mecánica de Sistemas Multicuerpo: Universidad Pública de Navarra 12 de Noviembre de 2008 Departamento de Ingeniería Mecánica, Energética y de Materiales Mecánica de Sistemas Multicuerpo: Análisis de la Silla de Ruedas Triesférica y Dinámica

More information

Foot Placement in the Simplest Slope Walker Reveals a Wide Range of Walking Solutions

Foot Placement in the Simplest Slope Walker Reveals a Wide Range of Walking Solutions Foot Placement in the Simplest Slope Walker Reveals a Wide Range of Walking Solutions Pranav A. Bhounsule Abstract We show that the simplest slope walker can walk over wide combinations of step lengths

More information

Kenzo Nonami Ranjit Kumar Barai Addie Irawan Mohd Razali Daud. Hydraulically Actuated Hexapod Robots. Design, Implementation. and Control.

Kenzo Nonami Ranjit Kumar Barai Addie Irawan Mohd Razali Daud. Hydraulically Actuated Hexapod Robots. Design, Implementation. and Control. Kenzo Nonami Ranjit Kumar Barai Addie Irawan Mohd Razali Daud Hydraulically Actuated Hexapod Robots Design, Implementation and Control 4^ Springer 1 Introduction 1 1.1 Introduction 1 1.2 Walking "Machines"

More information

-Elastic strain energy (duty factor decreases at higher speeds). Higher forces act on feet. More tendon stretch. More energy stored in tendon.

-Elastic strain energy (duty factor decreases at higher speeds). Higher forces act on feet. More tendon stretch. More energy stored in tendon. As velocity increases ( ) (i.e. increasing Froude number v 2 / gl) the component of the energy cost of transport associated with: -Internal kinetic energy (limbs accelerated to higher angular velocity).

More information

Virtual Model Control: An Intuitive Approach for Bipedal Locomotion

Virtual Model Control: An Intuitive Approach for Bipedal Locomotion Jerry Pratt Chee-Meng Chew Ann Torres Peter Dilworth Gill Pratt Leg Laboratory Massachusetts Institute of Technology Cambridge, Massachusetts 2139, USA http://www.ai.mit.edu/projects/leglab/ Virtual Model

More information

The Design and Control of a Bipedal Robot with Sensory Feedback

The Design and Control of a Bipedal Robot with Sensory Feedback International Journal of Advanced Robotic Systems ARTICLE The Design and Control of a Bipedal Robot with Sensory Feedback Regular Paper Teck-Chew Wee 1,*, Alessandro Astolfi 1 and Xie Ming 2 1 Department

More information

arxiv: v1 [cs.ro] 6 May 2018

arxiv: v1 [cs.ro] 6 May 2018 Comparison Study of Nonlinear Optimization of Step Durations and Foot Placement for Dynamic Walking Wenbin Hu, Iordanis Chatzinikolaidis, Kai Yuan, and Zhibin Li arxiv:85.55v [cs.ro] 6 May 8 Abstract This

More information