This package wraps jrl-walkgen. jrl-walkgen implements several pattern generator algorithms. These algorithms aims at generating walking trajectories for biped robots.

jrl-walkgen highly rely on jrl-dynamics for geometry, velocity and dynamics computation.

Supported algorithms

The following algorithms are supported:

  • Morisawa2007

  • Kajita2003 usable with HRP-2 only for now.

Algorithm choice is done though the algorithm parameter of the trajectory server node, see below.

ROS API

trajectory_server

Trajectory generation node.

Published Topics

com (nav_msgs/Path)
  • Center of mass trajectory.
footprints (visualization_msgs/MarkerArray)
  • Footprints position.
left_foot (nav_msgs/Path)
  • Left foot trajectory.
right_foot (nav_msgs/Path)
  • Right foot trajectory.
zmp (nav_msgs/Path)
  • ZMP trajectory.

Services

getPath (walk_msgs/GetPath)
  • Generate a trajectory from footprints positions.

Parameters

world_frame_id (string)
  • World frame name (i.e. the reference frame in which the trajectories are expressed).
algorithm (string, default: Morisawa2007)
  • Pattern generator algorithm.
step (Float64, default: 0.005)
  • Sampling step (seconds).
/robot_description (string)
  • Robot model (URDF).

References

  • M. Morisawa, S. Kajita, K. Kaneko, K. Harada, F. Kanehiro, K. Fujiwara, H. Hirukawa. Pattern Generation of Biped Walking Constrained on Parametric Surface. In Proc. of the 2005 IEEE International Conference on Robotics and Automation (ICRA) [ pdf ]

  • S. Kajita, F. Kanehiro, K. Kaneko, K. Fujiwara, K. Harada, K. Yokoi and H. Hirukawa. Biped Walking Pattern Generation by using Preview Control of Zero-Moment Point. In Proc. of the 2003 IEEE International Conference on Robotics and Automation (ICRA) [ pdf ]

  • A. Herdt, H. Diedam, P.-B. Wieber, D. Dimitrov, K. Mombaur, M. Diehl. Online Walking Motion Generation with Automatic Foot Step Placement. In Advanced Robotics Vol. 24 Issue 5-6, pp. 719--737 [ pdf ]

Wiki: jrl_walkgen_bridge (last edited 2012-03-06 15:22:05 by ThomasMoulard)