|  | 
| TF2SIMD_FORCE_INLINE tf2Scalar | angle (const Quaternion &q1, const Quaternion &q2) | 
|  | 
| TF2SIMD_FORCE_INLINE tf2Scalar | angleShortestPath (const Quaternion &q1, const Quaternion &q2) | 
|  | 
|  | ATTRIBUTE_ALIGNED16 (class) QuadWord | 
|  | 
| void | convert (const A &a, B &b) | 
|  | 
| void | convert (const A &a1, A &a2) | 
|  | 
| TF2SIMD_FORCE_INLINE tf2Scalar | dot (const Quaternion &q1, const Quaternion &q2) | 
|  | 
| template<> | 
| void | doTransform (const Eigen::Affine3d &t_in, Eigen::Affine3d &t_out, const geometry_msgs::TransformStamped &transform) | 
|  | Apply a geometry_msgs Transform to an Eigen Affine3d transform. This function is a specialization of the doTransform template defined in tf2/convert.h, although it can not be used in tf2_ros::BufferInterface::transform because this function relies on the existence of a time stamp and a frame id in the type which should get transformed.  More... 
 | 
|  | 
| template<> | 
| void | doTransform (const Eigen::Isometry3d &t_in, Eigen::Isometry3d &t_out, const geometry_msgs::TransformStamped &transform) | 
|  | 
| template<> | 
| void | doTransform (const Eigen::Quaterniond &t_in, Eigen::Quaterniond &t_out, const geometry_msgs::TransformStamped &transform) | 
|  | Apply a geometry_msgs TransformStamped to an Eigen-specific Quaterniond type. This function is a specialization of the doTransform template defined in tf2/convert.h, although it can not be used in tf2_ros::BufferInterface::transform because this functions rely on the existence of a time stamp and a frame id in the type which should get transformed.  More... 
 | 
|  | 
| template<> | 
| void | doTransform (const Eigen::Vector3d &t_in, Eigen::Vector3d &t_out, const geometry_msgs::TransformStamped &transform) | 
|  | Apply a geometry_msgs TransformStamped to an Eigen-specific Vector3d type. This function is a specialization of the doTransform template defined in tf2/convert.h, although it can not be used in tf2_ros::BufferInterface::transform because this functions rely on the existence of a time stamp and a frame id in the type which should get transformed.  More... 
 | 
|  | 
| void | doTransform (const T &data_in, T &data_out, const geometry_msgs::TransformStamped &transform) | 
|  | 
| template<> | 
| void | doTransform (const tf2::Stamped< Eigen::Affine3d > &t_in, tf2::Stamped< Eigen::Affine3d > &t_out, const geometry_msgs::TransformStamped &transform) | 
|  | Apply a geometry_msgs TransformStamped to an Eigen Affine3d transform. This function is a specialization of the doTransform template defined in tf2/convert.h, although it can not be used in tf2_ros::BufferInterface::transform because this function relies on the existence of a time stamp and a frame id in the type which should get transformed.  More... 
 | 
|  | 
| template<> | 
| void | doTransform (const tf2::Stamped< Eigen::Isometry3d > &t_in, tf2::Stamped< Eigen::Isometry3d > &t_out, const geometry_msgs::TransformStamped &transform) | 
|  | Apply a geometry_msgs TransformStamped to an Eigen Isometry transform. This function is a specialization of the doTransform template defined in tf2/convert.h, although it can not be used in tf2_ros::BufferInterface::transform because this function relies on the existence of a time stamp and a frame id in the type which should get transformed.  More... 
 | 
|  | 
| template<> | 
| void | doTransform (const tf2::Stamped< Eigen::Quaterniond > &t_in, tf2::Stamped< Eigen::Quaterniond > &t_out, const geometry_msgs::TransformStamped &transform) | 
|  | Apply a geometry_msgs TransformStamped to an Eigen-specific Quaterniond type. This function is a specialization of the doTransform template defined in tf2/convert.h.  More... 
 | 
|  | 
| template<> | 
| void | doTransform (const tf2::Stamped< Eigen::Vector3d > &t_in, tf2::Stamped< Eigen::Vector3d > &t_out, const geometry_msgs::TransformStamped &transform) | 
|  | Apply a geometry_msgs TransformStamped to an Eigen-specific Vector3d type. This function is a specialization of the doTransform template defined in tf2/convert.h.  More... 
 | 
