Namespaces | Functions
tf2_geometry_msgs.h File Reference
#include <boost/array.hpp>
#include <tf2/convert.h>
#include <tf2/LinearMath/Quaternion.h>
#include <tf2/LinearMath/Transform.h>
#include <geometry_msgs/PointStamped.h>
#include <geometry_msgs/QuaternionStamped.h>
#include <geometry_msgs/TransformStamped.h>
#include <geometry_msgs/Vector3Stamped.h>
#include <geometry_msgs/Pose.h>
#include <geometry_msgs/PoseStamped.h>
#include <geometry_msgs/PoseWithCovarianceStamped.h>
#include <geometry_msgs/Wrench.h>
#include <geometry_msgs/WrenchStamped.h>
#include <kdl/frames.hpp>
Include dependency graph for tf2_geometry_msgs.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Namespaces

 tf2
 

Functions

template<>
void tf2::doTransform (const geometry_msgs::Point &t_in, geometry_msgs::Point &t_out, const geometry_msgs::TransformStamped &transform)
 Apply a geometry_msgs TransformStamped to an geometry_msgs Point type. This function is a specialization of the doTransform template defined in tf2/convert.h. More...
 
template<>
void tf2::doTransform (const geometry_msgs::PointStamped &t_in, geometry_msgs::PointStamped &t_out, const geometry_msgs::TransformStamped &transform)
 Apply a geometry_msgs TransformStamped to an stamped geometry_msgs Point type. This function is a specialization of the doTransform template defined in tf2/convert.h. More...
 
template<>
void tf2::doTransform (const geometry_msgs::Quaternion &t_in, geometry_msgs::Quaternion &t_out, const geometry_msgs::TransformStamped &transform)
 Apply a geometry_msgs TransformStamped to an geometry_msgs Quaternion type. This function is a specialization of the doTransform template defined in tf2/convert.h. More...
 
template<>
void tf2::doTransform (const geometry_msgs::QuaternionStamped &t_in, geometry_msgs::QuaternionStamped &t_out, const geometry_msgs::TransformStamped &transform)
 Apply a geometry_msgs TransformStamped to an stamped geometry_msgs Quaternion type. This function is a specialization of the doTransform template defined in tf2/convert.h. More...
 
template<>
void tf2::doTransform (const geometry_msgs::Pose &t_in, geometry_msgs::Pose &t_out, const geometry_msgs::TransformStamped &transform)
 Apply a geometry_msgs TransformStamped to an geometry_msgs Pose type. This function is a specialization of the doTransform template defined in tf2/convert.h. More...
 
template<>
void tf2::doTransform (const geometry_msgs::PoseStamped &t_in, geometry_msgs::PoseStamped &t_out, const geometry_msgs::TransformStamped &transform)
 Apply a geometry_msgs TransformStamped to an stamped geometry_msgs Pose type. This function is a specialization of the doTransform template defined in tf2/convert.h. More...
 
template<>
void tf2::doTransform (const geometry_msgs::PoseWithCovarianceStamped &t_in, geometry_msgs::PoseWithCovarianceStamped &t_out, const geometry_msgs::TransformStamped &transform)
 Apply a geometry_msgs TransformStamped to an geometry_msgs PoseWithCovarianceStamped type. This function is a specialization of the doTransform template defined in tf2/convert.h. More...
 
template<>
void tf2::doTransform (const geometry_msgs::TransformStamped &t_in, geometry_msgs::TransformStamped &t_out, const geometry_msgs::TransformStamped &transform)
 Apply a geometry_msgs TransformStamped to an geometry_msgs Transform type. This function is a specialization of the doTransform template defined in tf2/convert.h. More...
 
template<>
void tf2::doTransform (const geometry_msgs::Vector3 &t_in, geometry_msgs::Vector3 &t_out, const geometry_msgs::TransformStamped &transform)
 Apply a geometry_msgs TransformStamped to an geometry_msgs Vector type. This function is a specialization of the doTransform template defined in tf2/convert.h. More...
 
