A 3-TIER INFRASTRUCTURE: VIRTUAL-, MINI-, ONLINE-HUBO STAIR CLIMBING AS A CASE STUDY

Size: px
Start display at page:

Download "A 3-TIER INFRASTRUCTURE: VIRTUAL-, MINI-, ONLINE-HUBO STAIR CLIMBING AS A CASE STUDY"

Transcription

1 3-TIER INFRSTRUCTURE: VIRTUL-, MINI-, ONLINE-HUBO STIR CLIMBING S CSE STUDY Youngbum Jun Mechanical Engineering and Mechanics Drexel University Philadelphia, P, US yj55@drexel.edu Paul Oh Mechanical Engineering and Mechanics Drexel University Philadelphia, P, US paul@coe.drexel.edu BSTRCT This paper introduces a 3-tier infrastructure for humanoid research. Using the KIST humanoid Hubo-, virtual-, mini-, and online-hubo comprise an infrastructure to respectively prototype, test-and-evaluate, and verify-andvalidate algorithms. The resulting closed-loop design cycle promotes research that can reproduced and verified by the humanoid research community. This paper presents stair-climbing as a case study, thus demonstrating the efficacy of the 3-tier approach. Beyond the 3-tier infrastructure, the paper presents an effective climbing pattern generation and analytic inverse kinematics. This stairclimbing approach is prototyped in virtual-hubo, experimentally tested-and-evaluated on mini-hubo, and verifiedand-validated on online-hubo. KEY WORDS Virtual-Hubo, Mini-Hubo, Hubo, Stair Climbing, 3-tier infrastructure 1 Introduction In past two decades a lot of humanoid research papers have been published. Many researchers have simulated or built their own humanoid robots to verify and validate algorithms and control techinuqes. However, the current actual humanoid technology has not caught up with the achievements in such papers since there was a critical gap; platforms were not easily available, and mechanically and systematically different, and hence research was difficult to validate and hence results were hard to reproduce. In 7 the National Science Foundation in the United States awarded a grant that partnered merican and Korean roboticists to create a 3-tier infrastructure to stimulate and advance humanoid research 1. This infrastructure served to fill such critical gaps. To overcome this challenge, virtual-, mini- and online-hubo were constructed to respectively prototype, test-and-evaluate, and verify-and-validate humanoid-based research. Based on the full-sized KIST Hubo humanoid, virtual-hubo is a zero-to-low cost simulator, mini-hubo is a 17-inch scaled open-source robot that one can construct for less than 1, USD and online- 1 This project was supported by a US NSF Grant 736 Figure 1. 3-tier infrastructure: virtual-, mini-, online-hubo stair climbing Hubo is the full-sized robot (called Jaemi Hubo) that is tethered to a gantry and can be programmed and monitored using the Internet in order to be world-widely accessed (see Figure. 1). n integrated software called Conductor [1] was developed to access 3-tier infrastructure and enabled a wide range of investigators to gain entry into humanoid research without being overly hindered by cost or maintanence. This paper serves to demonstrate the efficacy of the 3-tier infrastructure in humanoid research. Firstly, one s algorithms are prototyped in virtual-hubo and then secondly, tested and evaluated on mini-hubo. Thirdly, the algorithms modified and tuned in cycling between these two steps are ultimately verified and validated with online- Hubo. Through testing on 3-tier infrastructure, one s ideas are strongly supported and totally reproducible on many humanoid research environments since that is proved on simulation, miniature humanoid, and full sized humanoid platform. Stair-climbing was selected as a case study because there is wealth of humanoid literature on the subject. However, it was not clear to the authors if particular approaches could be universally applied to other humanoids and stair setups. Virtual-, mini-, and online-hubo provided the tools to quickly decide what could work and if any customization of the algorithms would be needed. There are generally two approaches to humanoid stair-climbing literature. The first focuses on trajectory