|  | 
| geometry_msgs::TransformStamped | eigenToTransform (const Eigen::Affine3d &T) | 
|  | Convert an Eigen Affine3d transform to the equivalent geometry_msgs message type.  More... 
 | 
|  | 
| geometry_msgs::TransformStamped | eigenToTransform (const Eigen::Isometry3d &T) | 
|  | Convert an Eigen Isometry3d transform to the equivalent geometry_msgs message type.  More... 
 | 
|  | 
| void | fromMsg (const A &, B &b) | 
|  | 
| void | fromMsg (const geometry_msgs::Point &msg, Eigen::Vector3d &out) | 
|  | Convert a Point message type to a Eigen-specific Vector3d type. This function is a specialization of the fromMsg template defined in tf2/convert.h.  More... 
 | 
|  | 
| void | fromMsg (const geometry_msgs::PointStamped &msg, tf2::Stamped< Eigen::Vector3d > &out) | 
|  | Convert a PointStamped message type to a stamped Eigen-specific Vector3d type. This function is a specialization of the fromMsg template defined in tf2/convert.h.  More... 
 | 
|  | 
| void | fromMsg (const geometry_msgs::Pose &msg, Eigen::Affine3d &out) | 
|  | Convert a Pose message transform type to a Eigen Affine3d. This function is a specialization of the toMsg template defined in tf2/convert.h.  More... 
 | 
|  | 
| void | fromMsg (const geometry_msgs::Pose &msg, Eigen::Isometry3d &out) | 
|  | Convert a Pose message transform type to a Eigen Isometry3d. This function is a specialization of the toMsg template defined in tf2/convert.h.  More... 
 | 
|  | 
| void | fromMsg (const geometry_msgs::PoseStamped &msg, tf2::Stamped< Eigen::Affine3d > &out) | 
|  | Convert a Pose message transform type to a stamped Eigen Affine3d. This function is a specialization of the toMsg template defined in tf2/convert.h.  More... 
 | 
|  | 
| void | fromMsg (const geometry_msgs::PoseStamped &msg, tf2::Stamped< Eigen::Isometry3d > &out) | 
|  | 
| void | fromMsg (const geometry_msgs::Quaternion &msg, Eigen::Quaterniond &out) | 
|  | Convert a Quaternion message type to a Eigen-specific Quaterniond type. This function is a specialization of the fromMsg template defined in tf2/convert.h.  More... 
 | 
|  | 
| void | fromMsg (const geometry_msgs::QuaternionStamped &msg, Stamped< Eigen::Quaterniond > &out) | 
|  | Convert a QuaternionStamped message type to a stamped Eigen-specific Quaterniond type. This function is a specialization of the fromMsg template defined in tf2/convert.h.  More... 
 | 
|  | 
| void | fromMsg (const geometry_msgs::Twist &msg, Eigen::Matrix< double, 6, 1 > &out) | 
|  | Convert a Twist message transform type to a Eigen 6x1 Matrix. This function is a specialization of the toMsg template defined in tf2/convert.h.  More... 
 | 
|  | 
| void | fromMsg (const geometry_msgs::Vector3 &msg, Eigen::Vector3d &out) | 
|  | Convert a Vector3 message type to a Eigen-specific Vector3d type. This function is a specialization of the fromMsg template defined in tf2/convert.h.  More... 
 | 