template<>
void tf2::doTransform (const geometry_msgs::Vector3Stamped &t_in, geometry_msgs::Vector3Stamped &t_out, const geometry_msgs::TransformStamped &transform)
 Apply a geometry_msgs TransformStamped to an stamped geometry_msgs Vector type. This function is a specialization of the doTransform template defined in tf2/convert.h. More...
 
template<>
void tf2::doTransform (const geometry_msgs::Wrench &t_in, geometry_msgs::Wrench &t_out, const geometry_msgs::TransformStamped &transform)
 
template<>
void tf2::doTransform (const geometry_msgs::WrenchStamped &t_in, geometry_msgs::WrenchStamped &t_out, const geometry_msgs::TransformStamped &transform)
 
void tf2::fromMsg (const geometry_msgs::Vector3 &in, tf2::Vector3 &out)
 Convert a Vector3 message to its equivalent tf2 representation. This function is a specialization of the fromMsg template defined in tf2/convert.h. More...
 
void tf2::fromMsg (const geometry_msgs::Vector3Stamped &msg, geometry_msgs::Vector3Stamped &out)
 Trivial "conversion" function for Vector3 message type. This function is a specialization of the fromMsg template defined in tf2/convert.h. More...
 
void tf2::fromMsg (const geometry_msgs::Vector3Stamped &msg, tf2::Stamped< tf2::Vector3 > &out)
 Convert a Vector3Stamped message to its equivalent tf2 representation. This function is a specialization of the fromMsg template defined in tf2/convert.h. More...
 
void tf2::fromMsg (const geometry_msgs::Point &in, tf2::Vector3 &out)
 Convert a Vector3 message to its equivalent tf2 representation. This function is a specialization of the fromMsg template defined in tf2/convert.h. More...
 
void tf2::fromMsg (const geometry_msgs::PointStamped &msg, geometry_msgs::PointStamped &out)
 Trivial "conversion" function for Point message type. This function is a specialization of the fromMsg template defined in tf2/convert.h. More...
 
void tf2::fromMsg (const geometry_msgs::PointStamped &msg, tf2::Stamped< tf2::Vector3 > &out)
 Convert a PointStamped message to its equivalent tf2 representation. This function is a specialization of the fromMsg template defined in tf2/convert.h. More...
 
void tf2::fromMsg (const geometry_msgs::Quaternion &in, tf2::Quaternion &out)
 Convert a Quaternion message to its equivalent tf2 representation. This function is a specialization of the fromMsg template defined in tf2/convert.h. More...
 
void tf2::fromMsg (const geometry_msgs::QuaternionStamped &msg, geometry_msgs::QuaternionStamped &out)
 Trivial "conversion" function for Quaternion message type. This function is a specialization of the fromMsg template defined in tf2/convert.h. More...
 
void tf2::fromMsg (const geometry_msgs::QuaternionStamped &in, tf2::Stamped< tf2::Quaternion > &out)
 Convert a QuaternionStamped message to its equivalent tf2 representation. This function is a specialization of the fromMsg template defined in tf2/convert.h. More...
 
void tf2::fromMsg (const geometry_msgs::Pose &in, tf2::Transform &out)
 Convert a geometry_msgs Pose message to an equivalent tf2 Transform type. More...
 
void tf2::fromMsg (const geometry_msgs::PoseStamped &msg, geometry_msgs::PoseStamped &out)
 Trivial "conversion" function for Pose message type. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
void tf2::fromMsg (const geometry_msgs::PoseStamped &msg, tf2::Stamped< tf2::Transform > &out)
 Convert a PoseStamped message to its equivalent tf2 representation. This function is a specialization of the fromMsg template defined in tf2/convert.h. More...
 
void tf2::fromMsg (const geometry_msgs::PoseWithCovarianceStamped &msg, geometry_msgs::PoseWithCovarianceStamped &out)
 Trivial "conversion" function for PoseWithCovarianceStamped message type. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
void tf2::fromMsg (const geometry_msgs::PoseWithCovarianceStamped &msg, tf2::Stamped< tf2::Transform > &out)
 Convert a PoseWithCovarianceStamped message to its equivalent tf2 representation. This function is a specialization of the fromMsg template defined in tf2/convert.h. More...
 
