Functions
tf Namespace Reference

Functions

void pointKDLToMsg (const KDL::Vector &k, geometry_msgs::Point &m)
 Converts a KDL Vector into a geometry_msgs Vector3. More...
 
void pointMsgToKDL (const geometry_msgs::Point &m, KDL::Vector &k)
 Conversion functions from/to the corresponding KDL and geometry_msgs types. More...
 
void poseKDLToMsg (const KDL::Frame &k, geometry_msgs::Pose &m)
 Converts a KDL Frame into a Pose message. More...
 
void PoseKDLToMsg (const KDL::Frame &k, geometry_msgs::Pose &m) __attribute__((deprecated))
 Converts a KDL Frame into a Pose message. More...
 
void poseMsgToKDL (const geometry_msgs::Pose &m, KDL::Frame &k)
 Converts a Pose message into a KDL Frame. More...
 
void PoseMsgToKDL (const geometry_msgs::Pose &m, KDL::Frame &k) __attribute__((deprecated))
 Converts a Pose message into a KDL Frame. More...
 
void quaternionKDLToMsg (const KDL::Rotation &k, geometry_msgs::Quaternion &m)
 Converts a KDL Rotation into a message quaternion. More...
 
void quaternionMsgToKDL (const geometry_msgs::Quaternion &m, KDL::Rotation &k)
 Converts a quaternion message into a KDL Rotation. More...
 
void transformKDLToMsg (const KDL::Frame &k, geometry_msgs::Transform &m)
 Converts a KDL Frame into a Transform message. More...
 
void transformMsgToKDL (const geometry_msgs::Transform &m, KDL::Frame &k)
 Converts a Transform message into a KDL Frame. More...
 
void twistKDLToMsg (const KDL::Twist &k, geometry_msgs::Twist &m)
 Converts a KDL Twist into a Twist message. More...
 
void TwistKDLToMsg (const KDL::Twist &k, geometry_msgs::Twist &m) __attribute__((deprecated))
 Converts a KDL Twist into a Twist message. More...
 
void twistMsgToKDL (const geometry_msgs::Twist &m, KDL::Twist &k)
 Converts a Twist message into a KDL Twist. More...
 
void TwistMsgToKDL (const geometry_msgs::Twist &m, KDL::Twist &k) __attribute__((deprecated))
 Converts a Twist message into a KDL Twist. More...
 
void vectorKDLToMsg (const KDL::Vector &k, geometry_msgs::Vector3 &m)
 Converts a KDL Vector into a Vector3 message. More...
 
void vectorMsgToKDL (const geometry_msgs::Vector3 &m, KDL::Vector &k)
 Converts a Vector3 message into a KDL Vector. More...
 
void wrenchKDLToMsg (const KDL::Wrench &k, geometry_msgs::Wrench &m)
 Converts a KDL Wrench into a Wrench message. More...
 
void wrenchMsgToKDL (const geometry_msgs::Wrench &m, KDL::Wrench &k)
 Converts a Wrench message into a KDL Wrench. More...
 

Function Documentation

void tf::pointKDLToMsg ( const KDL::Vector k,
geometry_msgs::Point &  m 
)

Converts a KDL Vector into a geometry_msgs Vector3.

Definition at line 41 of file kdl_msg.cpp.

void tf::pointMsgToKDL ( const geometry_msgs::Point &  m,
KDL::Vector k 
)

Conversion functions from/to the corresponding KDL and geometry_msgs types.

Converts a geometry_msgs Point into a KDL Vector

Definition at line 34 of file kdl_msg.cpp.

void tf::poseKDLToMsg ( const KDL::Frame k,
geometry_msgs::Pose &  m 
)

Converts a KDL Frame into a Pose message.

Definition at line 57 of file kdl_msg.cpp.

void tf::PoseKDLToMsg ( const KDL::Frame k,
geometry_msgs::Pose &  m 
)

Converts a KDL Frame into a Pose message.

Definition at line 155 of file kdl_msg.cpp.

void tf::poseMsgToKDL ( const geometry_msgs::Pose &  m,
KDL::Frame k 
)

Converts a Pose message into a KDL Frame.

Definition at line 48 of file kdl_msg.cpp.

void tf::PoseMsgToKDL ( const geometry_msgs::Pose &  m,
KDL::Frame k 
)

Converts a Pose message into a KDL Frame.

Definition at line 152 of file kdl_msg.cpp.

void tf::quaternionKDLToMsg ( const KDL::Rotation k,
geometry_msgs::Quaternion &  m 
)

Converts a KDL Rotation into a message quaternion.

Definition at line 71 of file kdl_msg.cpp.

void tf::quaternionMsgToKDL ( const geometry_msgs::Quaternion &  m,
KDL::Rotation k 
)

Converts a quaternion message into a KDL Rotation.

Definition at line 66 of file kdl_msg.cpp.

void tf::transformKDLToMsg ( const KDL::Frame k,
geometry_msgs::Transform &  m 
)

Converts a KDL Frame into a Transform message.

Definition at line 85 of file kdl_msg.cpp.

void tf::transformMsgToKDL ( const geometry_msgs::Transform &  m,
KDL::Frame k 
)

Converts a Transform message into a KDL Frame.

Definition at line 76 of file kdl_msg.cpp.

void tf::twistKDLToMsg ( const KDL::Twist k,
geometry_msgs::Twist &  m 
)

Converts a KDL Twist into a Twist message.

Definition at line 94 of file kdl_msg.cpp.

void tf::TwistKDLToMsg ( const KDL::Twist k,
geometry_msgs::Twist &  m 
)

Converts a KDL Twist into a Twist message.

Definition at line 161 of file kdl_msg.cpp.

void tf::twistMsgToKDL ( const geometry_msgs::Twist &  m,
KDL::Twist k 
)

Converts a Twist message into a KDL Twist.

Definition at line 104 of file kdl_msg.cpp.

void tf::TwistMsgToKDL ( const geometry_msgs::Twist &  m,
KDL::Twist k 
)

Converts a Twist message into a KDL Twist.

Definition at line 158 of file kdl_msg.cpp.

void tf::vectorKDLToMsg ( const KDL::Vector k,
geometry_msgs::Vector3 &  m 
)

Converts a KDL Vector into a Vector3 message.

Definition at line 121 of file kdl_msg.cpp.

void tf::vectorMsgToKDL ( const geometry_msgs::Vector3 &  m,
KDL::Vector k 
)

Converts a Vector3 message into a KDL Vector.

Definition at line 114 of file kdl_msg.cpp.

void tf::wrenchKDLToMsg ( const KDL::Wrench k,
geometry_msgs::Wrench &  m 
)

Converts a KDL Wrench into a Wrench message.

Definition at line 138 of file kdl_msg.cpp.

void tf::wrenchMsgToKDL ( const geometry_msgs::Wrench &  m,
KDL::Wrench k 
)

Converts a Wrench message into a KDL Wrench.

Definition at line 128 of file kdl_msg.cpp.



kdl_conversions
Author(s): Adam Leeper
autogenerated on Mon Jun 10 2019 12:25:24