$search

object_manipulator::msg Namespace Reference

Functions

geometry_msgs::Pose applyShift (const geometry_msgs::Pose &pose, const tf::Vector3 &shift)
 Returns a pose that has been translated along the basis vectors of the quaternion in the input pose.
std_msgs::ColorRGBA createColorMsg (const float red, const float green, const float blue, const float alpha=1.0)
geometry_msgs::Point createPointMsg (const geometry_msgs::Vector3 &v)
geometry_msgs::Point createPointMsg (const tf::Point &v)
geometry_msgs::Point createPointMsg (const float x, const float y, const float z)
geometry_msgs::Pose createPoseMsg (const tf::Pose &p)
geometry_msgs::Pose createPoseMsg (const geometry_msgs::Vector3 &v, const geometry_msgs::Quaternion &q)
geometry_msgs::Pose createPoseMsg (const geometry_msgs::Point &v, const geometry_msgs::Quaternion &q)
geometry_msgs::PoseStamped createPoseStampedMsg (const btTransform &pose, const std::string &frame_id, const ros::Time &stamp)
geometry_msgs::PoseStamped createPoseStampedMsg (const geometry_msgs::TransformStamped ts)
geometry_msgs::PoseStamped createPoseStampedMsg (const geometry_msgs::Point &v, const geometry_msgs::Quaternion &q, const std::string &frame_id, const ros::Time &stamp)
geometry_msgs::PoseStamped createPoseStampedMsg (const geometry_msgs::Pose &p, const std::string &frame_id, const ros::Time &stamp)
geometry_msgs::Quaternion createQuaternionMsg (const tf::Quaternion &q)
geometry_msgs::Quaternion createQuaternionMsg (const float x, const float y, const float z, const float w)
geometry_msgs::Transform createTransformMsg (const geometry_msgs::Vector3 &v, const geometry_msgs::Quaternion &q)
geometry_msgs::Transform createTransformMsg (const geometry_msgs::Point &v, const geometry_msgs::Quaternion &q)
geometry_msgs::TransformStamped createTransformStampedMsg (const geometry_msgs::Vector3 &v, const geometry_msgs::Quaternion &q, const std::string &frame_id, const ros::Time &stamp)
geometry_msgs::TransformStamped createTransformStampedMsg (const geometry_msgs::Transform &t, const std::string &frame_id, const ros::Time &stamp)
geometry_msgs::Vector3 createVector3Msg (const geometry_msgs::Point &v)
geometry_msgs::Vector3 createVector3Msg (const tf::Vector3 &v)
geometry_msgs::Vector3 createVector3Msg (const float x, const float y, const float z)

Function Documentation

geometry_msgs::Pose object_manipulator::msg::applyShift ( const geometry_msgs::Pose pose,
const tf::Vector3 shift 
) [inline]

Returns a pose that has been translated along the basis vectors of the quaternion in the input pose.

Definition at line 218 of file msg_helpers.h.

std_msgs::ColorRGBA object_manipulator::msg::createColorMsg ( const float  red,
const float  green,
const float  blue,
const float  alpha = 1.0 
) [inline]

Definition at line 57 of file msg_helpers.h.

geometry_msgs::Point object_manipulator::msg::createPointMsg ( const geometry_msgs::Vector3 v  )  [inline]

Definition at line 108 of file msg_helpers.h.

geometry_msgs::Point object_manipulator::msg::createPointMsg ( const tf::Point v  )  [inline]

Definition at line 100 of file msg_helpers.h.

geometry_msgs::Point object_manipulator::msg::createPointMsg ( const float  x,
const float  y,
const float  z 
) [inline]

Definition at line 92 of file msg_helpers.h.

geometry_msgs::Pose object_manipulator::msg::createPoseMsg ( const tf::Pose p  )  [inline]

Definition at line 152 of file msg_helpers.h.

geometry_msgs::Pose object_manipulator::msg::createPoseMsg ( const geometry_msgs::Vector3 v,
const geometry_msgs::Quaternion q 
) [inline]

Definition at line 144 of file msg_helpers.h.

geometry_msgs::Pose object_manipulator::msg::createPoseMsg ( const geometry_msgs::Point v,
const geometry_msgs::Quaternion q 
) [inline]

Definition at line 136 of file msg_helpers.h.

geometry_msgs::PoseStamped object_manipulator::msg::createPoseStampedMsg ( const btTransform &  pose,
const std::string &  frame_id,
const ros::Time stamp 
) [inline]

Definition at line 180 of file msg_helpers.h.

geometry_msgs::PoseStamped object_manipulator::msg::createPoseStampedMsg ( const geometry_msgs::TransformStamped  ts  )  [inline]

Definition at line 174 of file msg_helpers.h.

geometry_msgs::PoseStamped object_manipulator::msg::createPoseStampedMsg ( const geometry_msgs::Point v,
const geometry_msgs::Quaternion q,
const std::string &  frame_id,
const ros::Time stamp 
) [inline]

Definition at line 169 of file msg_helpers.h.

geometry_msgs::PoseStamped object_manipulator::msg::createPoseStampedMsg ( const geometry_msgs::Pose p,
const std::string &  frame_id,
const ros::Time stamp 
) [inline]

Definition at line 160 of file msg_helpers.h.

geometry_msgs::Quaternion object_manipulator::msg::createQuaternionMsg ( const tf::Quaternion q  )  [inline]

Definition at line 126 of file msg_helpers.h.

geometry_msgs::Quaternion object_manipulator::msg::createQuaternionMsg ( const float  x,
const float  y,
const float  z,
const float  w 
) [inline]

Definition at line 117 of file msg_helpers.h.

geometry_msgs::Transform object_manipulator::msg::createTransformMsg ( const geometry_msgs::Vector3 v,
const geometry_msgs::Quaternion q 
) [inline]

Definition at line 195 of file msg_helpers.h.

geometry_msgs::Transform object_manipulator::msg::createTransformMsg ( const geometry_msgs::Point v,
const geometry_msgs::Quaternion q 
) [inline]

Definition at line 187 of file msg_helpers.h.

geometry_msgs::TransformStamped object_manipulator::msg::createTransformStampedMsg ( const geometry_msgs::Vector3 v,
const geometry_msgs::Quaternion q,
const std::string &  frame_id,
const ros::Time stamp 
) [inline]

Definition at line 212 of file msg_helpers.h.

geometry_msgs::TransformStamped object_manipulator::msg::createTransformStampedMsg ( const geometry_msgs::Transform t,
const std::string &  frame_id,
const ros::Time stamp 
) [inline]

Definition at line 203 of file msg_helpers.h.

geometry_msgs::Vector3 object_manipulator::msg::createVector3Msg ( const geometry_msgs::Point v  )  [inline]

Definition at line 83 of file msg_helpers.h.

geometry_msgs::Vector3 object_manipulator::msg::createVector3Msg ( const tf::Vector3 v  )  [inline]

Definition at line 75 of file msg_helpers.h.

geometry_msgs::Vector3 object_manipulator::msg::createVector3Msg ( const float  x,
const float  y,
const float  z 
) [inline]

Definition at line 67 of file msg_helpers.h.

 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


object_manipulator
Author(s): Matei Ciocarlie and Kaijen Hsiao
autogenerated on Fri Mar 1 18:35:46 2013