2 generation. To overcome unmodeled dynamics Kajita s 3D linear inverted pendulum (3D-LIPM) is often employed []. For example, Huang et al in Singapore employ the 3D- LIMP and Webots to simulate a full-sized humanoid and use zero-moment point (ZMP [3]) preview control [4] to generate trajectories to walk forward on slopes [5]. Purdue University roboticists also employ Webots to simulate a HOP- humanoid. Similar to preview control, they employ a convolution sum and set stable region bounds by taking the third derivative of hip position modeled by a 3D- LIPM [6]. Researchers at Tsukuba use captured motion data to generate trajectories and simulate stair-climbing. Here, they decomposed the data into six phases, generate trajectories for each phase and then re-assemble the data for stair-climbing [7]. The second approach focuses on control techniques. KIST for example also employ a 3D-LIPM with cycloid algorithms. Using force/torque ankle sensor data, they employ an observer to compensate for errors between actual and desired ZMP. Only ankle joints are controlled and they experimentally demonstrate stair-climbing on Hubo [8]. In China, Fu et al experimentally demonstrate stair climbing on the THBIP-1 humanoid. Trajectories are manually designed and define stable regions. Instead of controlling the position of the center-of-mass, force sensors, gyros and accelerometers provide data to control hip and ankle joints [9]. Taiwanese researchers apply a fuzzy controller on a custom-built miniature humanoid. Here, foot placement phases are defined to climb stairs [1]. The authors of this paper are particularly interested in analytic solutions for trajectory-based approaches. The authors reproduced ZMP preview control [4] and real-time ankle controller for ZMP compensation [8] with Jacobian Pseudo-inverse Kinematics (IK) [11]. Based on insight gained from virtual-hubo prototyping, mini-hubo evaluation, and online-hubo verification the authors observed three main issues; Since unmodelled dynamics, ZMP preview control results in large forward momentum for long strides during the double-support phase. Phase for climbing motion is ambiguous in ZMP preview control. Jacobian pseudo-inverse IK is computationally poor that does not fit in the miniature humanoid. To resolve, cycloid velocity profiles [8] are combined with ZMP preview control and single-support phase () is decomposed into upward-single-support phase (U) and described in Section. n analytic IK solver is developed to improve computation efficiency in Section 3, that resolves the second issue. The experimental results with the algorithms finalized through 3-tier infrastructure are demonstrated in Section 4, that strongly support the author s proposal. The conclusion and future work are described in Section 5. Figure. Simplified humanoid model: 3D linear inverted pendulum Stair Climbing Pattern Generation.1 Center Of Mass Trajectory Since unmodelled dynamics in 3D-LIPM depicted in Figure., ZMP preview control results in large forward momentum for long strides during the double-support phase. That yields a robot falling down to the forward direction. To minimize the momentum in forward direction, cycloid function is used. First, one begins with the 3D-LIPM to yield a simple humanoid dynamics model []. Here, the robot is modeled as a point mass m of length l located at the humanoid s center-of-mass (COM). This results in an equation of motion in the X-direction ml θ = mglθ τ y (1) where g is the gravitational constant and τ y is the torque around Y -axis. ssuming that the height of the COM remains constant, then let z c = l where lθ is the X position of COM. Equation (1) then becomes z c g ẍ=x τ y mg The relationship between the X- and Y -directions for the COM (x com,y com ) and ZMP (x zmp,y zmp ) are given by and the ZMP in X- and Y -directions can be respectively defined as () x zmp = x com z c g ẍcom (3) y zmp = y com z c g ÿcom (4) Second, reference trajectories must be generated and a ZMP preview control [4] is used with optimal previewable control theory [1]. The result yields hip trajectories based on a given ZMP reference trajectory and the humanoid s dynamics. For this paper, only lateral hip trajectories are generated for reasons described in Section 1.

3 Hip Trajectory in Y direction from ZMP preview Hip trajectory in X direction by Cycloid lgorithm Yzmp Hipy 3 Hip in X from Cycloid lgorithm Hipx C Xzmp Distance between Foot B/ Step Distance, Forward ZMP trajectory B/ Walking Period, T = + T T1 T T3 T4 T5 T6 T7 Time Figure 3. ZMP previewer yields hip trajectory in Y - direction T T1 T T3 T4 Figure 5. Hip trajectory in forward direction using cycloid function Cycloid Function Comparison of the forward hip trajectory from ZMP preview and Cycloid when 1/3 stride of leg length 3 Hip in X from Cycloid lgorithm Hipx C Hipx P Xzmp mplitude, Step Distance, Foward ZMP trajectory Hip in X from ZMP preview T Period, T T T1 T T3 T4 Figure 4. Cycloid function: πt sin(πt) Figure 6. Hip trajectories generated by ZMP preview and cycloid algorithms For the Y -direction, Figure. 3 shows the hip trajectory for a given ZMP trajectory specified by the Double-Support Phase (), Single-Support Phase (), and the distance between each foot B. cycloid hip generation algorithm developed in [8] allows tuning velocity and hip positions. cycloid is a curve defined by the path of a point on the edge of a rolling wheel (Figure. 4). x cyc (t) represents this path over time x cyc = (π ft sin(π ft)) (5) π where is the amplitude and f is the frequency defined as 1 T when T is the period. To combine (5) with the ZMP equation in (3) for the X-direction, the second derivative of the cycloid function is needed ẍ cyc = π ((π f) sin(π ft)) (6) Equations (5) and (6) are combined x zmp = Wπ (Wπ ft (1+ z c g (π f) sin(π ft))) (7) where W is the weight value to control the acceleration of the hip in the double-support phase (), is the step distance, and f is T 1 when T = + and is the single-support phase. Figure. 5 shows the hip trajectory in X-direction using a cycloid algorithm for a given ZMP trajectory. The hip trajectories from the ZMP preview control and cycloid algorithm for X-direction are compared in Figure. 6. Here, is set to one-third of the leg length. Figure. 7 shows the velocity changes for the trajectories given in Figure. 6 thus illustrating the reduction in hip momentum when one employs cycloids versus ZMP preview control.. Climbing Motion of Hip For a given ZMP trajectory, the previous section derived hip trajectories in both the X- and Y -directions. For the stair climbing the vertical motion of hip should be defined and foot motion should be also derived from ZMP trajectory for stability. Different phases associated with human stair climbing are notionally depicted in Figure. 8. From this figure, one observes that person s body moves vertically between

