$search
#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 "LinearMath/btTransform.h"#include "ros/time.h"#include "ros/console.h"

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 | |
| namespace | tf |
Typedefs | |
| typedef btVector3 | tf::Point |
| The transform library representation of a point(Position). | |
| typedef btTransform | tf::Pose |
| A representation of pose (A position and orientation). | |
| typedef btQuaternion | tf::Quaternion |
| A representaton of orientation or rotation depending on context. | |
| typedef btTransform | tf::Transform |
| A representation of a translation and rotation. | |
| typedef btVector3 | tf::Vector3 |
| A representation of a translation. | |
Functions | |
| static tf::Quaternion | tf::createIdentityQuaternion () |
| construct an Identity Quaternion | |
| static tf::Quaternion | tf::createQuaternionFromRPY (double roll, double pitch, double yaw) |
| construct a Quaternion from Fixed angles | |
| static Quaternion | tf::createQuaternionFromYaw (double yaw) |
| construct a Quaternion from yaw only | |
| static geometry_msgs::Quaternion | tf::createQuaternionMsgFromRollPitchYaw (double roll, double pitch, double yaw) |
| construct a Quaternion Message from Fixed angles | |
| static geometry_msgs::Quaternion | tf::createQuaternionMsgFromYaw (double yaw) |
| construct a Quaternion Message from yaw only | |
| static double | tf::getYaw (const Quaternion &bt_q) |
| Helper function for getting yaw from a Quaternion. | |
| static bool | tf::operator== (const StampedTransform &a, const StampedTransform &b) |
| Comparison operator for StampedTransform. | |
| template<typename T > | |
| bool | tf::operator== (const Stamped< T > &a, const Stamped< T > &b) |
| Comparison Operator for Stamped datatypes. | |
| static void | tf::pointMsgToTF (const geometry_msgs::Point &msg_v, Point &bt_v) |
| convert Point msg to Point | |
| static void | tf::pointStampedMsgToTF (const geometry_msgs::PointStamped &msg, Stamped< Point > &bt) |
| convert PointStamped msg to Stamped<Point> | |
| static void | tf::pointStampedTFToMsg (const Stamped< Point > &bt, geometry_msgs::PointStamped &msg) |
| convert Stamped<Point> to PointStamped msg | |
| static void | tf::pointTFToMsg (const Point &bt_v, geometry_msgs::Point &msg_v) |
| convert Point to Point msg | |
| static void | tf::poseMsgToTF (const geometry_msgs::Pose &msg, Pose &bt) |
| convert Pose msg to Pose | |
| static void | tf::poseStampedMsgToTF (const geometry_msgs::PoseStamped &msg, Stamped< Pose > &bt) |
| convert PoseStamped msg to Stamped<Pose> | |
| static void | tf::poseStampedTFToMsg (const Stamped< Pose > &bt, geometry_msgs::PoseStamped &msg) |
| convert Stamped<Pose> to PoseStamped msg | |
| static void | tf::poseTFToMsg (const Pose &bt, geometry_msgs::Pose &msg) |
| convert Pose to Pose msg | |
| static void | tf::quaternionMsgToTF (const geometry_msgs::Quaternion &msg, Quaternion &bt) |
| convert Quaternion msg to Quaternion | |
| static void | tf::quaternionStampedMsgToTF (const geometry_msgs::QuaternionStamped &msg, Stamped< Quaternion > &bt) |
| convert QuaternionStamped msg to Stamped<Quaternion> | |
| static void | tf::quaternionStampedTFToMsg (const Stamped< Quaternion > &bt, geometry_msgs::QuaternionStamped &msg) |
| convert Stamped<Quaternion> to QuaternionStamped msg | |
| static void | tf::quaternionTFToMsg (const Quaternion &bt, geometry_msgs::Quaternion &msg) |
| convert Quaternion to Quaternion msg | |
| static void | tf::transformMsgToTF (const geometry_msgs::Transform &msg, Transform &bt) |
| convert Transform msg to Transform | |
| static void | tf::transformStampedMsgToTF (const geometry_msgs::TransformStamped &msg, StampedTransform &bt) |
| convert TransformStamped msg to tf::StampedTransform | |
| static void | tf::transformStampedTFToMsg (const StampedTransform &bt, geometry_msgs::TransformStamped &msg) |
| convert tf::StampedTransform to TransformStamped msg | |
| static void | tf::transformTFToMsg (const Transform &bt, geometry_msgs::Transform &msg) |
| convert Transform to Transform msg | |
| static void | tf::vector3MsgToTF (const geometry_msgs::Vector3 &msg_v, Vector3 &bt_v) |
| convert Vector3 msg to Vector3 | |
| static void | tf::vector3StampedMsgToTF (const geometry_msgs::Vector3Stamped &msg, Stamped< Vector3 > &bt) |
| convert Vector3Stamped msg to Stamped<Vector3> | |
| static void | tf::vector3StampedTFToMsg (const Stamped< Vector3 > &bt, geometry_msgs::Vector3Stamped &msg) |
| convert Stamped<Vector3> to Vector3Stamped msg | |
| static void | tf::vector3TFToMsg (const Vector3 &bt_v, geometry_msgs::Vector3 &msg_v) |
| convert Vector3 to Vector3 msg | |
Variables | |
| static const double | tf::QUATERNION_TOLERANCE = 0.1f |