New in Electric
Only released in EOL distros:
Package Summary
This packages provides a pattern generator based on half-steps for dimensionality reduction. It generates feet, center of mass and ZMP trajectories for humanoids robots from a set of 2d footprints.
- Author: Nicolas Perrin, Thomas Moulard/thomas.moulard@gmail.com
- License: BSD
- Source: git https://github.com/laas/humanoid_walk.git (branch: master)
Package Summary
This packages provides a pattern generator based on half-steps for dimensionality reduction. It generates feet, center of mass and ZMP trajectories for humanoids robots from a set of 2d footprints.
- Author: Nicolas Perrin, Thomas Moulard/thomas.moulard@gmail.com
- License: BSD
- Source: git https://github.com/laas/humanoid_walk.git (branch: master)
Contents
This package provides the reference implementation of the paper "A biped walking pattern generator based on “half-steps” for dimensionality reduction".
It can be used to generate walking trajectories for humanoid robots. See the tutorials to learn how to use this package.
Algorithm specific parameters
This algorithm requires additional parameters:
Global parameters
time before ZMP shift
time after ZMP shift
step
Per footprint parameters
slide up
slide down
horizontal distance
step height
ROS API
generator
Trajectory generation node.Published Topics
com (nav_msgs/Path)- Center of mass trajectory.
- Footprints position.
- Left foot trajectory.
- Right foot trajectory.
- ZMP trajectory.
Services
getPath (walk_msgs/GetPath)- Generate a trajectory from footprints positions.
Parameters
time_before_zmp_shift (Float64, default: 0.95)- Time between the beginning of the half-step and the ZMP shift.
- Time between the beginning of the ZMP shift and the end of the half-step.
- Discretization step. It is highly recommended to keep the default value (i.e. 0.005s).
- World frame name (i.e. the reference frame in which the trajectories are expressed).
Videos
The following demonstrations are relying on this pattern generator.
References
N. Perrin, O. Stasse, F. Lamiraux, E. Yoshida. A biped walking pattern generator based on “half-steps” for dimensionality reduction. In Proc. of the 2011 IEEE International Conference on Robotics and Automation (ICRA) [ pdf ]
L. Baudouin, N. Perrin, T. Moulard, O. Stasse, F. Lamiraux, E. Yoshida Real-time Replanning Using 3D Environment for Humanoid Robot. In Proc. of the 2011 IEEE/RAS International Conference on Humanoid Robots [ pdf ]