Functions
Setting and retrieving transforms maintained in this class

Functions

void robot_state::Transforms::copyTransforms (std::vector< geometry_msgs::TransformStamped > &transforms) const
 Get a vector of all the transforms as ROS messages.
const FixedTransformsMap & robot_state::Transforms::getAllTransforms () const
 Return all the transforms.
void robot_state::Transforms::setAllTransforms (const FixedTransformsMap &transforms)
 Set all the transforms: a map from string names of frames to corresponding Eigen::Affine3d (w.r.t the planning frame)
void robot_state::Transforms::setTransform (const Eigen::Affine3d &t, const std::string &from_frame)
 Set a transform in the transform tree (adding it if necessary)
void robot_state::Transforms::setTransform (const geometry_msgs::TransformStamped &transform)
 Set a transform in the transform tree (adding it if necessary)
void robot_state::Transforms::setTransforms (const std::vector< geometry_msgs::TransformStamped > &transforms)
 Set a transform in the transform tree (adding it if necessary)

Function Documentation

void robot_state::Transforms::copyTransforms ( std::vector< geometry_msgs::TransformStamped > &  transforms) const

Get a vector of all the transforms as ROS messages.

Parameters:
transformsThe output transforms

Definition at line 156 of file transforms.cpp.

Return all the transforms.

Returns:
A map from string names of frames to corresponding Eigen::Affine3d (w.r.t the planning frame)

Definition at line 78 of file transforms.cpp.

Set all the transforms: a map from string names of frames to corresponding Eigen::Affine3d (w.r.t the planning frame)

Definition at line 83 of file transforms.cpp.

void robot_state::Transforms::setTransform ( const Eigen::Affine3d &  t,
const std::string &  from_frame 
)

Set a transform in the transform tree (adding it if necessary)

Parameters:
tThe input transform (w.r.t the target frame)
from_frameThe frame for which the input transform is specified

Definition at line 120 of file transforms.cpp.

void robot_state::Transforms::setTransform ( const geometry_msgs::TransformStamped &  transform)

Set a transform in the transform tree (adding it if necessary)

Parameters:
transformThe input transform (the frame_id must match the target frame)

Definition at line 136 of file transforms.cpp.

void robot_state::Transforms::setTransforms ( const std::vector< geometry_msgs::TransformStamped > &  transforms)

Set a transform in the transform tree (adding it if necessary)

Parameters:
transformThe input transforms (the frame_id must match the target frame)

Definition at line 150 of file transforms.cpp.



moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Mon Oct 6 2014 02:24:47