Namespaces | Functions
kdl_msg.h File Reference
#include "kdl/frames.hpp"
#include <geometry_msgs/Point.h>
#include <geometry_msgs/Pose.h>
#include <geometry_msgs/Quaternion.h>
#include <geometry_msgs/Transform.h>
#include <geometry_msgs/Twist.h>
#include <geometry_msgs/Vector3.h>
#include <geometry_msgs/Wrench.h>
Include dependency graph for kdl_msg.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Namespaces

namespace  tf

Functions

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


kdl_conversions
Author(s): Adam Leeper
autogenerated on Thu Jun 6 2019 18:45:30