Public Member Functions | Static Public Member Functions | Protected Attributes | List of all members
moveit::core::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 moveit::core::Transforms:
Inheritance graph
[legend]

Public Member Functions

virtual bool canTransform (const std::string &from_frame) const
 Check whether data can be transformed from a particular frame. More...
 
const std::string & getTargetFrame () const
 Get the planning frame corresponding to this set of transforms. More...
 
virtual const Eigen::Affine3d & getTransform (const std::string &from_frame) const
 Get transform for from_frame (w.r.t target frame) More...
 
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. More...
 
 Transforms (const std::string &target_frame)
 Construct a transform list. More...
 
virtual ~Transforms ()
 Destructor. More...
 
Setting and retrieving transforms maintained in this class
const FixedTransformsMapgetAllTransforms () 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::Affine3d &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::Affine3d (w.r.t the planning frame) More...
 
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. 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::Affine3d &t_in, Eigen::Affine3d &t_out) const
 Transform a pose in from_frame to the target_frame. More...
 

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) More...
 

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 61 of file transforms.h.

Constructor & Destructor Documentation

moveit::core::Transforms::Transforms ( const std::string &  target_frame)

Construct a transform list.

Definition at line 46 of file transforms.cpp.

moveit::core::Transforms::~Transforms ( )
virtualdefault

Destructor.

Member Function Documentation

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 118 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.

Parameters
transformsThe output transforms

Definition at line 165 of file transforms.cpp.

const FixedTransformsMap & moveit::core::Transforms::getAllTransforms ( ) const

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 82 of file transforms.cpp.

const std::string & moveit::core::Transforms::getTargetFrame ( ) const

Get the planning frame corresponding to this set of transforms.

Returns
The planning frame

Definition at line 77 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)

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

Reimplemented in planning_scene::SceneTransforms.

Definition at line 100 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 92 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 64 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 87 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)

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

Definition at line 127 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)

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

Definition at line 144 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)

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

Definition at line 159 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.

Parameters
from_frameThe frame in which the input pose is specified
t_inThe input pose (in from_frame)
t_outThe 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.

Parameters
from_frameThe frame in which the input quaternion is specified
v_inThe input quaternion (in from_frame)
v_outThe 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.

Parameters
from_frameThe frame in which the input rotation matrix is specified
m_inThe input rotation matrix (in from_frame)
m_outThe 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.

Parameters
from_frameThe frame from which the transform is computed
v_inThe input vector (in from_frame)
v_outThe resultant (transformed) vector

Definition at line 139 of file transforms.h.

Member Data Documentation

std::string moveit::core::Transforms::target_frame_
protected

Definition at line 198 of file transforms.h.

FixedTransformsMap moveit::core::Transforms::transforms_
protected

Definition at line 199 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 Wed Jul 10 2019 04:03:06