Design of a Compliant Bipedal Walking Controller for the DARPA Robotics Challenge

Size: px
Start display at page:

Download "Design of a Compliant Bipedal Walking Controller for the DARPA Robotics Challenge"

Transcription

1 Design of a Compliant Bipedal Walking Controller for the DARPA Robotics Challenge Michael A. Hopkins, Robert J. Griffin, Alexander Leonessa *, Brian Y. Lattimer and Tomonari Furukawa Abstract This paper provides an overview of the bipedal walking controller implemented on ESCHER, a new torquecontrolled humanoid designed by Virginia Tech to compete in the DARPA Robotics Challenge (DRC). The robot s compliant control approach relies on an optimization-based inverse dynamics solver proposed in a previous publication. This work presents two unique features to improve stability on soft and uncertain terrain, developed in preparation for the dirt track and stairs task at the DRC Finals. First, a step adjustment algorithm is introduced to modify the swing foot position based on the divergent component of motion (DCM) error. Second, a simple heuristic is introduced to improve stability on compliant surfaces such as dirt and grass by modifying the design of the center of pressure (CoP) trajectory. The proposed approach is validated through DRC-related experiments demonstrating the robot s ability to climb stairs and traverse soft terrain. I. INTRODUCTION As bipeds, humanoid robots have the potential to achieve excellent mobility in natural and man-made environments, ideally matching the robustness and versatility of humans. The DARPA Robotic Challenge (DRC) helped bring a new generation of bipedal walking controllers to real hardware systems. Nevertheless, the high risk of failure at the competition indicates that a number of challenges still remain before bipeds can reliably negotiate difficult real-world scenarios. In [1], the authors presented an optimization-based wholebody controller enabling the THOR humanoid to walk on flat terrain using series elastic actuation. In preparation for the DRC, this approach was ported to ESCHER, a new 1.8 m tall humanoid developed at Virginia Tech (see Fig. 1). This paper provides an overview of the final bipedal walking controller used at competition, including a discussion of design considerations related to the dirt track and stairs task. The presented controls approach is an iteration of a previously published design which relies on divergent component of motion (DCM) tracking to stabilize the centroidal dynamics [1 3]. Two unique features are introduced to improve stability on soft and uncertain terrain. First, a new step adjustment algorithm is proposed to modify the swing foot trajectory during the single support phase using a simple heuristic based on the instantaneous DCM tracking error. Second, a simple, yet surprisingly effective modification to the nominal center of pressure (CoP) trajectory is introduced to reduce tracking errors on soft terrain. The proposed approach is verified through a variety of walking and push recovery experiments conducted using the ESCHER humanoid. The authors are with the Terrestrial Robotics, Engineering & Controls Laboratory (TREC) at Virginia Tech. ( robert.griffin@vt.edu) * This material is based upon work supported by (while serving at) the National Science Foundation. Fig. 1. Left: THOR humanoid walking on the Ex-USS Shadwell as part of the ONR Shipboard Autonomous Firefighting Robot (SAFFiR) program (photo courtesy of Virginia Tech / Logan Thomas). Right: ESCHER humanoid walking on the dirt track at the DARPA Robotics Challenge Finals (photo courtesy of DARPA). II. RELATED WORK A number of top-performing DRC teams developed compliant whole-body control strategies to enable the Atlas humanoid, supplied by Boston Dynamics, to traverse the final course [4 6]. As in [7 10], these approaches compute admissible joint torque and acceleration setpoints for whole-body control by solving an efficient convex optimization based on the rigid body dynamics. Feng et al. developed a hybrid inverse dynamics and inverse kinematics solver to enable the Atlas robot to walk on uneven terrain [4]. Kuindersma et al. stabilized the walking gait by minimizing an LQR cost function based on the zero moment point (ZMP) [5]. Johnson et al. and Koolen et al. tracked an instantaneous capture point (ICP) trajectory using an approach similar to the DCM-based controller presented in this paper [6, 11]. While several authors have proposed methods to improve walking on soft terrain including grass and sand [12, 13], experimental results are limited. Online adjustment of the target foothold position is a well-known approach to increase stability in response to external disturbances and unmodeled terrain features. A number of publications have presented reactive stepping strategies based on the linear inverted pendulum dynamics [14 16]. Englsberger et al. proposed a method to determine the upcoming foothold position given the desired DCM position at the end of the next step [17]. Unlike the method presented here, the authors computed the step adjustment based on the extrapolated DCM position at the time of heel-strike.

