|
moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
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.hpp>

Public Member Functions | |
| Transforms (const Transforms &)=delete | |
| Transforms cannot be copy-constructed. | |
| Transforms & | operator= (const Transforms &)=delete |
| Transforms cannot be copy-assigned. | |
| Transforms (const std::string &target_frame) | |
| Construct a transform list. | |
| virtual | ~Transforms () |
| Destructor. | |
| const std::string & | getTargetFrame () const |
| Get the planning frame corresponding to this set of transforms. | |
| virtual bool | canTransform (const std::string &from_frame) const |
| Check whether data can be transformed from a particular 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. | |
| virtual const Eigen::Isometry3d & | getTransform (const std::string &from_frame) const |
| Get transform for from_frame (w.r.t target frame) | |
Setting and retrieving transforms maintained in this class | |
| const FixedTransformsMap & | getAllTransforms () const |
| Return all the transforms. | |
| void | copyTransforms (std::vector< geometry_msgs::msg::TransformStamped > &transforms) const |
| Get a vector of all the transforms as ROS messages. | |
| void | setTransform (const Eigen::Isometry3d &t, const std::string &from_frame) |
| Set a transform in the transform tree (adding it if necessary) | |
| void | setTransform (const geometry_msgs::msg::TransformStamped &transform) |
| Set a transform in the transform tree (adding it if necessary) | |
| void | setTransforms (const std::vector< geometry_msgs::msg::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::Isometry3d (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::Isometry3d &t_in, Eigen::Isometry3d &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_map_ |
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 58 of file transforms.hpp.
|
delete |
Transforms cannot be copy-constructed.
| moveit::core::Transforms::Transforms | ( | const std::string & | target_frame | ) |
Construct a transform list.
Definition at line 57 of file transforms.cpp.
|
virtualdefault |
Destructor.
|
virtual |
Check whether data can be transformed from a particular frame.
Reimplemented in planning_scene::SceneTransforms.
Definition at line 128 of file transforms.cpp.
| void moveit::core::Transforms::copyTransforms | ( | std::vector< geometry_msgs::msg::TransformStamped > & | transforms | ) | const |
Get a vector of all the transforms as ROS messages.
| transforms | The output transforms. They are guaranteed to be valid isometries. |
Definition at line 178 of file transforms.cpp.

| const FixedTransformsMap & moveit::core::Transforms::getAllTransforms | ( | ) | const |
Return all the transforms.
Definition at line 84 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 79 of file transforms.cpp.

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

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

|
delete |
Transforms cannot be copy-assigned.
|
static |
Check if two frames end up being the same once the missing / are added as prefix (if they are missing)
Definition at line 70 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::Isometry3d (w.r.t the planning frame)
Definition at line 89 of file transforms.cpp.
| void moveit::core::Transforms::setTransform | ( | const Eigen::Isometry3d & | 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 140 of file transforms.cpp.

| void moveit::core::Transforms::setTransform | ( | const geometry_msgs::msg::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 151 of file transforms.cpp.

| void moveit::core::Transforms::setTransforms | ( | const std::vector< geometry_msgs::msg::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 172 of file transforms.cpp.

|
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). Make sure the pose is a valid isometry. |
| t_out | The resultant (transformed) pose. It is guaranteed to be a valid isometry. |
Definition at line 184 of file transforms.hpp.


|
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). Make sure the quaternion is normalized. |
| v_out | The resultant (transformed) quaternion. It is guaranteed to be a valid and normalized quaternion. |
Definition at line 159 of file transforms.hpp.


|
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). Make sure the matrix is a valid rotation matrix. |
| m_out | The resultant (transformed) rotation matrix. It is guaranteed to be a valid rotation matrix. |
Definition at line 172 of file transforms.hpp.

|
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 147 of file transforms.hpp.

|
protected |
Definition at line 210 of file transforms.hpp.
|
protected |
Definition at line 211 of file transforms.hpp.