Position and orientation information with respect to a given coordinate frame. More...
#include <Pose.h>
Public Member Functions | |
const Orientation & | getOrientation () const |
Orientation value accessor (immutable). | |
Orientation & | getOrientation () |
Orientation value accessor. | |
const Position & | getPosition () const |
Position value accessor. | |
Position & | getPosition () |
Position value accessor (immutable). | |
const std::string & | getRobotFixedFrameID () const |
Robot fixed frame ID value accessor. | |
Pose (const std::string &robot_fixed_frame_id="", const Position &position=Position(), const Orientation &orientation=Orientation()) | |
Create a new Pose. | |
Pose (const std::string &robot_fixed_frame_id, const geometry_msgs::Pose &pose) | |
Create a new Pose. | |
Pose (const geometry_msgs::PoseStamped &pose) | |
Create a new Pose. | |
Pose (const std::string &robot_fixed_frame_id, const geometry_msgs::PoseWithCovariance &pose) | |
Create a new Pose. | |
Pose (const geometry_msgs::PoseWithCovarianceStamped &pose) | |
Create a new Pose. | |
Pose (const std::string &robot_fixed_frame_id, const geometry_msgs::Transform &tf) | |
Create a new Pose. | |
Pose (const geometry_msgs::TransformStamped &tf) | |
Create a new Pose. | |
Pose (const std::string &robot_fixed_frame_id, const tf2::Transform &tf) | |
Create a new Pose. | |
void | setOrientation (const Orientation &orientation) |
Orientation value mutator. | |
void | setPosition (const Position &position) |
Position value mutator. | |
void | setRobotFixedFrameID (const std::string &robot_fixed_frame_id) |
Frame ID value mutator. | |
geometry_msgs::Pose | toROSPoseMessage () const |
geometry_msgs::PoseStamped | toROSPoseStampedMessage () const |
geometry_msgs::Transform | toROSTransformMessage () const |
tf2::Transform | toTF2Transform () const |
Private Attributes | |
Orientation | orientation_ |
Position | position_ |
std::string | robot_fixed_frame_id_ |
Position and orientation information with respect to a given coordinate frame.
A pose contains position and orientation information as well as a coordinate frame identifier. This coordinate frame should be a fixed frame on the robot. This class is useful for internal data management within the graspdb library. Convenience functions are added for use with ROS messages.
rail::pick_and_place::graspdb::Pose::Pose | ( | const std::string & | robot_fixed_frame_id = "" , |
const Position & | position = Position() , |
||
const Orientation & | orientation = Orientation() |
||
) |
Create a new Pose.
Creates a new Pose with the given frame identifier, position, and orientation (defaults are 0).
robot_fixed_frame_id | The reference frame identifier (defaults to the empty string). |
position | The position values (defaults are 0). |
orientation | The orientation values (defaults are 0). |
rail::pick_and_place::graspdb::Pose::Pose | ( | const std::string & | robot_fixed_frame_id, |
const geometry_msgs::Pose & | pose | ||
) |
Pose::Pose | ( | const geometry_msgs::PoseStamped & | pose | ) |
rail::pick_and_place::graspdb::Pose::Pose | ( | const std::string & | robot_fixed_frame_id, |
const geometry_msgs::PoseWithCovariance & | pose | ||
) |
Pose::Pose | ( | const geometry_msgs::PoseWithCovarianceStamped & | pose | ) |
rail::pick_and_place::graspdb::Pose::Pose | ( | const std::string & | robot_fixed_frame_id, |
const geometry_msgs::Transform & | tf | ||
) |
Pose::Pose | ( | const geometry_msgs::TransformStamped & | tf | ) |
Pose::Pose | ( | const std::string & | robot_fixed_frame_id, |
const tf2::Transform & | tf | ||
) |
const Orientation & Pose::getOrientation | ( | ) | const |
Orientation value accessor (immutable).
Get the orientation value of this Pose.
const Position & Pose::getPosition | ( | ) | const |
Position & Pose::getPosition | ( | ) |
const string & Pose::getRobotFixedFrameID | ( | ) | const |
void Pose::setOrientation | ( | const Orientation & | orientation | ) |
Orientation value mutator.
Set the orientation value of this Pose.
orientation | The new orientation value. |
void Pose::setPosition | ( | const Position & | position | ) |
void Pose::setRobotFixedFrameID | ( | const std::string & | robot_fixed_frame_id | ) |
geometry_msgs::Pose Pose::toROSPoseMessage | ( | ) | const |
geometry_msgs::PoseStamped Pose::toROSPoseStampedMessage | ( | ) | const |
geometry_msgs::Transform rail::pick_and_place::graspdb::Pose::toROSTransformMessage | ( | ) | const |
Converts this Pose object into a ROS Transform message.
tf2::Transform Pose::toTF2Transform | ( | ) | const |
Orientation data.
std::string rail::pick_and_place::graspdb::Pose::robot_fixed_frame_id_ [private] |