2 A. Hardware Design III. DESIGN AND MODELING In preparation for the 2013 DRC Trials, Virginia Tech developed the THOR humanoid, a 63 kg prototype platform featuring a compliant lower body with human-like range of motion [18]. The increased autonomy and run-time requirements of the DRC Finals spurred a design iteration leading to the development of ESCHER, the Electric Series Compliant Humanoid for Emergency Response. At 77 kg, the revised design features a new upper body with 11 DoF manipulators from HDT Global and onboard power and computing for extended operation. The hip pitch and knee assemblies were also upgraded to achieve the necessary output torque for locomotion on uneven terrain. Like its predecessor, ESCHER features custom linear series elastic actuators, enabling compliant control of all 12 degrees of freedom (DoF) in the lower body [19]. A titanium leaf spring is mounted in series with the actuator load to increase shock tolerance and decrease mechanical impedance. In-line load cell sensors provide direct force measurements to enable high-performance torque and impedance control of the hip, knee, and ankle joints. B. Dynamic Models As in [4 6], the presented controls approach employs a rigid body model to approximate the whole-body dynamics of an articulated humanoid. Assuming each joint behaves like an ideal torque source, the floating-base rigid body equations of motion are given by [ ] 0 = H q + C J T c f c, (1) τ where τ R n is the vector of joint torques, q R n+6 is the vector of generalized coordinates, and f c R 3 is the vector of external forces acting at each contact point, c = 1... N, with corresponding Jacobian, J c. Here H and C represent the joint-space inertia matrix and vector of centrifugal, Coriolis, and gravity torques, respectively. As in [9], approximate no-slip conditions are expressed by constraining the acceleration of each contact point using the equality, J c q + J c q = 0. The controls approach presented in Section IV makes extensive use of the divergent component of motion (DCM) to stabilize the centroidal dynamics of the rigid body system during walking. The DCM represents a linear transformation of the CoM state that partitions the second-order linear inverted pendulum dynamics into coupled first-order systems [17, 20]. Appropriate planning of the DCM can be used to ensure that the CoM is stabilizable following one or more steps. Assuming a constant CoM height, the closely related ICP defines the two-dimensional point at which the centroidal moment pivot (CMP) must be placed for the CoM to come to a complete rest [14], whereas the DCM defines the three-dimensional point at which the CoM converges. Using the time-varying formulation presented in [2], the DCM is defined as ξ = x + 1 ẋ, (2) ω Fig. 2. Left: DCM dynamics and external forces acting on an articulated humanoid. Right: Lateral step adjustment based on the estimated DCM error. Here r foot,r and r foot,r are the nominal and adjusted swing foot positions. where x R 3 is the CoM position and ω(t) > 0 is the timevarying natural frequency of the transformed CoM dynamics, ẋ = ω (ξ x). The coupled first-order DCM dynamics are given by ( ξ = ω ω ) (ξ r vrp ), (3) ω where r vrp R 3 represents the virtual repellent point (VRP) [2, 17]. Given (ω ω/ω) > 0, the VRP repels the DCM at a rate proportional to its distance; by definition, this threedimensional point maps the position of the CoM to the total linear momentum rate of change acting on the system, l = m(ω 2 ω)(x r vrp ). (4) Note that the linear momentum rate of change is related to the net contact force via Newton s second law, i.e. l = mẍ = f c + f g, where f g = [ 0, 0, mg ] T is the force of gravity and m is the total mass of the robot. The various reference points related to the DCM dynamics are illustrated in Fig. 2, including the enhanced centroidal moment pivot (ecmp) which maps the CoM position to the net contact force, f c = m(ω 2 ω)(x r ecmp ) [2, 17]. The ecmp is typically collocated with the center of pressure (CoP) in the robot s base of support to ensure that the line of action passes through the CoM. This results in a net horizontal angular momentum rate of change of zero. Note that the VRP lies directly above the ecmp with a vertical offset of z vrp = g/(ω 2 ω), determined by the gravitational constant and natural frequency [2]. Thus, if ω = 0, the natural frequency is given by ω = g IV. CONTROLS APPROACH z vrp. Figure 3 includes a high-level block diagram of the bipedal walking controller developed for the ESCHER humanoid. The presented controls approach is an extension of the compliant locomotion framework described in [1]. This section provides a summary of the overall design including a new step adjustment algorithm based on the DCM dynamics.

3 Fig. 3. High-level block diagram of ESCHER s stepping controller. Note that some control paths have been omitted to improve readability. A. State Machine Single-step and multi-step behaviors are implemented using the finite state machine depicted on the far left of Fig. 3 which transitions between various contact phases including double support, toe-off, single support, and heel-strike. In double support, both feet are assumed to be in contact with the surface. If an ankle or knee pitch limit is encountered by the predefined swing foot prior to single support, the robot transitions to a reactive toe-off state to compensate for the leg range of motion limits. Once the heel is unloaded, the swing foot rotates about the toe contact points, shifting the ankle pitch away from the soft limit. During single support, the swing foot travels to a new foothold position. After a predetermined duration, the state machine transitions to heelstrike, at which point the swing foot is lowered at a constant velocity until it contacts the ground and settles into a new foothold pose. When the foot is sufficiently loaded, the state machine transitions back to double support. B. Task-Space Planning The step controller obtains desired foothold poses and step durations from a footstep queue that is continuously populated by a high-level planner. As illustrated in Fig. 3, several mid-level planners are defined to compute task-space reference trajectories for the swing foot, pelvis, and DCM at the beginning of each double support phase. The DCM reference trajectory is generated using the realtime numeric planner described in [2]. First, a nominal CoP and ecmp trajectory is computed from the desired foothold poses to ensure no-tip conditions during each support phase. Second, the time-varying natural frequency, ω(t), is derived from the desired vertical CoM and ecmp trajectories. Third, an initial DCM reference trajectory is generated via reversetime integration of the DCM dynamics (3). Finally, the planner solves a time-varying LQR optimization to refine the trajectory over a short preview window, thereby eliminating any initial discontinuities due to replanning. Although more computationally intensive than the analytical DCM planners proposed by Englsberger et al. [17, 21], the proposed approach permits generic CoP and vertical CoM trajectories. The pelvis rotation and swing foot pose, R pelvis,r (t), R foot,r (t), and r foot,r (t), are generated using piecewise minimum jerk trajectories that interpolate between intermediate waypoints determined from the initial and final foothold poses. The upper body joint trajectories, q r (t), are defined by an internal planner that manages arm swinging during stepping. During manipulation, these trajectories are determined by an external planner that manages end-effector positioning and collision avoidance for tasks such as grasping and carrying an object. C. Task-Space Control Task-space position and velocity errors are regulated using a set of feedback controllers that command desired taskspace forces and accelerations. Table I lists the proportional and derivative gains used to compute desired linear and angular momentum rates of change, pelvis and swing foot accelerations, and upper body joint accelerations for the experiments in Section VI. To maintain rotation invariance, x and y-axis gains are represented in pelvis yaw coordinates. The computed motion tasks are tracked using the quadratic program (QP) formulation described in Section IV-E. The desired linear momentum rate of change is derived using a DCM tracking controller designed to stabilize the centroidal dynamics. This VRP-based controller uses PI feedback to regulate the estimated DCM error as described in [2]. The VRP setpoint is mapped to a desired linear momentum rate of change, l d, using (4). Proportional and integral gains of 3 m/m and 1 m/m s were selected for the experiments presented in Section VI, noting that the integral action is disabled during single support and heel-strike. The desired angular momentum rate of change is given by k d = 0. This reflects the assumption that the ecmp and CoP are collocated during walking, in which case, the horizontal moment about the CoM is equal to zero. Note that the robot s angular momentum is not directly regulated using feedback control. The proposed approach relies on Cartesian and joint-space PID controllers to track the pelvis, swing foot, and upper body trajectories and prevent excessive angular momentum during walking.