4 Change of linear velocity in ZMP preview and Cycloid lgorithm Hip trajectory in upward direction (Z direction) 3 Hip Velocity in X from Cycloid lgorithm Xzmp Vel C Vel P Hip trajectory in Z Hipz Yzmp Step Distance & Velocity Vp Vc Vc=approximately /3 of Vp Hip Velocity in X from ZMP preview Stair Height, H 3H H H Lateral ZMP trajectory T T1 T T3 T4 U Walking Period = +U+ T T1 T T3 T4 Figure 7. Hip trajectories generated by ZMP preview and cycloid algorithms Figure 9. Vertical hip motion (Z-direction) Figure 8. Human stair-climbing phases Figure 1. Foot motion in the human walking model and. To capture this phenomena the authors define an upward single-support phase (U). Hip vertical travel (Z-direction) is shown in Figure. 9 for a given ZMP trajectory in the Y -direction for a climbing period T and stair height H. The U period can be determined from simulation or experimentally. In Figure. 9, the U period was set to half of the period. First-order linear interpolation was then applied to generate hip motions in the Z-direction..3 Foot Trajectory Humanoid feet are the only body part that contact the ground when walking and hence play an important role in stability. However, their role in biped walking are often neglected. Through virtual-hubo prototyping, incorporating foot trajectories also improves stair-climbing performance. Figure. 1 depicts the foot-motion sequence. Sinusoids can be applied to design vertical foot positions (Zdirection) as in [8] [13]. By contrast, applying cycloids would provide foot position and minimize foot reaction forces when making ground contact. Such an approach needs three parameters: the duration; step distance in the X-direction; and the foot s maximum height. The first two parameters are obtained from the ZMP trajectory. The third parameter is defined manually. From concepts described in Section.1, (8) yields foot trajectories in the X-direction. Foot x = S d π (wt sin(wt )) (8) Equation (9) and (1) yield foot trajectories in the Z- directions when t < U and U < t, respectively. Foot z = H (wt sin(wt)) (9) π Foot z = H+ H (sin(wt) wt) (1) π where S d is the step distance in X-direction, w denotes π f, f = t 1, t is the duration, and H is the maximum foot motion height. When climbing stairs, stair height should be added to H in (9) as an offset. When added, the left and right foot trajectories in X- and Z-directions derived from (8) and (9) yield plots given in Figure. 11 and Figure. 1 for step distance and stair height SH.

5 The left and right foot trajectories in forward direction Xzmp Right Foot x Left Foot x 6 7 Torso Step Distance, Thigh Knee Yaw nkle 1 Pitch Roll T T1 T T3 Figure 11. Forward walking foot trajectories based on ZMP trajectory Figure 13. Joint configurations in legs of a humanoid Stair Height, SH SH SH The left and right foot trajectories in Z direction based on Hip motion in Z U Left foot in Z Right foot in Z Hip motion in Z Hip in Z Right Foot z Left Foot z Yaw Roll 4 (Back View) COM Thigh Roll Zc Pitch d Yt l leg Knee 1 l1 Ya nkle Roll Y Z Za T T1 T T3 Figure 1. Vertical left and right foot trajectories when stair climbing Figure 14. Joint configurations on walking in back-plane view 3 Vector Inverse Kinematics sketched in Figure. 13, a pair of humanoid legs typically consists of at least 13 degrees-of-freedom (DOF). Pattern generators typically solve the inverse kinematics (IK) for each leg (six DOF) and treat the hip as an end effector and foot as the origin. Computational costs often prevent direct control of hip position [8]-[1] [14]. One casually observes that people typically do not yaw their torso when walking straight. One explanation is perhaps the conserve angular momentum except when turning or intentionally taking long strides. Taking advantage of this zero yaw observation prescribes four constraints on the thighs: the angular momentum of yaw is zero; the upper body is always perpendicular to the ground; the bottom of foot is always parallel to the ground; and the height of COM is constant. With these contraints the three pitch angles and two roll axes in each leg can be analytically calculated in the vector space. This is important because these constraints allow real-time hip-position control without demanding extensive processing power. Figure. 14 shows the roll angles for the ankle θ 1 and thigh θ 4 in the back plane of the humanoid. Z a is the ankle height and equals Z f + l 1 where Z f is the foot height and l 1 is the ankle-to-foot length. The Y positions for the thigh Y t and hip Y h are related by Y t = Y h d. l leg denotes the D vector between the thigh and ankle joints. Through trigonometry θ 1 and θ 4 can be determined as θ 1 = 9 arccos((y t Y a )/ l leg )θ 4 = θ 1 (11) where l leg = (Z c Z a ) +(Y t Y a ) ll pitch angles can be calculated using the same approach. Figure. 15 shows the ankle θ, knee θ 3 and thigh θ 5 pitch angles. Let X, Y and Z symbols respectively denote joint positions X-, Y -, and Z-directions. Further, let the upper and lower leg link lengths be respectively denoted by l up and l low. l leg is the 3D vector between the thigh and ankle. pplying the law of cosines yields θ 3 = 18 arccos((l up+ l low l leg )/(lup l low )) (1)

