Public Member Functions | Static Public Member Functions | Protected Attributes
robot_state::Transforms Class Reference

Provides an implementation of a snapshot of a transform tree that can be easily queried for transforming different quantities. Transforms are maintained as a list of transforms to a particular frame. All stored transforms are considered fixed. More...

#include <transforms.h>

Inheritance diagram for robot_state::Transforms:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual bool canTransform (const std::string &from_frame) const
 Check whether data can be transformed from a particular frame.
void copyTransforms (std::vector< geometry_msgs::TransformStamped > &transforms) const
 Get a vector of all the transforms as ROS messages.
const FixedTransformsMapgetAllTransforms () const
 Return all the transforms.
const std::string & getTargetFrame () const
 Get the planning frame corresponding to this set of transforms.
virtual const Eigen::Affine3d & getTransform (const std::string &from_frame) const
 Get transform for from_frame (w.r.t target frame)
virtual bool isFixedFrame (const std::string &frame) const
 Check whether a frame stays constant as the state of the robot model changes.
void 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 setTransform (const Eigen::Affine3d &t, const std::string &from_frame)
 Set a transform in the transform tree (adding it if necessary)
void setTransform (const geometry_msgs::TransformStamped &transform)
 Set a transform in the transform tree (adding it if necessary)
void setTransforms (const std::vector< geometry_msgs::TransformStamped > &transforms)
 Set a transform in the transform tree (adding it if necessary)
void transformPose (const std::string &from_frame, const Eigen::Affine3d &t_in, Eigen::Affine3d &t_out) const
 Transform a pose in from_frame to the target_frame.
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.
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.
 Transforms (const std::string &target_frame)
 Construct a transform list.
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.
virtual ~Transforms ()
 Destructor.

Static Public Member Functions

static bool sameFrame (const std::string &frame1, const std::string &frame2)
 Check if two frames end up being the same once the missing / are added as prefix (if they are missing)

Protected Attributes

std::string target_frame_
FixedTransformsMap transforms_

Detailed Description

Provides an implementation of a snapshot of a transform tree that can be easily queried for transforming different quantities. Transforms are maintained as a list of transforms to a particular frame. All stored transforms are considered fixed.

Definition at line 59 of file transforms.h.


Constructor & Destructor Documentation

robot_state::Transforms::Transforms ( const std::string &  target_frame)

Construct a transform list.

Definition at line 42 of file transforms.cpp.

Destructor.

Definition at line 69 of file transforms.cpp.


Member Function Documentation

bool robot_state::Transforms::canTransform ( const std::string &  from_frame) const [virtual]

Check whether data can be transformed from a particular frame.

Reimplemented in planning_scene::SceneTransforms, and robot_state::StateTransforms.

Definition at line 112 of file transforms.cpp.

const std::string & robot_state::Transforms::getTargetFrame ( ) const

Get the planning frame corresponding to this set of transforms.

Returns:
The planning frame

Definition at line 73 of file transforms.cpp.

const Eigen::Affine3d & robot_state::Transforms::getTransform ( const std::string &  from_frame) const [virtual]

Get transform for from_frame (w.r.t target frame)

Parameters:
from_frameThe string id of the frame for which the transform is being computed
Returns:
The required transform

Reimplemented in planning_scene::SceneTransforms, and robot_state::StateTransforms.

Definition at line 96 of file transforms.cpp.

bool robot_state::Transforms::isFixedFrame ( const std::string &  frame) const [virtual]

Check whether a frame stays constant as the state of the robot model changes.

Reimplemented in planning_scene::SceneTransforms.

Definition at line 88 of file transforms.cpp.

bool robot_state::Transforms::sameFrame ( const std::string &  frame1,
const std::string &  frame2 
) [static]

Check if two frames end up being the same once the missing / are added as prefix (if they are missing)

Definition at line 58 of file transforms.cpp.


Member Data Documentation

std::string robot_state::Transforms::target_frame_ [protected]

Definition at line 193 of file transforms.h.

Definition at line 194 of file transforms.h.


The documentation for this class was generated from the following files:


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