4 D. Step Adjustment In the event of a disturbance, the momentum controller will attempt to stabilize the DCM by shifting the ecmp and CoP away from the nominal reference position. This can induce a significant moment about the CoM whenever the ecmp leaves the base of support. Due to the robot s limited range of motion, it is not always possible to sustain the corresponding angular momentum rates of change required to prevent a fall, especially during the single support phase. In such scenarios, a fall can often be avoided by adjusting the target foothold position to modify the base of support. The proposed controller employs a simple heuristic to implement real-time step adjustment in response to significant disturbances. As illustrated in Fig. 3, a feedforward path is included to adjust the nominal swing foot trajectory in response to the DCM tracking error. The reference position is given by r foot,r = projection ( r foot,r + deadband (ξ ξ r ) ), (5) where r foot,r is the nominal swing foot position, ξ is the estimated DCM position, and ξ r is the reference DCM position. The deadband function implements a neutral zone in the DCM error signal to maintain precise foothold tracking in the event of small disturbances. The vertical DCM error is eliminated to avoid early or late heel-strike events. The projection function projects the modified swing foot position into a safe region based on a conservative estimate of the collision-free state space. Figure 2 illustrates an ideal lateral step adjustment in response to a large DCM error. Note that the offset between the final DCM and swing foot position is equivalent to the offset between the reference DCM and swing foot position (assuming zero deadband). The future foothold positions are specified relative to the current support foot position. Thus, the responsibility to correct for horizontal drift in foothold tracking is tasked to the high-level footstep planner. In scenarios requiring precise foothold tracking, the step adjustment can be minimized by increasing the DCM error deadband or increasing the DCM controller stiffness. E. Inverse Dynamics (QP Formulation) Given desired task-space forces and accelerations at each time step, an inverse dynamics module is used to compute optimal joint accelerations, q, and generalized contact forces, ρ = [ ] ρ T 1... ρ T T N, by minimizing a quadratic cost function in the form, min q,ρ C b (b J 2 q J q) + λ q q 2 + λ ρ ρ 2. (6) Here b represents the vector of desired motion tasks, J represents the corresponding matrix of task-space Jacobians, Q b = C T b C b represents the task weighting matrix, and λ q and λ ρ define the regularization parameters. The QP includes linear Newton-Euler and Coulomb friction constraints in addition to joint position and torque limits to ensure dynamic feasibility of the optimized setpoints [1]. Table I lists the experimentally selected weights for each motion task. TABLE I WHOLE-BODY CONTROLLER WEIGHTS AND GAINS 1 Motion Task Units Weight P-Gain D-Gain l d N 5, 5, k d Nm 5, 5, ω pelvis,d rad/s 2 100, 100, , 70, 30 30, 30, 15 ω foot,d rad/s 2 500, 500, , 100, 75 5, 5, 5 r foot,d m/s 2 1e3, 1e3, 1e3 50, 50, , 35, 35 r contact,d m/s 2 1e5, 1e5, 1e5 0, 0, 0 0, 0, 0 q arm,d rad/s q waist,d rad/s F. Low-Level Control Joint torque setpoints are derived from the optimized joint accelerations and contact forces via the rigid body equations of motion (1). As illustrated in Fig. 3, joint velocity setpoints are obtained via leaky integration of the optimized joint accelerations. The computed torque and velocity setpoints are relayed to embedded motor controllers at a rate of 150 Hz. The update rate is currently limited by the robot s state estimator, which computes velocity estimates using a decoupled Kalman filter design. Upper body trajectories are tracked using a high-gain velocity controller for each DoF, while lower body trajectories are tracked using a low-gain impedance controller described in [3]. V. DESIGN CONSIDERATIONS FOR THE DRC This section presents implementation details and lessons learned in adapting ESCHER s walking controller to two of the challenges presented by the DRC Finals: the dirt track and the stairs task. A. Dirt Track As ESCHER was unable to attempt the driving task at the DRC, the robot was required to traverse the 200 ft dirt track on foot. Because the QP formulation presented in Section IV-E assumes a rigid contact model, soft terrain, such as dirt and grass, can introduce significant unmodeled dynamics during walking. Although low-impedance control of the lower body provides a certain degree of robustness to surface compliance, poor DCM tracking can lead to tipping as the CoP deviates to the edge of the support polygon. In particular, lateral tipping about the outside edge of the foot can occur when the momentum controller fails to prevent overshoot of the DCM trajectory near the end of the double support phase. This failure mode is particularly dangerous, as range of motion and self-collision risks often prevent proper step adjustment during single support. During the course of development, the authors found that a simple modification to the CoP reference trajectory could significantly improve performance on soft and uncertain terrain. In the bipedal walking literature, the CoP trajectory is often defined to pass through the center of each support foot. A notable exception is [22], where the authors shift the 1 Cartesian weights and gains are specified for the x, y, and z axes. 2 These weights are decreased to (2.5, 5, 1) during the single support phase to reduce oscillations in the sagittal plane.