6 5 COM (Xh,Yh,Zh) (Lateral View) Stair Climbing Trajectories for virtual, mini, online Hubo 3 Pitch Yaw Thigh (Xt,Yt,Zt) Roll l leg l up l Knee (Xk,Yk,Zk) llow l1 Distance Forward ZMP Trajectory Forward Hip Trajectory Forward foot Trajectory Lateral Hip Trajectory Foot Trajectory in Z Hip Motion in Z SD LD SH Lateral ZMP Trajectory nkle Z (Xa,Ya,Za) Y X LD Time (second) Figure 15. Joint configurations on walking in lateral-plane view Figure 16. Experimental results: Hip and foot trajectories θ 5 = 9 θ arccos((l up+ l leg l low )/(l up l leg )) (13) θ = 9 θ + arccos((l low + l leg l up )/(l low l leg ) (14) where l leg = (Z t Z a ) +(Y t Y a ) + X t X a ) θ = arccos((x t X a )/ l leg ) To compare computational times, calculations were performed on a dual core 3.37 GHz Pentium 4 running Matlab. Traditional Jacobian pseudo IK using damped least squares yielded joint angle calculations for 61 trajectory samples in.95 seconds. By contrast, calculation time was reduced more than 5% (.4 seconds) when yaw motions were constrained to zero. 4 Experimental Result from 3-tier Infrastructure tier Infrastructure Under the NSF grant that supports work in this project, the authors collaborator (Virgina Tech s RoMeLa Lab) designed mini-hubo, a DOF scaled version of the KIST Hubo, which stands.5 m tall and weighs 3 kg. The pair of legs consists of 13 DOF. The robot is equipped with an Intel tom 1.6 GHz processor and constructed with RX-8 Dynamixel servos, force/torque sensors at each ankle and communicates via USB and serial ports [13]. mini-hubo was designed to be open-sourced; plans for anyone to construct this robot are freely available on the web. Estimated construction costs are under 1, USD with less than 4 person-hours of machining and assembly time. Virtual-Hubo is the emulator component for the 3- tier infrastructure. Open Dynamics Engine (ODE)-based software allows one to better visualize how motion algorithms perform. graphical environment allows one to rapidly prototype and visualize algorithms that will be applied to mini- and online-hubo. This emulator can import CD models and employs the Webot ODE. The platform-independent architecture allows algorithms that run on virtual-hubo to port seamlessly to mini- and online- Hubo[1]. The platform-independent architecture, called Conductor [1], was developed by our group in order to allow algorithms that run on virtual-hubo to port seamlessly to mini- and online-hubo. This is accomplished by representing the control elements of the system in terms of a state variable approach, which is easily adjustable between the three architectures. The elements of control which are platform specific (motor drivers, calibration, etc) are left to lower level drivers that are easily interchangeable. Online-Hubo is built on top of the well-known full-sized humanoid, Hubo-, developed by HuboLab in KIST. The combination of remotely accessible and controllable software, and a powered safety harness allows the Hubo to be operated remotely. Researchers can access the robot anywhere, and monitor its motion via the Internet in realtime. With the Conductor, a program demonstated in Virtual-Hubo can be immediately loaded to online-hubo to verify its performance. 4. Virtual-, Mini-, online-hubo Experiments Based on the pattern generation algorithms with vector IK demonstrated in Section. and Section. 3, all trajectories applied to 3-tiers are generated in Figure. 16. The computational time in IK for each sample takes. miliseconds. That allows us to generate trajectories for and to control virtual-, mini-, and online-hubo on real time, that are run on 5Hz, 5Hz, and 1Hz respectively. It implies that the proposed algorithms overcome a limitation that Hubo- had in the previous stair climbing algorithms, which used joint trajectories generated on offline. The experiments run on 3-tiers are shown in Figure. 17, 18, and 19 as an image sequence. The stair height was set up as same as the ratio of dimension bewtween mini- and online-hubo. In the experiments, however, we tuned the momentum down for online-hubo since virtual-

7 Figure 17. Mini-Hubo simulation in Webots Figure 19. Hubo Experimental result: stair climbing of Mini- Figure 18. Hubo Experimental result: stair climbing of Mini- This paper presented stair-climbing as the authors first case study. lgorithms were rapidly prototyped in simulation, test-and-evaluated on mini-hubo, and then verified-and-validated on online-hubo. The results are promising and serve to demonstrate the efficacy of the 3- tier infrastructure and algorithms reproducible and reliable. Future work entails completion online-hubo ready to open to the public. The authors are currently working to post the simulator and open-source mini-hubo plans for free download. The team is also working to provide access to Jaemi Hubo (online-hubo) so roboticists can control the robot over the Internet. The net effect provides a universally accessible infrastructure; case studies like stair-climbing provide a context to begin analytical dialogs, reproduce experiments, identify best practices and ultimately lay foundational theory that vertical advances the state-of-the-art in humanoid research. and mini-hubo are one third in dimension but almost one fifteen in weight. 5 Conclusion and Future Work Until recently, the barrier to enter humanoid research was very high; full-sized humanoids were difficult to acquire and maintain. This made reproducing humanoid experiments and validating approaches by other roboticists next to impossible. In recent years, both simulators and miniature humanoids became widely available. Such platforms could serve as tools to rapidly prototype and test-andevaluate algorithms. Using such platforms to overcome barriers and benchmark humanoid research approaches embarked the authors on a 5-year project. The project develops a 3-tier infrastructure consisting of virtual-, mini- and online-hubo. References [1] Sherbert, R., Oh, P.Y., Conductor: Controller Development Framework for High Degree of Freedom System, IEEE Int. Conf. on Intelligent Robots and Systems (IROS11), San Francisco, US, Oct 11 (accepted to be published). [] Kajita, S., Kanehiro, F., Kaneko, K., Yokoi, K., Hirukawa, H., The 3D Linear Inverted Pendulum Model: Simple Modeling for a Biped Walking Pattern Generation, IEEE Int. Conf. on Intelligent Robots and Systems (IROS1), V1, pp.39-46, Oct. 1. [3] Vukobratovic, M., Borovac, B., Zero-Moment Point- Thirty five years of its life, Int.Journal of Humanoid Robotics, V1 N1, pp , 4