|  | 
| void | getEulerYPR (const A &a, double &yaw, double &pitch, double &roll) | 
|  | 
| const std::string & | getFrameId (const T &t) | 
|  | 
| const std::string & | getFrameId (const tf2::Stamped< P > &t) | 
|  | 
| const ros::Time & | getTimestamp (const T &t) | 
|  | 
| const ros::Time & | getTimestamp (const tf2::Stamped< P > &t) | 
|  | 
| A | getTransformIdentity () | 
|  | 
| double | getYaw (const A &a) | 
|  | 
| TF2SIMD_FORCE_INLINE Quaternion | inverse (const Quaternion &q) | 
|  | 
| TF2SIMD_FORCE_INLINE tf2Scalar | length (const Quaternion &q) | 
|  | 
| TF2SIMD_FORCE_INLINE Vector3 | lerp (const Vector3 &v1, const Vector3 &v2, const tf2Scalar &t) | 
|  | 
| TF2SIMD_FORCE_INLINE Vector3 | operator* (const Matrix3x3 &m, const Vector3 &v) | 
|  | 
| TF2SIMD_FORCE_INLINE Matrix3x3 | operator* (const Matrix3x3 &m1, const Matrix3x3 &m2) | 
|  | 
| TF2SIMD_FORCE_INLINE Quaternion | operator* (const Quaternion &q, const Vector3 &w) | 
|  | 
| TF2SIMD_FORCE_INLINE Quaternion | operator* (const Quaternion &q1, const Quaternion &q2) | 
|  | 
| TF2SIMD_FORCE_INLINE Vector3 | operator* (const tf2Scalar &s, const Vector3 &v) | 
|  | 
| TF2SIMD_FORCE_INLINE Vector3 | operator* (const Vector3 &v, const Matrix3x3 &m) | 
|  | 
| TF2SIMD_FORCE_INLINE Vector3 | operator* (const Vector3 &v, const tf2Scalar &s) | 
|  | 
| TF2SIMD_FORCE_INLINE Vector3 | operator* (const Vector3 &v1, const Vector3 &v2) | 
|  | 
| TF2SIMD_FORCE_INLINE Quaternion | operator* (const Vector3 &w, const Quaternion &q) | 
|  | 
| TF2SIMD_FORCE_INLINE Vector3 | operator+ (const Vector3 &v1, const Vector3 &v2) | 
|  | 
| TF2SIMD_FORCE_INLINE Quaternion | operator- (const Quaternion &q) | 
|  | 
| TF2SIMD_FORCE_INLINE Vector3 | operator- (const Vector3 &v) | 
|  | 
| TF2SIMD_FORCE_INLINE Vector3 | operator- (const Vector3 &v1, const Vector3 &v2) | 
|  | 
| TF2SIMD_FORCE_INLINE Vector3 | operator/ (const Vector3 &v, const tf2Scalar &s) | 
|  | 
| TF2SIMD_FORCE_INLINE Vector3 | operator/ (const Vector3 &v1, const Vector3 &v2) | 
|  | 
| TF2SIMD_FORCE_INLINE bool | operator== (const Matrix3x3 &m1, const Matrix3x3 &m2) | 
|  | 
| bool | operator== (const Stamped< T > &a, const Stamped< T > &b) | 
|  | 
| TF2SIMD_FORCE_INLINE bool | operator== (const Transform &t1, const Transform &t2) | 
|  | 
| bool | operator> (const TransformStorage &lhs, const TransformStorage &rhs) | 
|  | 
| TF2SIMD_FORCE_INLINE Vector3 | quatRotate (const Quaternion &rotation, const Vector3 &v) | 
|  | 
| void | setIdentity (geometry_msgs::Transform &tx) | 
|  | 
| TF2SIMD_FORCE_INLINE Quaternion | shortestArcQuat (const Vector3 &v0, const Vector3 &v1) | 
|  | 
| TF2SIMD_FORCE_INLINE Quaternion | shortestArcQuatNormalize2 (Vector3 &v0, Vector3 &v1) | 
|  | 
| TF2SIMD_FORCE_INLINE Quaternion | slerp (const Quaternion &q1, const Quaternion &q2, const tf2Scalar &t) | 
|  | 
| bool | startsWithSlash (const std::string &frame_id) | 
|  | 
| std::string | stripSlash (const std::string &in) | 
|  | 
| TF2SIMD_FORCE_INLINE tf2Scalar | tf2Angle (const Vector3 &v1, const Vector3 &v2) | 
|  | 
| TF2SIMD_FORCE_INLINE Vector3 | tf2Cross (const Vector3 &v1, const Vector3 &v2) | 
|  | 
| TF2SIMD_FORCE_INLINE tf2Scalar | tf2Distance (const Vector3 &v1, const Vector3 &v2) | 
|  | 
| TF2SIMD_FORCE_INLINE tf2Scalar | tf2Distance2 (const Vector3 &v1, const Vector3 &v2) | 
|  | 
| TF2SIMD_FORCE_INLINE tf2Scalar | tf2Dot (const Vector3 &v1, const Vector3 &v2) | 
|  | 
| TF2SIMD_FORCE_INLINE void | tf2PlaneSpace1 (const Vector3 &n, Vector3 &p, Vector3 &q) | 
|  | 
| TF2SIMD_FORCE_INLINE void | tf2SwapScalarEndian (const tf2Scalar &sourceVal, tf2Scalar &destVal) | 
|  | 
| TF2SIMD_FORCE_INLINE void | tf2SwapVector3Endian (const Vector3 &sourceVec, Vector3 &destVec) | 
|  | 
| TF2SIMD_FORCE_INLINE tf2Scalar | tf2Triple (const Vector3 &v1, const Vector3 &v2, const Vector3 &v3) | 
|  | 
| TF2SIMD_FORCE_INLINE void | tf2UnSwapVector3Endian (Vector3 &vector) | 
|  | 
| B | toMsg (const A &a) | 
|  | 
| geometry_msgs::Pose | toMsg (const Eigen::Affine3d &in) | 
|  | Convert a Eigen Affine3d transform type to a Pose message. This function is a specialization of the toMsg template defined in tf2/convert.h.  More... 
 | 