5 Fig. 4. The nominal CoP trajectory is shifted towards the inside of the support foot to improve stability on soft terrain and reduce lateral motion of the CoM during walking. CoP towards the big toe during single support to reduce the amount of hip sway. A similar approach is proposed here to improve stability on compliant terrain. As illustrated in Fig. 4, a lateral offset is introduced to shift the CoP toward the inside of the support foot. This decreases the lateral motion of the CoM similar to narrowing the step width, yet without the additional risk of self-collision. By increasing the nominal distance of the CoP to the outer edge of the foot, additional horizontal torque is available to correct for DCM overshoot. This decreases the risk of outward tipping. In the event of inward tipping, the controller can still regain stability through an appropriate step adjustment. B. Stairs Task The DRC course featured an industrial stairway and rough terrain area designed to test the robot s mobility in structured and unstructured environments. The team chose to focus development efforts on the stairs task rather than the rough terrain, due to initial range of motion issues encountered while stepping down on the cinder blocks. Although the proposed controls approach was designed to support locomotion on uneven terrain, a number of difficulties arose during the course of testing due to the risk of collision between the support leg and upper stair when stepping up. In order to increase the available workspace, a half-step strategy was adopted, permitting the robot to place the center of the support foot on the lip of the stair. As illustrated in Fig. 5, the rear contact points were shifted to the middle of the sole in order to appropriately constrain the CoP trajectory. To prevent knee and shin collisions, a soft position limit was enforced on the ankle pitch joint corresponding to the measured angle of collision. Using this approach, the inverse dynamics optimization was able to appropriately adjust the ankle pitch to avoid collision during stepping. By reducing the available ankle range of motion, careful design of the nominal CoM height trajectory was required to enable the robot to safely step onto the stair. Fig. 5 includes the vertical CoM and DCM reference trajectories corresponding to a 23 cm (9 in) step. Note that the CoM begins to accelerate at the beginning of the double support phase. Raising the CoM height early in the step cycle tends to rotate the support ankle away from the soft position limit. This has the added benefit of straightening the support knee, resulting in lower knee torques. As the CoM height increases, the length of the swing leg also increases. As a result, significant toe-off is required to allow the foot to remain in contact with the stair prior to lift-off. Fig. 5. Left: A half-step strategy is implemented to increase the available collision-free workspace of the support leg when ascending stairs. Right: During ascension, vertical CoM acceleration initiates at the beginning of the double support phase (shaded in gray), reducing the required knee torque. VI. EXPERIMENTAL RESULTS This section presents experimental results for the ESCHER humanoid demonstrating the walking controller s ability to negotiate each of the challenges discussed in the previous section. Identical control parameters are used in each experiment (refer to Table I), with the exception of the stairs task which required stiffer tracking of the z-axis DCM trajectory. A. Soft and Uncertain Terrain Images of ESCHER walking on a various indoor and outdoor terrain including grass, gravel, dirt, and unmodeled blocks can be seen in Fig. 6. Compliant control of the lower body enables accurate tracking of the desired ground reaction forces, allowing the robot to adapt naturally to uncertain terrain features. Figure 7 includes the desired and estimated horizontal CoP, VRP, and DCM trajectories corresponding to two separate walking experiments conducted on 3.5 cm pile height artificial turf (refer to Fig. 6-a). In the first experiment, the desired CoP waypoints are shifted by 2 cm towards in the inside of the foot as described in Section V-A. In the second experiment, the CoP waypoints are defined at the center of the support foot. In each case, the desired footstep plan consists of eight forward steps with a stride length of 0.15 m, step duration of 2 s, double support time of 0.6 s and single support time of 1.4 s. The results demonstrate that the lateral CoP offset can significantly reduce oscillations in the VRP, DCM, and CoP trajectories resulting from unmodeled surface compliance. Note that, without the offset, the estimated CoP approaches the edge of the foot on multiple occasions, indicating that the robot is approaching a tipping point. Fig. 6. ESCHER walking on various terrain including grass, gravel, and 3.8 cm blocks. In each case, the controller assumes a rigid contact surface, and has no knowledge of height variations or surface compliance.

