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>
Public Member Functions | |
virtual bool | canTransform (const std::string &from_frame) const |
Check whether data can be transformed from a particular frame. | |
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. This is true for any transform mainatined by this object. | |
Transforms (const std::string &target_frame) | |
Construct a transform list. | |
virtual | ~Transforms () |
Destructor. | |
Setting and retrieving transforms maintained in this class | |
const FixedTransformsMap & | getAllTransforms () const |
Return all the transforms. | |
void | copyTransforms (std::vector< geometry_msgs::TransformStamped > &transforms) const |
Get a vector of all the transforms as ROS messages. | |
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 | 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) | |
Applying transforms | |
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. | |
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. | |
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. | |
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_ |
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 61 of file transforms.h.
moveit::core::Transforms::Transforms | ( | const std::string & | target_frame | ) |
Construct a transform list.
Definition at line 42 of file transforms.cpp.
moveit::core::Transforms::~Transforms | ( | ) | [virtual] |
Destructor.
Definition at line 70 of file transforms.cpp.
bool moveit::core::Transforms::canTransform | ( | const std::string & | from_frame | ) | const [virtual] |
Check whether data can be transformed from a particular frame.
Reimplemented in planning_scene::SceneTransforms.
Definition at line 115 of file transforms.cpp.
void moveit::core::Transforms::copyTransforms | ( | std::vector< geometry_msgs::TransformStamped > & | transforms | ) | const |
Get a vector of all the transforms as ROS messages.
transforms | The output transforms |
Definition at line 161 of file transforms.cpp.
const moveit::core::FixedTransformsMap & moveit::core::Transforms::getAllTransforms | ( | ) | const |
Return all the transforms.
Definition at line 79 of file transforms.cpp.
const std::string & moveit::core::Transforms::getTargetFrame | ( | ) | const |
Get the planning frame corresponding to this set of transforms.
Definition at line 74 of file transforms.cpp.
const Eigen::Affine3d & moveit::core::Transforms::getTransform | ( | const std::string & | from_frame | ) | const [virtual] |
Get transform for from_frame (w.r.t target frame)
from_frame | The string id of the frame for which the transform is being computed |
Reimplemented in planning_scene::SceneTransforms.
Definition at line 97 of file transforms.cpp.
bool moveit::core::Transforms::isFixedFrame | ( | const std::string & | frame | ) | const [virtual] |
Check whether a frame stays constant as the state of the robot model changes. This is true for any transform mainatined by this object.
Reimplemented in planning_scene::SceneTransforms.
Definition at line 89 of file transforms.cpp.
bool moveit::core::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 59 of file transforms.cpp.
void moveit::core::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)
Definition at line 84 of file transforms.cpp.
void moveit::core::Transforms::setTransform | ( | const Eigen::Affine3d & | t, |
const std::string & | from_frame | ||
) |
Set a transform in the transform tree (adding it if necessary)
t | The input transform (w.r.t the target frame) |
from_frame | The frame for which the input transform is specified |
Definition at line 124 of file transforms.cpp.
void moveit::core::Transforms::setTransform | ( | const geometry_msgs::TransformStamped & | transform | ) |
Set a transform in the transform tree (adding it if necessary)
transform | The input transform (the frame_id must match the target frame) |
Definition at line 140 of file transforms.cpp.
void moveit::core::Transforms::setTransforms | ( | const std::vector< geometry_msgs::TransformStamped > & | transforms | ) |
Set a transform in the transform tree (adding it if necessary)
transform | The input transforms (the frame_id must match the target frame) |
Definition at line 155 of file transforms.cpp.
void moveit::core::Transforms::transformPose | ( | const std::string & | from_frame, |
const Eigen::Affine3d & | t_in, | ||
Eigen::Affine3d & | t_out | ||
) | const [inline] |
Transform a pose in from_frame to the target_frame.
from_frame | The frame in which the input pose is specified |
t_in | The input pose (in from_frame) |
t_out | The resultant (transformed) pose |
Definition at line 173 of file transforms.h.
void moveit::core::Transforms::transformQuaternion | ( | const std::string & | from_frame, |
const Eigen::Quaterniond & | q_in, | ||
Eigen::Quaterniond & | q_out | ||
) | const [inline] |
Transform a quaternion in from_frame to the target_frame.
from_frame | The frame in which the input quaternion is specified |
v_in | The input quaternion (in from_frame) |
v_out | The resultant (transformed) quaternion |
Definition at line 150 of file transforms.h.
void moveit::core::Transforms::transformRotationMatrix | ( | const std::string & | from_frame, |
const Eigen::Matrix3d & | m_in, | ||
Eigen::Matrix3d & | m_out | ||
) | const [inline] |
Transform a rotation matrix in from_frame to the target_frame.
from_frame | The frame in which the input rotation matrix is specified |
m_in | The input rotation matrix (in from_frame) |
m_out | The resultant (transformed) rotation matrix |
Definition at line 162 of file transforms.h.
void moveit::core::Transforms::transformVector3 | ( | const std::string & | from_frame, |
const Eigen::Vector3d & | v_in, | ||
Eigen::Vector3d & | v_out | ||
) | const [inline] |
Transform a vector in from_frame to the target_frame Note: assumes that v_in and v_out are "free" vectors, not points.
from_frame | The frame from which the transform is computed |
v_in | The input vector (in from_frame) |
v_out | The resultant (transformed) vector |
Definition at line 139 of file transforms.h.
std::string moveit::core::Transforms::target_frame_ [protected] |
Definition at line 198 of file transforms.h.
Definition at line 199 of file transforms.h.