void tf2::fromMsg (const geometry_msgs::Transform &in, tf2::Transform &out)
 Convert a Transform message to its equivalent tf2 representation. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
void tf2::fromMsg (const geometry_msgs::TransformStamped &msg, geometry_msgs::TransformStamped &out)
 Convert a TransformStamped message to its equivalent tf2 representation. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
void tf2::fromMsg (const geometry_msgs::TransformStamped &msg, tf2::Stamped< tf2::Transform > &out)
 Convert a TransformStamped message to its equivalent tf2 representation. This function is a specialization of the fromMsg template defined in tf2/convert.h. More...
 
void tf2::fromMsg (const geometry_msgs::WrenchStamped &msg, geometry_msgs::WrenchStamped &out)
 
void tf2::fromMsg (const geometry_msgs::WrenchStamped &msg, tf2::Stamped< boost::array< tf2::Vector3, 2 > > &out)
 
template<>
const std::string & tf2::getFrameId (const geometry_msgs::Vector3Stamped &t)
 Extract a frame ID from the header of a Vector message. This function is a specialization of the getFrameId template defined in tf2/convert.h. More...
 
template<>
const std::string & tf2::getFrameId (const geometry_msgs::PointStamped &t)
 Extract a frame ID from the header of a Point message. This function is a specialization of the getFrameId template defined in tf2/convert.h. More...
 
template<>
const std::string & tf2::getFrameId (const geometry_msgs::QuaternionStamped &t)
 Extract a frame ID from the header of a Quaternion message. This function is a specialization of the getFrameId template defined in tf2/convert.h. More...
 
template<>
const std::string & tf2::getFrameId (const geometry_msgs::PoseStamped &t)
 Extract a frame ID from the header of a Pose message. This function is a specialization of the getFrameId template defined in tf2/convert.h. More...
 
template<>
const std::string & tf2::getFrameId (const geometry_msgs::PoseWithCovarianceStamped &t)
 Extract a frame ID from the header of a PoseWithCovarianceStamped message. This function is a specialization of the getFrameId template defined in tf2/convert.h. More...
 
template<>
const std::string & tf2::getFrameId (const geometry_msgs::TransformStamped &t)
 Extract a frame ID from the header of a Transform message. This function is a specialization of the getFrameId template defined in tf2/convert.h. More...
 
template<>
const std::string & tf2::getFrameId (const geometry_msgs::WrenchStamped &t)
 
template<>
const ros::Timetf2::getTimestamp (const geometry_msgs::Vector3Stamped &t)
 Extract a timestamp from the header of a Vector message. This function is a specialization of the getTimestamp template defined in tf2/convert.h. More...
 
template<>
const ros::Timetf2::getTimestamp (const geometry_msgs::PointStamped &t)
 Extract a timestamp from the header of a Point message. This function is a specialization of the getTimestamp template defined in tf2/convert.h. More...
 
template<>
const ros::Timetf2::getTimestamp (const geometry_msgs::QuaternionStamped &t)
 Extract a timestamp from the header of a Quaternion message. This function is a specialization of the getTimestamp template defined in tf2/convert.h. More...
 
template<>
const ros::Timetf2::getTimestamp (const geometry_msgs::PoseStamped &t)
 Extract a timestamp from the header of a Pose message. This function is a specialization of the getTimestamp template defined in tf2/convert.h. More...
 
template<>
const ros::Timetf2::getTimestamp (const geometry_msgs::PoseWithCovarianceStamped &t)
 Extract a timestamp from the header of a PoseWithCovarianceStamped message. This function is a specialization of the getTimestamp template defined in tf2/convert.h. More...
 
template<>
const ros::Timetf2::getTimestamp (const geometry_msgs::TransformStamped &t)
 Extract a timestamp from the header of a Transform message. This function is a specialization of the getTimestamp template defined in tf2/convert.h. More...
 
template<>
const ros::Timetf2::getTimestamp (const geometry_msgs::WrenchStamped &t)
 
KDL::Frame tf2::gmTransformToKDL (const geometry_msgs::TransformStamped &t) __attribute__((deprecated))
 Convert a TransformStamped message to a KDL frame. More...
 