6 Fig. 8. Time-lapse of ESCHER stepping up onto a 23 cm x 28 cm block, representative of the stairs task at the DRC Finals. Fig. 7. Desired and estimated DCM, VRP, and CoP trajectories while walking on artificial turf with a 2 s step duration. In the top plot, the CoP trajectory is shifted inward by 2 cm to improve tracking performance. In the bottom plot, the CoP passes through the center of the foot. B. Uneven Terrain Figure 8 includes images of the robot stepping onto a set of cinder blocks with the same height and depth as the industrial stairs in the DRC Finals course (23 cm x 28 cm). Image 3a and 3b were captured during toe-off, as the robot pitched the right ankle to extend the effective length of the swing leg. In this experiment, the heel of the left foot was positioned 10 cm from the lip of the stair. With 60% of the sole in contact, this configuration provided a slight safety margin to prevent the foot from rocking given the limited base of support. Note that the support bar on the knee clears the upper stair by approximately 2 cm using the methods described in Section V-B. A minimum position limit of 0.6 radians was selected for the ankle pitch joint in order to prevent collision. For this experiment, the proportional gain of the DCM controller was increased from 3 m/m to 5 m/m in the vertical axis, while the vertical l d weighting was increased from 1 to 5 to improve tracking (refer to Table I). C. Step Adjustment In a final experiment, ESCHER was subjected to external disturbance forces while walking forward on flat terrain. Figure 10 includes the lateral CoM, VRP, and DCM trajectories over the course of eight steps. The figure marks the desired horizontal position of the swing foot at the time of heelstrike to illustrate the corresponding step adjustments. As in the compliant terrain experiments, each footstep was selected with a 2 s step duration and 0.15 m stride length to emulate a moderate walking speed. Two disturbance impulses of increasing magnitude were applied at approximately 6 and 10 seconds. Figure 9 includes a time lapse of the robot recovering from the large push applied to the left hip using the proposed step adjustment strategy (5). As illustrated in Fig. 10, each push results in a significant deviation of the estimated DCM from the nominal reference trajectory. The DCM error transients appearing in the Fig. 9. Time-lapse of a lateral step adjustment in response to an external disturbance applied to the hip (corresponding to Fig. 10 at the 10 s mark). Fig. 10. Lateral DCM, VRP, and CoM trajectories during step adjustment experiment. The desired swing foot position at the time of each heel strike is noted by the triangle markers (blue for nominal, yellow for adjusted reference). The two lateral pushes occur at approximately 6 and 10 seconds. undisturbed steps occur primarily during heel-strike and are quickly corrected by the momentum controller. The DCM error transient following the first push is within the deadband of the step adjustment algorithm. Thus, the desired foothold position remains unchanged, as the momentum controller is able to eliminate the error by shifting the ecmp. The second push, however, results in an error that exceeds the deadband, triggering a step adjustment of 6.8 cm in the same direction as the disturbance force. The modified base of support allows the robot to apply the necessary restoring forces to stabilize the DCM following heel-strike. Note that the DCM tracking quality is recovered within one step.

