Public Member Functions | Private Member Functions | Private Attributes | List of all members
planning_scene::SceneTransforms Class Reference
Inheritance diagram for planning_scene::SceneTransforms:
Inheritance graph
[legend]

Public Member Functions

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)
 
- Public Member Functions inherited from moveit::core::Transforms
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 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::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...
 

Private Member Functions

bool knowsObjectFrame (const std::string &frame_id) const
 

Private Attributes

const PlanningScenescene_
 

Additional Inherited Members

- Static Public Member Functions inherited from moveit::core::Transforms
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 inherited from moveit::core::Transforms
std::string target_frame_
 
FixedTransformsMap transforms_map_
 

Detailed Description

Definition at line 92 of file planning_scene.cpp.

Constructor & Destructor Documentation

◆ SceneTransforms()

planning_scene::SceneTransforms::SceneTransforms ( const PlanningScene scene)
inline

Definition at line 95 of file planning_scene.cpp.

Member Function Documentation

◆ canTransform()

bool planning_scene::SceneTransforms::canTransform ( const std::string &  from_frame) const
inlineoverridevirtual

Check whether data can be transformed from a particular frame.

Reimplemented from moveit::core::Transforms.

Definition at line 99 of file planning_scene.cpp.

◆ getTransform()

const Eigen::Isometry3d& planning_scene::SceneTransforms::getTransform ( const std::string &  from_frame) const
inlineoverridevirtual

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. It is guaranteed to be a valid isometry.

Reimplemented from moveit::core::Transforms.

Definition at line 116 of file planning_scene.cpp.

◆ isFixedFrame()

bool planning_scene::SceneTransforms::isFixedFrame ( const std::string &  frame) const
inlineoverridevirtual

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 from moveit::core::Transforms.

Definition at line 104 of file planning_scene.cpp.

◆ knowsObjectFrame()

bool planning_scene::SceneTransforms::knowsObjectFrame ( const std::string &  frame_id) const
inlineprivate

Definition at line 123 of file planning_scene.cpp.

Member Data Documentation

◆ scene_

const PlanningScene* planning_scene::SceneTransforms::scene_
private

Definition at line 128 of file planning_scene.cpp.


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


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Sun Mar 3 2024 03:23:37