Wiki

Only released in EOL distros:  

humanoid_walk: halfsteps_pattern_generator | walk_interfaces | walk_msgs | walk_tools

Package Summary

Gathers tools providing useful computations when dealing with walking trajectory generation.

humanoid_walk: halfsteps_pattern_generator | walk_interfaces | walk_msgs | walk_tools

Package Summary

Gathers tools providing useful computations when dealing with walking trajectory generation.

ROS API

ZMP estimation from force sensors

The most widely used balance criterion is the (virtual) Zero Momentum Point. When this point exits the robot polygon support, the robot start falling.

It is therefore interesting to monitor this point while the robot is running to make sure that it stays near its planned position.

A method to estimate the ZMP position is to measure the force applied on both feet and deduce the ZMP position from it. This tool realizes this computation and makes the following assuption:

zmp_estimator

ZMP estimation node from feet force sensors

Subscribed Topics

~left_foot_wrench (geometry_msgs/WrenchStamped) ~right_foot_wrench (geometry_msgs/WrenchStamped)

Published Topics

zmp_estimated (geometry_msgs/Vector3Stamped)

Parameters

left_foot_wrench (string, default: left_foot) right_foot_wrench (string, default: right_foot) contact_threshold (Float64, default: 10) approximate_sync (Float64, default: 0.001) queue_size (Float64, default: 10) reference_frame (string, default: /world) left_foot_x (Float64, default: 0.) left_foot_y (Float64, default: 0.) left_foot_z (Float64, default: 0.105) right_foot_x (Float64, default: 0.) right_foot_y (Float64, default: 0.) right_foot_z (Float64, default: 0.105)

For instance, you may run this script by typing:

   1 rosrun walk_tools zmp_monitor _left_foot_wrench:=/force_0 _right_foot_wrench:=/force_1

Effort monitor

During movement execution, effort monitoring on each actuator prevents robot dammage.

This script regularly checks that the current torques reported by the joint_states topic are lower than the limit indicated in the robot URDF model. If the effort is higher that 85% of the limit, a warning is issued. Warning and errors are reported using the ROS diagnostics stack.

effort_monitor

Monitor efforts on joints.

Subscribed Topics

joint_states (sensor_msgs/JointStates)

Published Topics

diagnosics (diagnostic_msgs/DiagnosticArray)

force_monitor

Monitor force applied to robot feet. The script makes the assumption that the reaction force is along the Z axis.

Subscribed Topics

left_foot (geometry_msgs/WrenchStamped) right_foot (geometry_msgs/WrenchStamped)

Published Topics

diagnosics (diagnostic_msgs/DiagnosticArray)

Parameters

force_warning_threshold (Float64) force_error_threshold (Float64)

Wiki: walk_tools (last edited 2012-03-15 00:32:15 by ThomasMoulard)