7 VII. CONCLUSION The experimental results demonstrated the effectiveness of the proposed controls approach for locomotion on soft and uneven terrain. By shifting the nominal CoP trajectory towards the inside of the foot, the controller was able to reduce lateral sway and improve tracking performance in the presence of unknown surface features. This simple modification was critical to the robot s ability to walk on outdoor surfaces including dirt, gravel, and grass. The proposed step adjustment algorithm was shown to increase controller robustness in the presence of external disturbances. The results motivate the use of simple heuristics to modify the swing foot position in response to the estimated DCM error. The proposed walking controller was used during the DRC Finals without modification. On the first day, the robot fell when traversing the 200 ft dirt track due to a minor hardware complication. On the second day, the robot was able to walk from the starting line to the door, verifying the reliability of the proposed approach on compliant terrain. Additional experiments were performed using identical control parameters on a variety of terrain to test the reliability of the approach. Although unable to attempt the stairs task at the DRC Finals, ESCHER successfully demonstrated the proposed approach outside of competition. The use of a half-step strategy significantly increased the available workspace. When combined with careful vertical CoM planning, a soft position limit on the ankle joint allowed the robot to avoid collisions in a natural fashion when stepping up. Future research efforts will focus on alternative methods for real-time step adjustment using model predictive control. Additional efforts will investigate optimization-based methods to generate the nominal CoM height trajectory on uneven terrain. ACKNOWLEDGMENTS This material is supported by ONR through grant N and by DARPA through grant N We would like to thank the DRC competition team and all of the students who contributed to the development of ESCHER. REFERENCES [1] M. A. Hopkins, D. W. Hong, and A. Leonessa, Compliant locomotion using whole-body control and Divergent Component of Motion tracking, in Robotics and Automation (ICRA), IEEE International Conference on, May [2] M. A. Hopkins, D. W. Hong, and A. Leonessa, Humanoid locomotion on uneven terrain using the time-varying Divergent Component of Motion, in Humanoid Robots (Humanoids), 14th IEEE-RAS International Conference on, Nov [3] M. A. Hopkins, S. A. Ressler, D. F. Lahr, D. W. Hong, and A. Leonessa, Embedded joint-space control of a series elastic humanoid, in Intelligent Robots and Systems (IROS), IEEE/RSJ International Conference on, Hamburg, Germany, October [4] S. Feng, E. Whitman, X. Xinjilefu, and C. G. Atkeson, Optimizationbased full body control for the DARPA Robotics Challenge, Journal of Field Robotics, vol. 32, no. 2, pp , [5] S. Kuindersma, F. Permenter, and R. Tedrake, An efficiently solvable quadratic program for stabilizing dynamic locomotion, in Robotics and Automation (ICRA), IEEE International Conference on, May [6] M. Johnson, B. Shrewsbury, S. Bertrand, T. Wu, D. Duran, M. Floyd, P. Abeles, D. Stephen, N. Mertins, A. Lesman et al., Team IHMC s lessons learned from the DARPA Robotics Challenge Trials, Journal of Field Robotics, vol. 32, no. 2, pp , [7] B. Stephens and C. Atkeson, Dynamic balance force control for compliant humanoid robots, in Intelligent Robots and Systems (IROS), IEEE/RSJ International Conference on, Oct 2010, pp [8] S.-H. Lee and A. Goswami, Ground reaction force control at each foot: A momentum-based humanoid balance controller for non-level and non-stationary ground, in Intelligent Robots and Systems (IROS), IEEE/RSJ International Conference on, Oct 2010, pp [9] A. Herzog, L. Righetti, F. Grimminger, P. Pastor, and S. Schaal, Balancing experiments on a torque-controlled humanoid with hierarchical inverse dynamics, in Intelligent Robots and Systems (IROS 2014), 2014 IEEE/RSJ International Conference on, Sept 2014, pp [10] P. M. Wensing and D. E. Orin, Generation of dynamic humanoid behaviors through task-space control with conic optimization, in Robotics and Automation (ICRA), IEEE International Conference on, May 2013, pp [11] T. Koolen, J. Smith, G. Thomas, S. Bertrand, J. Carff, N. Mertins, D. Stephen, P. Abeles, J. Englsberger, S. McCrory, J. van Egmond, M. Griffioen, M. Floyd, S. Kobus, N. Manor, S. Alsheikh, D. Duran, L. Bunch, E. Morphis, L. Colasanto, K.-L. Ho Hoang, B. Layton, P. Neuhaus, M. Johnson, and J. Pratt, Summary of team IHMC s virtual robotics challenge entry, in Humanoid Robots (Humanoids), 13th IEEE-RAS International Conference on, Oct [12] K. Hashimoto, H. jin Kang, M. Nakamura, E. Falotico, H. ok Lim, A. Takanishi, C. Laschi, P. Dario, and A. Berthoz, Realization of biped walking on soft ground with stabilization control based on gait analysis, in Intelligent Robots and Systems (IROS), 2012 IEEE/RSJ International Conference on, Oct 2012, pp [13] Y. Zheng, H. Wang, S. Li, Y. Liu, D. Orin, K. Sohn, Y. Jun, and P. Oh, Humanoid robots walking on grass, sands and rocks, in Technologies for Practical Robot Applications (TePRA), 2013 IEEE International Conference on, April 2013, pp [14] J. Pratt, J. Carff, S. Drakunov, and A. Goswami, Capture Point: A Step toward Humanoid Push Recovery, in Humanoid Robots (Humanoids), 6th IEEE-RAS International Conference on, Dec 2006, pp [15] H. Diedam, D. Dimitrov, P. B. Wieber, K. Mombaur, and M. Diehl, Online walking gait generation with adaptive foot positioning through linear model predictive control, in Intelligent Robots and Systems (IROS), IEEE/RSJ International Conference on, Sept 2008, pp [16] J. Urata, K. Nshiwaki, Y. Nakanishi, K. Okada, S. Kagami, and M. Inaba, Online decision of foot placement using singular lq preview regulation, in Humanoid Robots (Humanoids), th IEEE-RAS International Conference on, Oct 2011, pp [17] J. Englsberger, C. Ott, and A. Albu-Schaffer, Three-dimensional bipedal walking control based on divergent component of motion, Robotics, IEEE Transactions on, vol. 31, no. 2, pp , April [18] B. Lee, Design of a humanoid robot for disaster response, Master s thesis, Virginia Polytechnic Institute and State University, April [19] C. Knabe, B. Lee, V. Orekhov, and D. Hong, Design of a compact, lightweight, electromechanical linear series elastic actuator, in ASME International Design Engineering Technical Conference, [20] T. Takenaka, T. Matsumoto, and T. Yoshiike, Real time motion generation and control for biped robot -1st report: Walking gait pattern generation, in Intelligent Robots and Systems (IROS), IEEE/RSJ International Conference on, Oct 2009, pp [21] J. Englsberger, T. Koolen, S. Betrand, J. Pratt, C. Ott, and A. Albu- Schaffer, Trajectory generation for continuous leg forces during double support and heel-to-toe shift based on divergent component of motion, in Intelligent Robots and Systems (IROS), IEEE/RSJ International Conference on, Sept [22] K. Harada, K. Miura, M. Morisawa, K. Kaneko, S. Nakaoka, F. Kanehiro, T. Tsuji, and S. Kajita, Toward human-like walking pattern generator, in Intelligent Robots and Systems (IROS), IEEE/RSJ International Conference on, Oct 2009, pp

arxiv: v1 [cs.ro] 28 Feb 2017

arxiv: v1 [cs.ro] 28 Feb 2017 Robust Bipedal Locomotion Control Based on Model Predictive Control and Divergent Component of Motion Milad Shafiee-Ashtiani, 1 Aghil Yousefi-Koma, 1 and Masoud Shariat-Panahi 2 arxiv:170208742v1 [csro]

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

arxiv: v1 [cs.ro] 27 Jul 2016

arxiv: v1 [cs.ro] 27 Jul 2016 Walking on Partial Footholds Including Line Contacts with the Humanoid Robot Atlas* Georg Wiedebach 1, Sylvain Bertrand 1, Tingfan Wu 1, Luca Fiorio 2, Stephen McCrory 1, Robert Griffin 1, Francesco Nori

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

arxiv: v2 [cs.ro] 12 Jan 2017

arxiv: v2 [cs.ro] 12 Jan 2017 Walking on Partial Footholds Including Line Contacts with the Humanoid Robot Atlas* Georg Wiedebach 1, Sylvain Bertrand 1, Tingfan Wu 1, Luca Fiorio 2, Stephen McCrory 1, Robert Griffin 1, Francesco Nori

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

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

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

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

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

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

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

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

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

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

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

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

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

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

