Public Member Functions | Private Attributes
rail::pick_and_place::graspdb::Pose Class Reference

Position and orientation information with respect to a given coordinate frame. More...

#include <Pose.h>

List of all members.

Public Member Functions

const OrientationgetOrientation () const
 Orientation value accessor (immutable).
OrientationgetOrientation ()
 Orientation value accessor.
const PositiongetPosition () const
 Position value accessor.
PositiongetPosition ()
 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_

Detailed Description

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.

Definition at line 47 of file Pose.h.


Constructor & Destructor Documentation

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

Parameters:
robot_fixed_frame_idThe reference frame identifier (defaults to the empty string).
positionThe position values (defaults are 0).
orientationThe orientation values (defaults are 0).
rail::pick_and_place::graspdb::Pose::Pose ( const std::string &  robot_fixed_frame_id,
const geometry_msgs::Pose &  pose 
)

Create a new Pose.

Creates a new Pose with the given frame identifier and pose data from the given ROS message.

Parameters:
robot_fixed_frame_idThe reference frame identifier.
poseThe ROS Pose message to extract position and orientation data from.
Pose::Pose ( const geometry_msgs::PoseStamped &  pose)

Create a new Pose.

Creates a new Pose with the given pose data from the given ROS PoseStamped message. Timestamp information is ignored from the header.

Parameters:
poseThe ROS PoseStamped message to extract data from.

Definition at line 29 of file Pose.cpp.

rail::pick_and_place::graspdb::Pose::Pose ( const std::string &  robot_fixed_frame_id,
const geometry_msgs::PoseWithCovariance &  pose 
)

Create a new Pose.

Creates a new Pose with the given pose data from the given frame identifier and ROS PoseWithCovariance message. Covariance information is ignored.

Parameters:
robot_fixed_frame_idThe reference frame identifier.
poseThe ROS PoseWithCovariance message to extract data from.
Pose::Pose ( const geometry_msgs::PoseWithCovarianceStamped &  pose)

Create a new Pose.

Creates a new Pose with the given pose data from the given frame identifier and ROS PoseWithCovarianceStamped message. Timestamp and covariance information is ignored.

Parameters:
poseThe ROS PoseWithCovariance message to extract data from.

Definition at line 39 of file Pose.cpp.

rail::pick_and_place::graspdb::Pose::Pose ( const std::string &  robot_fixed_frame_id,
const geometry_msgs::Transform &  tf 
)

Create a new Pose.

Creates a new Pose with the given frame identifier and positional data from the given ROS Transform message.

Parameters:
robot_fixed_frame_idThe reference frame identifier.
positionThe ROS Transform message to extract position and orientation data from.
Pose::Pose ( const geometry_msgs::TransformStamped &  tf)

Create a new Pose.

Creates a new Pose with the positional data from the given ROS TransformStamped message. The frame ID is taken from the header (the parent frame). Timestamp information and child frame ID is ignored.

Parameters:
positionThe ROS TransformStamped message to extract data from.

Definition at line 50 of file Pose.cpp.

Pose::Pose ( const std::string &  robot_fixed_frame_id,
const tf2::Transform tf 
)

Create a new Pose.

Creates a new Pose with the given frame identifier and positional data from the given ROS tf2 Transform.

Parameters:
robot_fixed_frame_idThe reference frame identifier.
positionThe ROS tf2 Transform to extract position and orientation data from.

Definition at line 56 of file Pose.cpp.


Member Function Documentation

const Orientation & Pose::getOrientation ( ) const

Orientation value accessor (immutable).

Get the orientation value of this Pose.

Returns:
The orientation value.

Definition at line 91 of file Pose.cpp.

Orientation value accessor.

Get the orientation value of this Pose.

Returns:
The orientation value.

Definition at line 96 of file Pose.cpp.

const Position & Pose::getPosition ( ) const

Position value accessor.

Get the position value of this Pose.

Returns:
The position value.

Definition at line 76 of file Pose.cpp.

Position value accessor (immutable).

Get the position value of this Pose.

Returns:
The position value.

Definition at line 81 of file Pose.cpp.

const string & Pose::getRobotFixedFrameID ( ) const

Robot fixed frame ID value accessor.

Get the robot fixed frame ID value of this Pose.

Returns:
The robot fixed frame ID value.

Definition at line 66 of file Pose.cpp.

void Pose::setOrientation ( const Orientation orientation)

Orientation value mutator.

Set the orientation value of this Pose.

Parameters:
orientationThe new orientation value.

Definition at line 86 of file Pose.cpp.

void Pose::setPosition ( const Position position)

Position value mutator.

Set the position value of this Pose.

Parameters:
positionThe new position value.

Definition at line 71 of file Pose.cpp.

void Pose::setRobotFixedFrameID ( const std::string &  robot_fixed_frame_id)

Frame ID value mutator.

Set the frame ID value of this Pose.

Parameters:
frame_idThe new frame ID value.

Definition at line 61 of file Pose.cpp.

geometry_msgs::Pose Pose::toROSPoseMessage ( ) const

Converts this Pose object into a ROS Pose message.

Returns:
The ROS Pose message with this pose data.

Definition at line 101 of file Pose.cpp.

geometry_msgs::PoseStamped Pose::toROSPoseStampedMessage ( ) const

Converts this Pose object into a ROS PoseStamped message. Timestamp information is set to 0.

Returns:
The ROS PoseStamped message with this pose data.

Definition at line 109 of file Pose.cpp.

Converts this Pose object into a ROS Transform message.

Returns:
The ROS Transform message with this positional data.

Converts this Pose object into a ROS tf2 Transform.

Returns:
The ROS tf2 Transform with this positional data.

Definition at line 118 of file Pose.cpp.


Member Data Documentation

Orientation data.

Definition at line 239 of file Pose.h.

Position data.

Definition at line 237 of file Pose.h.

Frame identifier.

Definition at line 235 of file Pose.h.


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


graspdb
Author(s): Russell Toris
autogenerated on Thu Jun 6 2019 19:44:01