8 [4] Kajita, S., Kanehiro, F., Kaneko, K., Fujiwara, K., Harada, K., Yokoi, K., Hirukawa, H., Biped Walking Pattern Generation Using Preview Control of the Zero-Moment-Point, IEEE Int. Conf. on Robotics and utomation (ICR3), Taipei, Taiwan, V, pp , Sept. 3 [5] Huang, W., Chew, C.M., Zheng, Y., Hong, G.S. Pattern Generation for Bipedal Walking on Slopes and Stairs,IEEE Humanoids (Humanoids8), pp 5-1, Daejeon, Korea, Dec. 8 [6] Park, H.., li, M.., Lee, C.S.G., Convolution- Sum-Based Generation of Walking Patterns for Uneven Terrains,IEEE Humanoids (Humanoids1),pp , Nashville, TN, Dec. 1 [7] Kim, S.H., Sankai Y., Stair Climbing Task of Humanoid Robot by Phase Composition and Phase Sequence,IEEE Int. Workshop on Robots and Human Interactive Communication, pp , 5 [8] Kim, J.Y., Park, I.W., Oh, J.H., Realization of Dynamic Stair Climbing for Biped Humanoid Robot Using Force/Torque Sensors,Journal of Intelligent and Robotic Systems, V56, I4, Nov. 9 [9] Fu, C., Chen, K., Gait Synthesis and Sensory Control of Stair Climbing for a Humanoid Robot, IEEE Tran. on Industrial Electronics, V55 N5, pp , May 8 [1] Li, T.H.S., Su, Y.T., Kuo, C.H., Chen, C.Y., Hsu, C.L., Lu, M.F., Stair-Climbing Control of Humanoid Robot using Force and ccelerometer Sensors, SICE nnual Conference, Kagawa Univ, Japen, Sept. 7 [11] S.R.Buss, Introduction to Inverse Kinematics with Jacobian Transpose, Pseudoinverse and Damped Least Squares methods,dept. Mathematics, Univ. of California, San Diego, 9 [1] Katayama, T., Ohki, T., Inoue, T., Kato, T., Design of an Optimal Controller for a Discrete-Time System Subject to Previewable Demand, Int Journal of Control, V41, I3, pp , March 1985 [13] Jun, Y.B., Ellenberg, R., Oh, P.Y., Realiztion of Miniature Humanoid for Obstacle voidance with Real-Time ZMP Preview Control Used for Full-Sized Humanoid, IEEE Humanoids (Humanoids1),pp , Nashville, TN, Dec. 1 [14] Jun, Y.B., Ellenberg, R., and Oh, P.Y., From Concept to Realization: Designing Miniature Humanoids for Running 6th Cybernetics and Information Technologies, System and pplication (CITS), Orlando, US, July 9

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

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 Walking Pattern Generator for Biped Robots on Uneven Terrains

A Walking Pattern Generator for Biped Robots on Uneven Terrains A Walking Pattern Generator for Biped Robots on Uneven Terrains Yu Zheng, Ming C. Lin, Dinesh Manocha Albertus Hendrawan Adiwahono, Chee-Meng Chew Abstract We present a new method to generate biped walking

More information

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

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

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

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

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

Feasibility and Optimization of Fast Quadruped Walking with One- Versus Two-at-a-Time Swing Leg Motions for RoboSimian

Feasibility and Optimization of Fast Quadruped Walking with One- Versus Two-at-a-Time Swing Leg Motions for RoboSimian Feasibility and Optimization of Fast Quadruped Walking with One- Versus Two-at-a-Time Swing Leg Motions for RoboSimian Peter Ha and Katie Byl Abstract This paper presents two planning methods for generating

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

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

Modelling and simulation of the humanoid robot HOAP-3 in the OpenHRP3 platform

Modelling and simulation of the humanoid robot HOAP-3 in the OpenHRP3 platform Modelling and simulation of the humanoid robot -3 in the 3 platform C.A. Monje, P. Pierro, T. Ramos, M. González-Fierro, C. Balaguer. Abstract The aim of this work is to model and simulate the humanoid

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

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

Learning Footstep Prediction from Motion. capture

Learning Footstep Prediction from Motion. capture Learning Footstep Prediction from Motion Capture Andreas Schmitz, Marcell Missura, and Sven Behnke University of Bonn, Computer Science VI, Autonomous Intelligent Systems Roemerstr. 164, 53117 Bonn, Germany

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

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

Motion Planning of Ladder Climbing for Humanoid Robots

Motion Planning of Ladder Climbing for Humanoid Robots Motion Planning of Ladder Climbing for Humanoid Robots Yajia Zhang, Jingru Luo, Kris Hauser School of Informatics & Computing Indiana University Bloomington, IN 47408 Robert Ellenberg, Paul Oh Mechanical

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

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

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

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

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

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

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

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

Online Generation of Humanoid Walking Motion based on a Fast. The University of Tokyo, Tokyo, Japan,

Online Generation of Humanoid Walking Motion based on a Fast. The University of Tokyo, Tokyo, Japan, Online Generation of Humanoid Walking Motion based on a Fast Generation Method of Motion Pattern that Follows Desired ZMP Koichi Nishiwaki 1, Satoshi Kagami 2,Yasuo Kuniyoshi 1, Masayuki Inaba 1,Hirochika

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

Biped Walking Pattern Generation by using Preview Control of Zero-Moment Point

Biped Walking Pattern Generation by using Preview Control of Zero-Moment Point Proceedings of the 23 IEEE International Conference on Robotics & Automation Taipei, Taiwan, September 4-9, 23 Biped Walking Pattern Generation by using Preview Control of Zero-Moment Point Shuuji KAJITA,

More information

The Mathematical Model and Computer Simulation of a Quadruped Robot

The Mathematical Model and Computer Simulation of a Quadruped Robot Research Experience for Undergraduates 2014 Milwaukee School of Engineering National Science Foundation Grant June 1- August 8, 2014 The Mathematical Model and Computer Simulation of a Quadruped Robot

More information

Dynamic State Estimation using Quadratic Programming

Dynamic State Estimation using Quadratic Programming 214 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS 214) September 14-18, 214, Chicago, IL, USA Dynamic State Estimation using Quadratic Programming X Xinjilefu, Siyuan Feng and