AFRL-RI-RS-TR

AFRL-RI-RS-TR AFRL-RI-RS-TR-2014-045 ROBUST ROBOT CONTROL USING MULTIPLE MODEL-BASED POLICY OPTIMIZATION AND FAST VALUE FUNCTION-BASED PLANNING CARNEGIE MELLON UNIVERSITY MARCH 2014 FINAL TECHNICAL REPORT APPROVED FOR

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

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

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

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

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

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

Online Learning of Low Dimensional Strategies for High-Level Push Recovery in Bipedal Humanoid Robots

Online Learning of Low Dimensional Strategies for High-Level Push Recovery in Bipedal Humanoid Robots 2013 IEEE International Conference on Robotics and Automation (ICRA) Karlsruhe, Germany, May 6-10, 2013 Online Learning of Low Dimensional Strategies for High-Level Push Recovery in Bipedal Humanoid Robots

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

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

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

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

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

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

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

Spider Robot for Motion with Quasistatic. Force Constraints

Spider Robot for Motion with Quasistatic. Force Constraints Spider Robot for Motion with Quasistatic Force Constraints Shraga Shoval, Elon Rimon and Amir Shapira Technion - Israel Institute of Technology - Haifa, Israel 32000. Abstract In quasistatic motions the

More information

Optimal Gait Primitives for Dynamic Bipedal Locomotion

Optimal Gait Primitives for Dynamic Bipedal Locomotion 2012 IEEE/RSJ International Conference on Intelligent Robots and Systems October 7-12, 2012. Vilamoura, Algarve, Portugal Optimal Gait Primitives for Dynamic Bipedal Locomotion Bokman Lim, Jusuk Lee, Joohyung

More information

Fail Operational Controls for an Independent Metering Valve

Fail Operational Controls for an Independent Metering Valve Group 14 - System Intergration and Safety Paper 14-3 465 Fail Operational Controls for an Independent Metering Valve Michael Rannow Eaton Corporation, 7945 Wallace Rd., Eden Prairie, MN, 55347, email:

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

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

RECENTLY, various humanoid robots have been

RECENTLY, various humanoid robots have been Stability Improvement Using Soft Sole on Humanoid Robot Masanao Koeda 1, Tsuneo Yoshikawa 1, and Keita Nakagawa 1 1 Ritsumeikan University, College of Information Science and Engineering, Department of

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

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

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

Compliant Attitude Control and Stepping Strategy for Balance Recovery with the Humanoid COMAN

Compliant Attitude Control and Stepping Strategy for Balance Recovery with the Humanoid COMAN 2013 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS) November 3-7 2013. Tokyo Japan Compliant Attitude Control and Stepping Strategy for Balance Recovery with the Humanoid COMAN

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

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

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

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

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

The Design of ZMP Measure System for Biped Robot LI Bin 1, a, LI Zhihai 2, b, LI Jiejia 1, c, BU Chunguang 2, d

The Design of ZMP Measure System for Biped Robot LI Bin 1, a, LI Zhihai 2, b, LI Jiejia 1, c, BU Chunguang 2, d 2nd International Conference on Electrical, Computer Engineering and Electronics (ICECEE 2015) The Design of ZMP Measure System for Biped Robot LI Bin 1, a, LI Zhihai 2, b, LI Jiejia 1, c, BU Chunguang

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

Creation of a Fallback Catch Method. Megan Berry Mechanical Engineering Senior MAE 490 (4 credits)

Creation of a Fallback Catch Method. Megan Berry Mechanical Engineering Senior MAE 490 (4 credits) Creation of a Fallback Catch Method Megan Berry Mechanical Engineering Senior MAE 490 (4 credits) Abstract In order that the Cornell Ranger remains autonomous during long distance record attempts and avoids

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

ZIPWAKE DYNAMIC TRIM CONTROL SYSTEM OUTLINE OF OPERATING PRINCIPLES BEHIND THE AUTOMATIC MOTION CONTROL FEATURES

ZIPWAKE DYNAMIC TRIM CONTROL SYSTEM OUTLINE OF OPERATING PRINCIPLES BEHIND THE AUTOMATIC MOTION CONTROL FEATURES ZIPWAKE DYNAMIC TRIM CONTROL SYSTEM OUTLINE OF OPERATING PRINCIPLES BEHIND THE AUTOMATIC MOTION CONTROL FEATURES TABLE OF CONTENTS 1 INTRODUCTION 3 2 SYSTEM COMPONENTS 3 3 PITCH AND ROLL ANGLES 4 4 AUTOMATIC

More information

Gait Sequence generation of a Hybrid Wheeled-Legged Robot for negotiating discontinuous terrain

Gait Sequence generation of a Hybrid Wheeled-Legged Robot for negotiating discontinuous terrain 1 Gait Sequence generation of a Hybrid Wheeled-Legged Robot for negotiating discontinuous terrain Sartaj Singh, K Madhava Krishna Abstract-- In this paper we develop an algorithm to generate gait sequences

More information

ABSTRACT PATTERNS USING 3D-DYNAMIC MODELING. Kaustav Nandy, Master of Science, Department of Electrical And Computer Engineering

ABSTRACT PATTERNS USING 3D-DYNAMIC MODELING. Kaustav Nandy, Master of Science, Department of Electrical And Computer Engineering ABSTRACT Title of Thesis: IDENTIFICATION OF HUMAN WALKING PATTERNS USING 3D-DYNAMIC MODELING Kaustav Nandy, Master of Science, 26 Thesis Directed By: Professor. Rama Chellappa Department of Electrical

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

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

