|
bool | canTransform (const std::string &from_frame) const override |
| Check whether data can be transformed from a particular frame. More...
|
|
const Eigen::Isometry3d & | getTransform (const std::string &from_frame) const override |
| Get transform for from_frame (w.r.t target frame) More...
|
|
bool | isFixedFrame (const std::string &frame) const override |
| Check whether a frame stays constant as the state of the robot model changes. This is true for any transform mainatined by this object. More...
|
|
| SceneTransforms (const PlanningScene *scene) |
|
const std::string & | getTargetFrame () const |
| Get the planning frame corresponding to this set of transforms. More...
|
|
| Transforms (const std::string &target_frame) |
| Construct a transform list. More...
|
|
virtual | ~Transforms () |
| Destructor. More...
|
|
const FixedTransformsMap & | getAllTransforms () const |
| Return all the transforms. More...
|
|
void | copyTransforms (std::vector< geometry_msgs::TransformStamped > &transforms) const |
| Get a vector of all the transforms as ROS messages. More...
|
|
void | setTransform (const Eigen::Isometry3d &t, const std::string &from_frame) |
| Set a transform in the transform tree (adding it if necessary) More...
|
|
void | setTransform (const geometry_msgs::TransformStamped &transform) |
| Set a transform in the transform tree (adding it if necessary) More...
|
|
void | setTransforms (const std::vector< geometry_msgs::TransformStamped > &transforms) |
| Set a transform in the transform tree (adding it if necessary) More...
|
|
void | setAllTransforms (const FixedTransformsMap &transforms) |
| Set all the transforms: a map from string names of frames to corresponding Eigen::Isometry3d (w.r.t the planning frame) More...
|
|
void | transformVector3 (const std::string &from_frame, const Eigen::Vector3d &v_in, Eigen::Vector3d &v_out) const |
| Transform a vector in from_frame to the target_frame Note: assumes that v_in and v_out are "free" vectors, not points. More...
|
|
void | transformQuaternion (const std::string &from_frame, const Eigen::Quaterniond &q_in, Eigen::Quaterniond &q_out) const |
| Transform a quaternion in from_frame to the target_frame. More...
|
|
void | transformRotationMatrix (const std::string &from_frame, const Eigen::Matrix3d &m_in, Eigen::Matrix3d &m_out) const |
| Transform a rotation matrix in from_frame to the target_frame. More...
|
|
void | transformPose (const std::string &from_frame, const Eigen::Isometry3d &t_in, Eigen::Isometry3d &t_out) const |
| Transform a pose in from_frame to the target_frame. More...
|
|
Definition at line 92 of file planning_scene.cpp.