move3d_ros_lib
0.1.0
move3d/ros API interface
|
The SingleJoint2dUpdater class is a plugin class for the HumanMgr. It takes a 2D+rotation position and a constant height. More...
#include <single_joint_2d_updater.h>
Public Member Functions | |
virtual bool | update (Robot *h, const Eigen::Affine3d &base, const std::map< std::string, Eigen::Affine3d > &joints, const HumanSettings &settings) |
update the robot with the given elements More... | |
virtual bool | computeConf (Robot *h, const Eigen::Affine3d &base, const std::map< std::string, Eigen::Affine3d > &joints, const HumanSettings &settings, RobotState &q) |
compute the configuration without updating the human in move3d More... | |
The SingleJoint2dUpdater class is a plugin class for the HumanMgr. It takes a 2D+rotation position and a constant height.
It reads only the base position in the input and takes a "height" parameter from the settings. The human base joint (e.g. pelvis) is placed in the position "base" translated of (0,0,height).
|
virtual |
compute the configuration without updating the human in move3d
[in] | h | Robot object representing the human in move3d |
[in] | base | base position |
[in] | joints | joint positions |
[in] | settings | settings for that human |
[out] | q | the computed configuration |
Implements move3d::BaseHumanUpdater.
|
virtual |
update the robot with the given elements
h | the Robot object representing the human in move3d |
base | the base position |
joints | the joint positions |
settings | settings for that human |
Implements move3d::BaseHumanUpdater.