Reactive Balance Control in Walking based on a Bipedal Linear Inverted Pendulum Model

Reactive Balance Control in Walking based on a Bipedal Linear Inverted Pendulum Model 2011 IEEE International Conference on Robotics and Automation Shanghai International Conference Center May 9-13, 2011, Shanghai, China Reactive Balance Control in Walking based on a Bipedal Linear Inverted

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

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

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

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

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

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

Practical Bipedal Walking Control on Uneven Terrain Using Surface Learning and Push Recovery

Practical Bipedal Walking Control on Uneven Terrain Using Surface Learning and Push Recovery 2011 IEEE/RSJ International Conference on Intelligent Robots and Systems September 25-30, 2011. San Francisco, CA, USA Practical Bipedal Walking Control on Uneven Terrain Using Surface Learning and Push

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

Motion Representation of Walking/Slipping/Turnover for Humanoid Robot by Newton-Euler Method

Motion Representation of Walking/Slipping/Turnover for Humanoid Robot by Newton-Euler Method SICE Annual Conference 211 September 13-18, 211, Waseda University, Tokyo, Japan Motion Representation of Walking//Turnover for Humanoid Robot by Newton-Euler Method Tomohide Maeba 1, Geng Wang 1, Fujia

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

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

+ t1 t2 moment-time curves

+ t1 t2 moment-time curves Part 6 - Angular Kinematics / Angular Impulse 1. While jumping over a hurdle, an athlete s hip angle was measured to be 2.41 radians. Within 0.15 seconds, the hurdler s hip angle changed to be 3.29 radians.

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

Coaching the Triple Jump Boo Schexnayder

Coaching the Triple Jump Boo Schexnayder I. Understanding the Event A. The Run and Its Purpose B. Hip Undulation and the Phases C. Making the Connection II. III. IV. The Approach Run A. Phases B. Technical Features 1. Posture 2. Progressive Body

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

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

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

A Neuromuscular Model of Human Locomotion and its Applications to Robotic Devices

A Neuromuscular Model of Human Locomotion and its Applications to Robotic Devices A Neuromuscular Model of Human Locomotion and its Applications to Robotic Devices The 10th Workshop on Humanoid Soccer Robots at 15th IEEE-RAS International Conference on Humanoid Robots Nov 3, 2015 Seungmoon

More information

Programmable Valves Enable Both Precision Motion Control and Energy Saving

Programmable Valves Enable Both Precision Motion Control and Energy Saving Programmable Valves Enable Both Precision Motion Control and Energy Saving Dr. Bin Yao Purdue University West Lafayette, IN 47907, USA 1 Outline Development of Programmable Valves Control of Programmable

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

Shuuji Kajita and Kazuo Tani

Shuuji Kajita and Kazuo Tani of Shuuji Kajita and Kazuo Tani in experimental study of a iped robot is presented. A new scheme named the Linear Inverted Pendulum Mode is utilized for controlling a biped walking on rugged terrain. We

More information

In this course you will learn the following

In this course you will learn the following Module 11 : Example study of robots Lecture 40 : NATARAJ a case study of a 6-legged robot Objectives In this course you will learn the following Mobile Robots Legged Robots Nataraj Robot Nataraj Development

More information

LOCOMOTION CONTROL CYCLES ADAPTED FOR DISABILITIES IN HEXAPOD ROBOTS

LOCOMOTION CONTROL CYCLES ADAPTED FOR DISABILITIES IN HEXAPOD ROBOTS LOCOMOTION CONTROL CYCLES ADAPTED FOR DISABILITIES IN HEXAPOD ROBOTS GARY B. PARKER and INGO CYLIAX Department of Computer Science, Indiana University, Bloomington, IN 47405 gaparker@cs.indiana.edu, cyliax@cs.indiana.edu

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

-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

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

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

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

Ranger Walking Initiation Stephanie Schneider 5/15/2012 Final Report for Cornell Ranger Research

Ranger Walking Initiation Stephanie Schneider 5/15/2012 Final Report for Cornell Ranger Research 1 Ranger Walking Initiation Stephanie Schneider sns74@cornell.edu 5/15/2012 Final Report for Cornell Ranger Research Abstract I joined the Biorobotics Lab this semester to gain experience with an application

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

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

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

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

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

Development of a Locomotion and Balancing Strategy for Humanoid Robots

Development of a Locomotion and Balancing Strategy for Humanoid Robots University of Denver Digital Commons @ DU Electronic Theses and Dissertations Graduate Studies 1-1-2018 Development of a Locomotion and Balancing Strategy for Humanoid Robots Emile Bahdi University of

More information

Variable Face Milling to Normalize Putter Ball Speed and Maximize Forgiveness

Variable Face Milling to Normalize Putter Ball Speed and Maximize Forgiveness Proceedings Variable Face Milling to Normalize Putter Ball Speed and Maximize Forgiveness Jacob Lambeth *, Dustin Brekke and Jeff Brunski Cleveland Golf, 5601 Skylab Rd. Huntington Beach, CA 92647, USA;

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

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

Efficient Gait Generation using Reinforcement Learning

Efficient Gait Generation using Reinforcement Learning Efficient Gait Generation using Reinforcement Learning Josep M Porta and Enric Celaya Institut de Robòtica i Informàtica Industrial, UPC-CSIC, Barcelona, Spain. SYNOPSIS The use of a free gait becomes

More information