More information

Design of a Three-Axis Rotary Platform

Design of a Three-Axis Rotary Platform Design of a Three-Axis Rotary Platform William Mendez, Yuniesky Rodriguez, Lee Brady, Sabri Tosunoglu Mechanics and Materials Engineering, Florida International University 10555 W Flagler Street, Miami,

More information

Climbing Stairs with Humanoid Robots

Climbing Stairs with Humanoid Robots Lehrstuhl für Angewandte Mechnik Fakultät für Maschinenwesen Technische Universität München Climbing Stairs with Humanoid Robots Semesterarbeit an der Fakultät für Maschinenwesen der Technischen Universität

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

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

A CONTROL ARCHITECTURE FOR DYNAMICALLY STABLE GAITS OF SMALL SIZE HUMANOID ROBOTS. Andrea Manni,1, Angelo di Noi and Giovanni Indiveri 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

More information

Human Motion Tracking Control with Strict Contact Force Constraints for Floating-Base Humanoid Robots

Human Motion Tracking Control with Strict Contact Force Constraints for Floating-Base Humanoid Robots 2013 13th IEEE-RAS International Conference on Humanoid Robots (Humanoids). October 15-17, 2013. Atlanta, GA Human Motion Tracking Control with Strict Contact Force Constraints for Floating-Base Humanoid

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

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

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

Documents. OpenSim Tutorial. March 10, 2009 GCMAS Annual Meeting, Denver, CO. Jeff Reinbolt, Ajay Seth, Scott Delp. Website: SimTK.

Documents. OpenSim Tutorial. March 10, 2009 GCMAS Annual Meeting, Denver, CO. Jeff Reinbolt, Ajay Seth, Scott Delp. Website: SimTK. Documents OpenSim Tutorial March 10, 2009 GCMAS Annual Meeting, Denver, CO Jeff Reinbolt, Ajay Seth, Scott Delp Website: SimTK.org/home/opensim OpenSim Tutorial Agenda 10:30am 10:40am Welcome and goals

More information

Real Time Biped Walking Gait Pattern Generator for a Real Robot

Real Time Biped Walking Gait Pattern Generator for a Real Robot Real Time Biped Walking Gait Pattern Generator for a Real Robot Feng Xue 1, Xiaoping Chen 1, Jinsu Liu 1, and Daniele Nardi 2 1 Department of Computer Science and Technology, University of Science and

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

Dynamic Simulation of a KUKA KR5 Industrial Robot using MATLAB SimMechanics

Dynamic Simulation of a KUKA KR5 Industrial Robot using MATLAB SimMechanics Dynamic Simulation of a KUKA KR5 Industrial Robot using MATLAB SimMechanics Arun Dayal Udai, C.G Rajeevlochana, Subir Kumar Saha Abstract The paper discusses a method for the dynamic simulation of a KUKA

More information

Generalizations of the Capture Point to Nonlinear Center of Mass Paths and Uneven Terrain