geometry_msgs::Vector3 tf2::toMsg (const tf2::Vector3 &in)
 Convert a tf2 Vector3 type to its equivalent geometry_msgs representation. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
geometry_msgs::Vector3Stamped tf2::toMsg (const geometry_msgs::Vector3Stamped &in)
 Trivial "conversion" function for Vector3 message type. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
geometry_msgs::Vector3Stamped tf2::toMsg (const tf2::Stamped< tf2::Vector3 > &in)
 Convert as stamped tf2 Vector3 type to its equivalent geometry_msgs representation. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
geometry_msgs::Point & tf2::toMsg (const tf2::Vector3 &in, geometry_msgs::Point &out)
 Convert a tf2 Vector3 type to its equivalent geometry_msgs representation. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
geometry_msgs::PointStamped tf2::toMsg (const geometry_msgs::PointStamped &in)
 Trivial "conversion" function for Point message type. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
geometry_msgs::PointStamped tf2::toMsg (const tf2::Stamped< tf2::Vector3 > &in, geometry_msgs::PointStamped &out)
 Convert as stamped tf2 Vector3 type to its equivalent geometry_msgs representation. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
geometry_msgs::Quaternion tf2::toMsg (const tf2::Quaternion &in)
 Convert a tf2 Quaternion type to its equivalent geometry_msgs representation. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
geometry_msgs::QuaternionStamped tf2::toMsg (const geometry_msgs::QuaternionStamped &in)
 Trivial "conversion" function for Quaternion message type. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
geometry_msgs::QuaternionStamped tf2::toMsg (const tf2::Stamped< tf2::Quaternion > &in)
 Convert as stamped tf2 Quaternion type to its equivalent geometry_msgs representation. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
geometry_msgs::Pose & tf2::toMsg (const tf2::Transform &in, geometry_msgs::Pose &out)
 Convert a tf2 Transform type to an equivalent geometry_msgs Pose message. More...
 
geometry_msgs::PoseStamped tf2::toMsg (const geometry_msgs::PoseStamped &in)
 Trivial "conversion" function for Pose message type. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
geometry_msgs::PoseStamped tf2::toMsg (const tf2::Stamped< tf2::Transform > &in, geometry_msgs::PoseStamped &out)
 Convert as stamped tf2 Pose type to its equivalent geometry_msgs representation. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
geometry_msgs::PoseWithCovarianceStamped tf2::toMsg (const geometry_msgs::PoseWithCovarianceStamped &in)
 Trivial "conversion" function for PoseWithCovarianceStamped message type. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
geometry_msgs::PoseWithCovarianceStamped tf2::toMsg (const tf2::Stamped< tf2::Transform > &in, geometry_msgs::PoseWithCovarianceStamped &out)
 Convert as stamped tf2 PoseWithCovarianceStamped type to its equivalent geometry_msgs representation. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
geometry_msgs::Transform tf2::toMsg (const tf2::Transform &in)
 Convert a tf2 Transform type to its equivalent geometry_msgs representation. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
geometry_msgs::TransformStamped tf2::toMsg (const geometry_msgs::TransformStamped &in)
 Trivial "conversion" function for Transform message type. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
geometry_msgs::TransformStamped tf2::toMsg (const tf2::Stamped< tf2::Transform > &in)
 Convert as stamped tf2 Transform type to its equivalent geometry_msgs representation. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
 
geometry_msgs::WrenchStamped tf2::toMsg (const geometry_msgs::WrenchStamped &in)
 
geometry_msgs::WrenchStamped tf2::toMsg (const tf2::Stamped< boost::array< tf2::Vector3, 2 > > &in, geometry_msgs::WrenchStamped &out)
 
geometry_msgs::PoseWithCovariance::_covariance_type tf2::transformCovariance (const geometry_msgs::PoseWithCovariance::_covariance_type &cov_in, const tf2::Transform &transform)
 Transform the covariance matrix of a PoseWithCovarianceStamped message to a new frame. More...
 


tf2_geometry_msgs
Author(s): Wim Meeussen
autogenerated on Fri Oct 16 2020 19:08:59