Classes | Namespaces | Typedefs | Functions | Variables
transform_datatypes.h File Reference
#include <string>
#include "geometry_msgs/PointStamped.h"
#include "geometry_msgs/Vector3Stamped.h"
#include "geometry_msgs/QuaternionStamped.h"
#include "geometry_msgs/TransformStamped.h"
#include "geometry_msgs/PoseStamped.h"
#include "tf/LinearMath/Transform.h"
#include "ros/time.h"
#include "ros/console.h"
Include dependency graph for transform_datatypes.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

class  tf::Stamped< T >
 The data type which will be cross compatable with geometry_msgs This is the tf datatype equivilant of a MessageStamped. More...
 
class  tf::StampedTransform
 The Stamped Transform datatype used by tf. More...
 

Namespaces

 tf
 

Typedefs

typedef tf::Vector3 tf::Point
 
typedef tf::Transform tf::Pose
 

Functions

static tf::Quaternion tf::createIdentityQuaternion ()
 construct an Identity Quaternion More...
 
static tf::Quaternion tf::createQuaternionFromRPY (double roll, double pitch, double yaw)
 construct a Quaternion from Fixed angles More...
 
static Quaternion tf::createQuaternionFromYaw (double yaw)
 construct a Quaternion from yaw only More...
 
static geometry_msgs::Quaternion tf::createQuaternionMsgFromRollPitchYaw (double roll, double pitch, double yaw)
 construct a Quaternion Message from Fixed angles More...
 
static geometry_msgs::Quaternion tf::createQuaternionMsgFromYaw (double yaw)
 construct a Quaternion Message from yaw only More...
 
static double tf::getYaw (const Quaternion &bt_q)
 Helper function for getting yaw from a Quaternion. More...
 
static double tf::getYaw (const geometry_msgs::Quaternion &msg_q)
 Helper function for getting yaw from a Quaternion message. More...
 
template<typename T >
bool tf::operator== (const Stamped< T > &a, const Stamped< T > &b)
 Comparison Operator for Stamped datatypes. More...
 
static bool tf::operator== (const StampedTransform &a, const StampedTransform &b)
 Comparison operator for StampedTransform. More...
 
static void tf::pointMsgToTF (const geometry_msgs::Point &msg_v, Point &bt_v)
 convert Point msg to Point More...
 
static void tf::pointStampedMsgToTF (const geometry_msgs::PointStamped &msg, Stamped< Point > &bt)
 convert PointStamped msg to Stamped<Point> More...
 
static void tf::pointStampedTFToMsg (const Stamped< Point > &bt, geometry_msgs::PointStamped &msg)
 convert Stamped<Point> to PointStamped msg More...
 
static void tf::pointTFToMsg (const Point &bt_v, geometry_msgs::Point &msg_v)
 convert Point to Point msg More...
 
static void tf::poseMsgToTF (const geometry_msgs::Pose &msg, Pose &bt)
 convert Pose msg to Pose More...
 
static void tf::poseStampedMsgToTF (const geometry_msgs::PoseStamped &msg, Stamped< Pose > &bt)
 convert PoseStamped msg to Stamped<Pose> More...
 
static void tf::poseStampedTFToMsg (const Stamped< Pose > &bt, geometry_msgs::PoseStamped &msg)
 convert Stamped<Pose> to PoseStamped msg More...
 
static void tf::poseTFToMsg (const Pose &bt, geometry_msgs::Pose &msg)
 convert Pose to Pose msg More...
 
static void tf::quaternionMsgToTF (const geometry_msgs::Quaternion &msg, Quaternion &bt)
 convert Quaternion msg to Quaternion More...
 
static void tf::quaternionStampedMsgToTF (const geometry_msgs::QuaternionStamped &msg, Stamped< Quaternion > &bt)
 convert QuaternionStamped msg to Stamped<Quaternion> More...
 
static void tf::quaternionStampedTFToMsg (const Stamped< Quaternion > &bt, geometry_msgs::QuaternionStamped &msg)
 convert Stamped<Quaternion> to QuaternionStamped msg More...
 
static void tf::quaternionTFToMsg (const Quaternion &bt, geometry_msgs::Quaternion &msg)
 convert Quaternion to Quaternion msg More...
 
static void tf::transformMsgToTF (const geometry_msgs::Transform &msg, Transform &bt)
 convert Transform msg to Transform More...
 
static void tf::transformStampedMsgToTF (const geometry_msgs::TransformStamped &msg, StampedTransform &bt)
 convert TransformStamped msg to tf::StampedTransform More...
 
static void tf::transformStampedTFToMsg (const StampedTransform &bt, geometry_msgs::TransformStamped &msg)
 convert tf::StampedTransform to TransformStamped msg More...
 
static void tf::transformTFToMsg (const Transform &bt, geometry_msgs::Transform &msg)
 convert Transform to Transform msg More...
 
static void tf::vector3MsgToTF (const geometry_msgs::Vector3 &msg_v, Vector3 &bt_v)
 convert Vector3 msg to Vector3 More...
 
static void tf::vector3StampedMsgToTF (const geometry_msgs::Vector3Stamped &msg, Stamped< Vector3 > &bt)
 convert Vector3Stamped msg to Stamped<Vector3> More...
 
static void tf::vector3StampedTFToMsg (const Stamped< Vector3 > &bt, geometry_msgs::Vector3Stamped &msg)
 convert Stamped<Vector3> to Vector3Stamped msg More...
 
static void tf::vector3TFToMsg (const Vector3 &bt_v, geometry_msgs::Vector3 &msg_v)
 convert Vector3 to Vector3 msg More...
 

Variables

static const double tf::QUATERNION_TOLERANCE = 0.1f
 


tf
Author(s): Tully Foote, Eitan Marder-Eppstein, Wim Meeussen
autogenerated on Mon Jun 10 2019 12:25:26