Generalizations of the Capture Point to Nonlinear Center of Mass Paths and Uneven Terrain Generalizations of the Capture Point to Nonlinear Center of Mass Paths and Uneven Terrain Oscar E. Ramos and Kris Hauser Abstract The classical Capture Point (CP technique allows biped robots to take protective

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. Ateson *, Jessica K. Hodgins *, Darrin C. Bentivegna *,** and Sung Ju Cho * * Robotics

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

Sound and fast footstep planning for humanoid robots

Sound and fast footstep planning for humanoid robots Sound and fast footstep planning for humanoid robots Nicolas Perrin, Olivier Stasse, Léo Baudouin, Florent Lamiraux, Eiichi Yoshida Abstract In this paper we present some concepts for sound and fast footstep

More information

Leg Motion Primitives for a Humanoid Robot to Imitate Human Dances

Leg Motion Primitives for a Humanoid Robot to Imitate Human Dances Leg Motion Primitives for a Humanoid Robot to Imitate Human Dances Shinichiro Nakaoka 1, Atsushi Nakazawa 2, Kazuhito Yokoi 3 and Katsushi Ikeuchi 1 1 The University of Tokyo,Tokyo, Japan (nakaoka@cvl.iis.u-tokyo.ac.jp)

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

An Optimal Planning of Falling Motions of a Humanoid Robot

An Optimal Planning of Falling Motions of a Humanoid Robot Proceedings of the 27 IEEE/RSJ International Conference on Intelligent Robots and Systems San Diego, CA, USA, Oct 29 - Nov 2, 27 TuB5.3 An Optimal Planning of Falling Motions of a Humanoid Robot Kiyoshi

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

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

A simple example. Assume we want to find the change in the rotation angles to get the end effector to G. Effect of changing s

A simple example. Assume we want to find the change in the rotation angles to get the end effector to G. Effect of changing s CENG 732 Computer Animation This week Inverse Kinematics (continued) Rigid Body Simulation Bodies in free fall Bodies in contact Spring 2006-2007 Week 5 Inverse Kinematics Physically Based Rigid Body Simulation

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

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

Intuitive and Flexible User Interface for Creating Whole Body Motions of Biped Humanoid Robots

Intuitive and Flexible User Interface for Creating Whole Body Motions of Biped Humanoid Robots The 2010 IEEE/RSJ International Conference on Intelligent Robots and Systems October 18-22, 2010, Taipei, Taiwan Intuitive and Flexible User Interface for Creating Whole Body Motions of Biped Humanoid

More information

Motion Capture & Simulation

Motion Capture & Simulation Motion Capture & Simulation Motion Capture Character Reconstructions Joint Angles Need 3 points to compute a rigid body coordinate frame 1 st point gives 3D translation, 2 nd point gives 2 angles, 3 rd

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

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

Operation Trajectory Control of Industrial Robots Based on Motion Simulation

Operation Trajectory Control of Industrial Robots Based on Motion Simulation Operation Trajectory Control of Industrial Robots Based on Motion Simulation Chengyi Xu 1,2, Ying Liu 1,*, Enzhang Jiao 1, Jian Cao 2, Yi Xiao 2 1 College of Mechanical and Electronic Engineering, Nanjing

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

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

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

Real-time gait planner for human walking using a lower limb exoskeleton and its implementation on Exoped robot

Real-time gait planner for human walking using a lower limb exoskeleton and its implementation on Exoped robot > REPLACE THIS LINE WITH YOUR PAPER IDENTIFICATION NUMBER (DOUBLE-CLICK HERE TO EDIT) < 1 Real-time gait planner for human walking using a lower limb exoskeleton and its implementation on Exoped robot

More information

Dynamics modeling of structure-varying kinematic chains for free-flying robots

Dynamics modeling of structure-varying kinematic chains for free-flying robots Dynamics modeling of structure-varying kinematic chains for free-flying robots Roberto Lampariello, Satoko Abiko, Gerd Hirzinger Institute of Robotics and Mechatronics German Aerospace Center (DLR) 8 Weßling,

More information

Evolutionary Motion Design for Humanoid Robots

Evolutionary Motion Design for Humanoid Robots Evolutionary Motion Design for Humanoid Robots Toshihiko Yanase Department of Frontier Informatics The University of Tokyo Chiba 277-8561, Japan yanase@iba.k.u-tokyo.ac.jp Hitoshi Iba Department of Frontier

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

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

Redundancy Resolution by Minimization of Joint Disturbance Torque for Independent Joint Controlled Kinematically Redundant Manipulators

Redundancy Resolution by Minimization of Joint Disturbance Torque for Independent Joint Controlled Kinematically Redundant Manipulators 56 ICASE :The Institute ofcontrol,automation and Systems Engineering,KOREA Vol.,No.1,March,000 Redundancy Resolution by Minimization of Joint Disturbance Torque for Independent Joint Controlled Kinematically

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

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

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

Imitation Control for Biped Robot Using Wearable Motion Sensor

Imitation Control for Biped Robot Using Wearable Motion Sensor Imitation Control for Biped Robot Using Wearable Motion Sensor Tao Liu e-mail: liu.tao@kochi-tech.ac.jp Yoshio Inoue Kyoko Shibata Department of Intelligent Mechanical Systems Engineering, Kochi University

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

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

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

Development of Vision System on Humanoid Robot HRP-2

Development of Vision System on Humanoid Robot HRP-2 Development of Vision System on Humanoid Robot HRP-2 Yutaro Fukase Institute of Technology, Shimizu Corporation, Japan fukase@shimz.co.jp Junichiro Maeda Institute of Technology, Shimizu Corporation, Japan

More information

Table of Contents Introduction Historical Review of Robotic Orienting Devices Kinematic Position Analysis Instantaneous Kinematic Analysis

Table of Contents Introduction Historical Review of Robotic Orienting Devices Kinematic Position Analysis Instantaneous Kinematic Analysis Table of Contents 1 Introduction 1 1.1 Background in Robotics 1 1.2 Robot Mechanics 1 1.2.1 Manipulator Kinematics and Dynamics 2 1.3 Robot Architecture 4 1.4 Robotic Wrists 4 1.5 Origins of the Carpal

More information

Ann L. Torres. at the. June others the right to do so.

Ann L. Torres. at the. June others the right to do so. Virtual Model Control of a Hexapod Walking Robot by Ann L. Torres Submitted to the Department of Mechanical Engineering in partial fulllment of the requirements for the degree of Bachelor of Science in

More information

Intermediate Desired Value Approach for Continuous Transition among Multiple Tasks of Robots

Intermediate Desired Value Approach for Continuous Transition among Multiple Tasks of Robots 2 IEEE International Conference on Robotics and Automation Shanghai International Conference Center May 9-3, 2, Shanghai, China Intermediate Desired Value Approach for Continuous Transition among Multiple

More information

Inverse Kinematics Analysis for Manipulator Robot With Wrist Offset Based On the Closed-Form Algorithm

Inverse Kinematics Analysis for Manipulator Robot With Wrist Offset Based On the Closed-Form Algorithm Inverse Kinematics Analysis for Manipulator Robot With Wrist Offset Based On the Closed-Form Algorithm Mohammed Z. Al-Faiz,MIEEE Computer Engineering Dept. Nahrain University Baghdad, Iraq Mohammed S.Saleh

More information

INSTITUTE OF AERONAUTICAL ENGINEERING

INSTITUTE OF AERONAUTICAL ENGINEERING Name Code Class Branch Page 1 INSTITUTE OF AERONAUTICAL ENGINEERING : ROBOTICS (Autonomous) Dundigal, Hyderabad - 500 0 MECHANICAL ENGINEERING TUTORIAL QUESTION BANK : A7055 : IV B. Tech I Semester : MECHANICAL

More information

Leg Motion Primitives for a Dancing Humanoid Robot

Leg Motion Primitives for a Dancing Humanoid Robot Leg Motion Primitives for a Dancing Humanoid Robot Shinichiro Nakaoka, Atsushi Nakazawa, Kazuhito Yokoi and Katsushi Ikeuchi Institute of Industrial Science, The University of Tokyo 4-6-1 Komaba, Meguro-ku,

More information

Human Gait Recognition Using Bezier Curves

Human Gait Recognition Using Bezier Curves Human Gait Recognition Using Bezier Curves Pratibha Mishra Samrat Ashok Technology Institute Vidisha, (M.P.) India Shweta Ezra Dhar Polytechnic College Dhar, (M.P.) India Abstract-- Gait recognition refers

More information

Humanoid Robotics. Inverse Kinematics and Whole-Body Motion Planning. Maren Bennewitz

Humanoid Robotics. Inverse Kinematics and Whole-Body Motion Planning. Maren Bennewitz Humanoid Robotics Inverse Kinematics and Whole-Body Motion Planning Maren Bennewitz 1 Motivation Plan a sequence of configurations (vector of joint angle values) that let the robot move from its current

More information

Experimental Evaluation of the Dynamic Simulation of Biped Walking of Humanoid Robots

Experimental Evaluation of the Dynamic Simulation of Biped Walking of Humanoid Robots Proceedings of the 2003 IEEE International Conference on Robotics & Automation Taipei, Taiwan, September 14-19, 2003 Experimental Evaluation of the Dynamic Simulation of Biped Walking of Humanoid Robots

More information

Simultaneous Tracking and Balancing of Humanoid Robots for Imitating Human Motion Capture Data

Simultaneous Tracking and Balancing of Humanoid Robots for Imitating Human Motion Capture Data The 2009 IEEE/RSJ International Conference on Intelligent Robots and Systems October 11-15, 2009 St. Louis, USA Simultaneous Tracking and Balancing of Humanoid Robots for Imitating Human Motion Capture

More information

Fast foot prints re-planning and motion generation during walking in physical human-humanoid interaction

Fast foot prints re-planning and motion generation during walking in physical human-humanoid interaction Fast foot prints re-planning and motion generation during walking in physical human-humanoid interaction Olivier Stasse, Paul Evrard, Nicolas Perrin, Nicolas Mansard, Abderrahmane Kheddar Abstract In this

More information

Synthesis of Controllers for Stylized Planar Bipedal Walking

Synthesis of Controllers for Stylized Planar Bipedal Walking Synthesis of Controllers for Stylized Planar Bipedal Walking Dana Sharon, and Michiel van de Panne Department of Computer Science University of British Columbia Vancouver, BC, V6T 1Z4, Canada {dsharon,van}@cs.ubc.ca

More information

Biped Walking Control Based on Hybrid Position/Force Control

Biped Walking Control Based on Hybrid Position/Force Control The 29 IEEE/RSJ International Conference on Intelligent Robots and Systems October -5, 29 St. Louis, USA Biped Walking Control Based on Hybrid Position/Force Control Thomas Buschmann, Sebastian Lohmeier

More information

Humanoid Robotics. Inverse Kinematics and Whole-Body Motion Planning. Maren Bennewitz

Humanoid Robotics. Inverse Kinematics and Whole-Body Motion Planning. Maren Bennewitz Humanoid Robotics Inverse Kinematics and Whole-Body Motion Planning Maren Bennewitz 1 Motivation Planning for object manipulation Whole-body motion to reach a desired goal configuration Generate a sequence

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

Computers and Mathematics with Applications. Gait detection based stable locomotion control system for biped robots

Computers and Mathematics with Applications. Gait detection based stable locomotion control system for biped robots Computers and Mathematics with Applications 64 (2012) 1431 1440 Contents lists available at SciVerse ScienceDirect Computers and Mathematics with Applications journal homepage: www.elsevier.com/locate/camwa

More information

INVERSE KINEMATICS ANALYSIS OF A 5-AXIS RV-2AJ ROBOT MANIPULATOR

INVERSE KINEMATICS ANALYSIS OF A 5-AXIS RV-2AJ ROBOT MANIPULATOR www.arpnjournals.com INVERSE KINEMATICS ANALYSIS OF A 5-AXIS RV-2AJ ROBOT MANIPULATOR Mohammad Afif Ayob 1a, Wan Nurshazwani Wan Zakaria 1b, Jamaludin Jalani 2c, Mohd Razali Md Tomari 1d 1 ADvanced Mechatronics

More information

Humanoid Robotics. Monte Carlo Localization. Maren Bennewitz

Humanoid Robotics. Monte Carlo Localization. Maren Bennewitz Humanoid Robotics Monte Carlo Localization Maren Bennewitz 1 Basis Probability Rules (1) If x and y are independent: Bayes rule: Often written as: The denominator is a normalizing constant that ensures

More information

LOCOMOTION AND BALANCE CONTROL OF HUMANOID ROBOTS WITH DYNAMIC AND KINEMATIC CONSTRAINTS. Yu Zheng

LOCOMOTION AND BALANCE CONTROL OF HUMANOID ROBOTS WITH DYNAMIC AND KINEMATIC CONSTRAINTS. Yu Zheng LOCOMOTION AND BALANCE CONTROL OF HUMANOID ROBOTS WITH DYNAMIC AND KINEMATIC CONSTRAINTS Yu Zheng A dissertation submitted to the faculty of the University of North Carolina at Chapel Hill in partial fulfillment

More information

Pick and Place Robot Simulation

Pick and Place Robot Simulation Pick and Place Robot Simulation James Beukers Jordan Jacobson ECE 63 Fall 4 December 6, 4 Contents Introduction System Overview 3 3 State Space Model 3 4 Controller Design 6 5 Simulation and Results 7

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