|  | 
| geometry_msgs::Pose | toMsg (const Eigen::Isometry3d &in) | 
|  | Convert a Eigen Isometry3d transform type to a Pose message. This function is a specialization of the toMsg template defined in tf2/convert.h.  More... 
 | 
|  | 
| geometry_msgs::Twist | toMsg (const Eigen::Matrix< double, 6, 1 > &in) | 
|  | Convert a Eigen 6x1 Matrix type to a Twist message. This function is a specialization of the toMsg template defined in tf2/convert.h.  More... 
 | 
|  | 
| geometry_msgs::Quaternion | toMsg (const Eigen::Quaterniond &in) | 
|  | Convert a Eigen Quaterniond type to a Quaternion message. This function is a specialization of the toMsg template defined in tf2/convert.h.  More... 
 | 
|  | 
| geometry_msgs::Point | toMsg (const Eigen::Vector3d &in) | 
|  | Convert a Eigen Vector3d type to a Point message. This function is a specialization of the toMsg template defined in tf2/convert.h.  More... 
 | 
|  | 
| geometry_msgs::Vector3 & | toMsg (const Eigen::Vector3d &in, geometry_msgs::Vector3 &out) | 
|  | Convert an Eigen Vector3d type to a Vector3 message. This function is a specialization of the toMsg template defined in tf2/convert.h.  More... 
 | 
|  | 
| geometry_msgs::QuaternionStamped | toMsg (const Stamped< Eigen::Quaterniond > &in) | 
|  | Convert a stamped Eigen Quaterniond type to a QuaternionStamped message. This function is a specialization of the toMsg template defined in tf2/convert.h.  More... 
 | 
|  | 
| geometry_msgs::PoseStamped | toMsg (const tf2::Stamped< Eigen::Affine3d > &in) | 
|  | Convert a stamped Eigen Affine3d transform type to a Pose message. This function is a specialization of the toMsg template defined in tf2/convert.h.  More... 
 | 
|  | 
| geometry_msgs::PoseStamped | toMsg (const tf2::Stamped< Eigen::Isometry3d > &in) | 
|  | 
| geometry_msgs::PointStamped | toMsg (const tf2::Stamped< Eigen::Vector3d > &in) | 
|  | Convert a stamped Eigen Vector3d type to a PointStamped message. This function is a specialization of the toMsg template defined in tf2/convert.h.  More... 
 | 
|  | 
| void | transformMsgToTF2 (const geometry_msgs::Transform &msg, tf2::Transform &tf2) | 
|  | 
| void | transformTF2ToMsg (const tf2::Quaternion &orient, const tf2::Vector3 &pos, geometry_msgs::Transform &msg) | 
|  | 
| void | transformTF2ToMsg (const tf2::Quaternion &orient, const tf2::Vector3 &pos, geometry_msgs::TransformStamped &msg, ros::Time stamp, const std::string &frame_id, const std::string &child_frame_id) | 
|  | 
| void | transformTF2ToMsg (const tf2::Transform &tf2, geometry_msgs::Transform &msg) | 
|  | 
| void | transformTF2ToMsg (const tf2::Transform &tf2, geometry_msgs::TransformStamped &msg, ros::Time stamp, const std::string &frame_id, const std::string &child_frame_id) | 
|  | 
| Eigen::Isometry3d | transformToEigen (const geometry_msgs::Transform &t) | 
|  | Convert a timestamped transform to the equivalent Eigen data type.  More... 
 | 
|  | 
| Eigen::Isometry3d | transformToEigen (const geometry_msgs::TransformStamped &t) | 
|  | Convert a timestamped transform to the equivalent Eigen data type.  More... 
 | 
|  |