| Namespaces | |
| filter_failure_reasons | |
| Classes | |
| class | Matrix3x3 | 
| struct | Matrix3x3DoubleData | 
| struct | Matrix3x3FloatData | 
| class | MessageFilter | 
| class | MessageFilterBase | 
| class | Quaternion | 
| class | Stamped | 
| class | StampedTransform | 
| class | tfVector4 | 
| class | TimeCache | 
| class | Transform | 
| class | TransformBroadcaster | 
| struct | TransformDoubleData | 
| class | Transformer | 
| struct | TransformFloatData | 
| class | TransformListener | 
| struct | TransformLists | 
| class | TransformStorage | 
| struct | Vector3DoubleData | 
| struct | Vector3FloatData | 
| Typedefs | |
| typedef uint32_t | CompactFrameID | 
| typedef tf2::ConnectivityException | ConnectivityException | 
| typedef tf2::ExtrapolationException | ExtrapolationException | 
| typedef filter_failure_reasons::FilterFailureReason | FilterFailureReason | 
| typedef tf2::InvalidArgumentException | InvalidArgument | 
| typedef tf2::LookupException | LookupException | 
| typedef std::pair< ros::Time, CompactFrameID > | P_TimeAndFrameID | 
| typedef tf::Vector3 | Point | 
| typedef tf::Transform | Pose | 
| typedef tf2::TransformException | TransformException | 
| Enumerations | |
| enum | ErrorValues | 
| enum | ExtrapolationMode | 
| Functions | |
| ROS_DEPRECATED geometry_msgs::Pose | addDelta (const geometry_msgs::Pose &pose, const geometry_msgs::Twist &twist, const double &t) | 
| Starting from a Pose from A to B, apply a Twist with reference frame A and reference point B, during a time t.  More... | |
| TFSIMD_FORCE_INLINE tfScalar | angle (const Quaternion &q1, const Quaternion &q2) | 
| TFSIMD_FORCE_INLINE tfScalar | angleShortestPath (const Quaternion &q1, const Quaternion &q2) | 
| void | assertQuaternionValid (const geometry_msgs::Quaternion &q) | 
| void | assertQuaternionValid (const tf::Quaternion &q) | 
| ATTRIBUTE_ALIGNED16 (class) QuadWord | |
| static tf::Quaternion | createIdentityQuaternion () | 
| static tf::Quaternion | createQuaternionFromRPY (double roll, double pitch, double yaw) | 
| static Quaternion | createQuaternionFromYaw (double yaw) | 
| static geometry_msgs::Quaternion | createQuaternionMsgFromRollPitchYaw (double roll, double pitch, double yaw) | 
| static geometry_msgs::Quaternion | createQuaternionMsgFromYaw (double yaw) | 
| TFSIMD_FORCE_INLINE tfScalar | dot (const Quaternion &q1, const Quaternion &q2) | 
| std::string | getPrefixParam (ros::NodeHandle &nh) | 
| static double | getYaw (const geometry_msgs::Quaternion &msg_q) | 
| static double | getYaw (const Quaternion &bt_q) | 
| TFSIMD_FORCE_INLINE Quaternion | inverse (const Quaternion &q) | 
| TFSIMD_FORCE_INLINE tfScalar | length (const Quaternion &q) | 
| TFSIMD_FORCE_INLINE Vector3 | lerp (const Vector3 &v1, const Vector3 &v2, const tfScalar &t) | 
| void | matrixEigenToTF (const Eigen::Matrix3d &e, tf::Matrix3x3 &t) | 
| Converts an Eigen Quaternion into a tf Matrix3x3.  More... | |
| void | matrixTFToEigen (const tf::Matrix3x3 &t, Eigen::Matrix3d &e) | 
| Converts a tf Matrix3x3 into an Eigen Quaternion.  More... | |
| TFSIMD_FORCE_INLINE Vector3 | operator* (const Matrix3x3 &m, const Vector3 &v) | 
| TFSIMD_FORCE_INLINE Matrix3x3 | operator* (const Matrix3x3 &m1, const Matrix3x3 &m2) | 
| TFSIMD_FORCE_INLINE Quaternion | operator* (const Quaternion &q, const Vector3 &w) | 
| TFSIMD_FORCE_INLINE Quaternion | operator* (const Quaternion &q1, const Quaternion &q2) | 
| TFSIMD_FORCE_INLINE Vector3 | operator* (const tfScalar &s, const Vector3 &v) | 
| TFSIMD_FORCE_INLINE Vector3 | operator* (const Vector3 &v, const Matrix3x3 &m) | 
| TFSIMD_FORCE_INLINE Vector3 | operator* (const Vector3 &v, const tfScalar &s) | 
| TFSIMD_FORCE_INLINE Vector3 | operator* (const Vector3 &v1, const Vector3 &v2) | 
| TFSIMD_FORCE_INLINE Quaternion | operator* (const Vector3 &w, const Quaternion &q) | 
| TFSIMD_FORCE_INLINE Vector3 | operator+ (const Vector3 &v1, const Vector3 &v2) | 
| TFSIMD_FORCE_INLINE Quaternion | operator- (const Quaternion &q) | 
| TFSIMD_FORCE_INLINE Vector3 | operator- (const Vector3 &v) | 
| TFSIMD_FORCE_INLINE Vector3 | operator- (const Vector3 &v1, const Vector3 &v2) | 
| TFSIMD_FORCE_INLINE Vector3 | operator/ (const Vector3 &v, const tfScalar &s) | 
| TFSIMD_FORCE_INLINE Vector3 | operator/ (const Vector3 &v1, const Vector3 &v2) | 
| TFSIMD_FORCE_INLINE bool | operator== (const Matrix3x3 &m1, const Matrix3x3 &m2) | 
| bool | operator== (const Stamped< T > &a, const Stamped< T > &b) | 
| static bool | operator== (const StampedTransform &a, const StampedTransform &b) | 
| TFSIMD_FORCE_INLINE bool | operator== (const Transform &t1, const Transform &t2) | 
| void | pointKDLToMsg (const KDL::Vector &k, geometry_msgs::Point &m) | 
| void | pointMsgToKDL (const geometry_msgs::Point &m, KDL::Vector &k) | 
| static void | pointMsgToTF (const geometry_msgs::Point &msg_v, Point &bt_v) | 
| static void | pointStampedMsgToTF (const geometry_msgs::PointStamped &msg, Stamped< Point > &bt) | 
| static void | pointStampedTFToMsg (const Stamped< Point > &bt, geometry_msgs::PointStamped &msg) | 
| static void | pointTFToMsg (const Point &bt_v, geometry_msgs::Point &msg_v) | 
| void | poseEigenToTF (const Eigen::Affine3d &e, tf::Pose &t) | 
| Converts an Eigen Affine3d into a tf Transform.  More... | |
| void | poseEigenToTF (const Eigen::Isometry3d &e, tf::Pose &t) | 
| Converts an Eigen Isometry3d into a tf Transform.  More... | |
| ROS_DEPRECATED void | PoseKDLToMsg (const KDL::Frame &k, geometry_msgs::Pose &m) | 
| void | poseKDLToMsg (const KDL::Frame &k, geometry_msgs::Pose &m) | 
| void | poseKDLToTF (const KDL::Frame &k, tf::Pose &t) | 
| Converts a KDL Frame into a tf Pose.  More... | |
| ROS_DEPRECATED void | PoseKDLToTF (const KDL::Frame &k, tf::Pose &t) | 
| Converts a KDL Frame into a tf Pose.  More... | |
| void | poseMsgToKDL (const geometry_msgs::Pose &m, KDL::Frame &k) | 
| ROS_DEPRECATED void | PoseMsgToKDL (const geometry_msgs::Pose &m, KDL::Frame &k) | 
| static void | poseMsgToTF (const geometry_msgs::Pose &msg, Pose &bt) | 
| static void | poseStampedMsgToTF (const geometry_msgs::PoseStamped &msg, Stamped< Pose > &bt) | 
| static void | poseStampedTFToMsg (const Stamped< Pose > &bt, geometry_msgs::PoseStamped &msg) | 
| void | poseTFToEigen (const tf::Pose &t, Eigen::Affine3d &e) | 
| Converts a tf Pose into an Eigen Affine3d.  More... | |
| void | poseTFToEigen (const tf::Pose &t, Eigen::Isometry3d &e) | 
| Converts a tf Pose into an Eigen Isometry3d.  More... | |
| void | poseTFToKDL (const tf::Pose &t, KDL::Frame &k) | 
| Converts a tf Pose into a KDL Frame.  More... | |
| ROS_DEPRECATED void | PoseTFToKDL (const tf::Pose &t, KDL::Frame &k) | 
| Converts a tf Pose into a KDL Frame.  More... | |
| static void | poseTFToMsg (const Pose &bt, geometry_msgs::Pose &msg) | 
| void | quaternionEigenToTF (const Eigen::Quaterniond &e, tf::Quaternion &t) | 
| Converts an Eigen Quaternion into a tf Quaternion.  More... | |
| void | quaternionKDLToMsg (const KDL::Rotation &k, geometry_msgs::Quaternion &m) | 
| void | quaternionKDLToTF (const KDL::Rotation &k, tf::Quaternion &t) | 
| Converts a tf Quaternion into a KDL Rotation.  More... | |
| ROS_DEPRECATED void | QuaternionKDLToTF (const KDL::Rotation &k, tf::Quaternion &t) | 
| Converts a tf Quaternion into a KDL Rotation.  More... | |
| void | quaternionMsgToKDL (const geometry_msgs::Quaternion &m, KDL::Rotation &k) | 
| static void | quaternionMsgToTF (const geometry_msgs::Quaternion &msg, Quaternion &bt) | 
| static void | quaternionStampedMsgToTF (const geometry_msgs::QuaternionStamped &msg, Stamped< Quaternion > &bt) | 
| static void | quaternionStampedTFToMsg (const Stamped< Quaternion > &bt, geometry_msgs::QuaternionStamped &msg) | 
| void | quaternionTFToEigen (const tf::Quaternion &t, Eigen::Quaterniond &e) | 
| Converts a tf Quaternion into an Eigen Quaternion.  More... | |
| void | quaternionTFToKDL (const tf::Quaternion &t, KDL::Rotation &k) | 
| Converts a tf Quaternion into a KDL Rotation.  More... | |
| ROS_DEPRECATED void | QuaternionTFToKDL (const tf::Quaternion &t, KDL::Rotation &k) | 
| Converts a tf Quaternion into a KDL Rotation.  More... | |
| static void | quaternionTFToMsg (const Quaternion &bt, geometry_msgs::Quaternion &msg) | 
| TFSIMD_FORCE_INLINE Vector3 | quatRotate (const Quaternion &rotation, const Vector3 &v) | 
| ROS_DEPRECATED std::string | remap (const std::string &frame_id) | 
| static ROS_DEPRECATED std::string | remap (const std::string &prefix, const std::string &frame_name) | 
| std::string | resolve (const std::string &prefix, const std::string &frame_name) | 
| TFSIMD_FORCE_INLINE Quaternion | shortestArcQuat (const Vector3 &v0, const Vector3 &v1) | 
| TFSIMD_FORCE_INLINE Quaternion | shortestArcQuatNormalize2 (Vector3 &v0, Vector3 &v1) | 
| TFSIMD_FORCE_INLINE Quaternion | slerp (const Quaternion &q1, const Quaternion &q2, const tfScalar &t) | 
| std::string | strip_leading_slash (const std::string &frame_name) | 
| TFSIMD_FORCE_INLINE tfScalar | tfAngle (const Vector3 &v1, const Vector3 &v2) | 
| TFSIMD_FORCE_INLINE Vector3 | tfCross (const Vector3 &v1, const Vector3 &v2) | 
| TFSIMD_FORCE_INLINE tfScalar | tfDistance (const Vector3 &v1, const Vector3 &v2) | 
| TFSIMD_FORCE_INLINE tfScalar | tfDistance2 (const Vector3 &v1, const Vector3 &v2) | 
| TFSIMD_FORCE_INLINE tfScalar | tfDot (const Vector3 &v1, const Vector3 &v2) | 
| TFSIMD_FORCE_INLINE void | tfPlaneSpace1 (const Vector3 &n, Vector3 &p, Vector3 &q) | 
| TFSIMD_FORCE_INLINE void | tfSwapScalarEndian (const tfScalar &sourceVal, tfScalar &destVal) | 
| TFSIMD_FORCE_INLINE void | tfSwapVector3Endian (const Vector3 &sourceVec, Vector3 &destVec) | 
| TFSIMD_FORCE_INLINE tfScalar | tfTriple (const Vector3 &v1, const Vector3 &v2, const Vector3 &v3) | 
| TFSIMD_FORCE_INLINE void | tfUnSwapVector3Endian (Vector3 &vector) | 
| void | transformEigenToTF (const Eigen::Affine3d &e, tf::Transform &t) | 
| Converts an Eigen Affine3d into a tf Transform.  More... | |
| void | transformEigenToTF (const Eigen::Isometry3d &e, tf::Transform &t) | 
| Converts an Eigen Isometry3d into a tf Transform.  More... | |
| void | transformKDLToMsg (const KDL::Frame &k, geometry_msgs::Transform &m) | 
| void | transformKDLToTF (const KDL::Frame &k, tf::Transform &t) | 
| Converts a KDL Frame into a tf Transform.  More... | |
| ROS_DEPRECATED void | TransformKDLToTF (const KDL::Frame &k, tf::Transform &t) | 
| Converts a KDL Frame into a tf Transform.  More... | |
| void | transformMsgToKDL (const geometry_msgs::Transform &m, KDL::Frame &k) | 
| static void | transformMsgToTF (const geometry_msgs::Transform &msg, Transform &bt) | 
| static void | transformStampedMsgToTF (const geometry_msgs::TransformStamped &msg, StampedTransform &bt) | 
| static void | transformStampedTFToMsg (const StampedTransform &bt, geometry_msgs::TransformStamped &msg) | 
| void | transformTFToEigen (const tf::Transform &t, Eigen::Affine3d &e) | 
| Converts a tf Transform into an Eigen Affine3d.  More... | |
| void | transformTFToEigen (const tf::Transform &t, Eigen::Isometry3d &e) | 
| Converts a tf Transform into an Eigen Isometry3d.  More... | |
| void | transformTFToKDL (const tf::Transform &t, KDL::Frame &k) | 
| Converts a tf Transform into a KDL Frame.  More... | |
| ROS_DEPRECATED void | TransformTFToKDL (const tf::Transform &t, KDL::Frame &k) | 
| Converts a tf Transform into a KDL Frame.  More... | |
| static void | transformTFToMsg (const Transform &bt, geometry_msgs::Transform &msg) | 
| void | twistKDLToMsg (const KDL::Twist &k, geometry_msgs::Twist &m) | 
| ROS_DEPRECATED void | TwistKDLToMsg (const KDL::Twist &k, geometry_msgs::Twist &m) | 
| void | twistMsgToKDL (const geometry_msgs::Twist &m, KDL::Twist &k) | 
| ROS_DEPRECATED void | TwistMsgToKDL (const geometry_msgs::Twist &m, KDL::Twist &k) | 
| static void | vector3MsgToTF (const geometry_msgs::Vector3 &msg_v, Vector3 &bt_v) | 
| static void | vector3StampedMsgToTF (const geometry_msgs::Vector3Stamped &msg, Stamped< Vector3 > &bt) | 
| static void | vector3StampedTFToMsg (const Stamped< Vector3 > &bt, geometry_msgs::Vector3Stamped &msg) | 
| static void | vector3TFToMsg (const Vector3 &bt_v, geometry_msgs::Vector3 &msg_v) | 
| void | vectorEigenToTF (const Eigen::Vector3d &e, tf::Vector3 &t) | 
| Converts an Eigen Vector3d into a tf Vector3.  More... | |
| void | vectorKDLToMsg (const KDL::Vector &k, geometry_msgs::Vector3 &m) | 
| void | vectorKDLToTF (const KDL::Vector &k, tf::Vector3 &t) | 
| Converts a tf Vector3 into a KDL Vector.  More... | |
| ROS_DEPRECATED void | VectorKDLToTF (const KDL::Vector &k, tf::Vector3 &t) | 
| Converts a tf Vector3 into a KDL Vector.  More... | |
| void | vectorMsgToKDL (const geometry_msgs::Vector3 &m, KDL::Vector &k) | 
| void | vectorTFToEigen (const tf::Vector3 &t, Eigen::Vector3d &e) | 
| Converts a tf Vector3 into an Eigen Vector3d.  More... | |
| void | vectorTFToKDL (const tf::Vector3 &t, KDL::Vector &k) | 
| Converts a tf Vector3 into a KDL Vector.  More... | |
| ROS_DEPRECATED void | VectorTFToKDL (const tf::Vector3 &t, KDL::Vector &k) | 
| Converts a tf Vector3 into a KDL Vector.  More... | |
| void | wrenchKDLToMsg (const KDL::Wrench &k, geometry_msgs::Wrench &m) | 
| void | wrenchMsgToKDL (const geometry_msgs::Wrench &m, KDL::Wrench &k) | 
| Variables | |
| CONNECTIVITY_ERROR | |
| EXTRAPOLATE_BACK | |
| EXTRAPOLATE_FORWARD | |
| EXTRAPOLATION_ERROR | |
| INTERPOLATE | |
| LOOKUP_ERROR | |
| NO_ERROR | |
| ONE_VALUE | |
| static const double | QUATERNION_TOLERANCE | 
| geometry_msgs::Pose tf::addDelta | ( | const geometry_msgs::Pose & | pose, | 
| const geometry_msgs::Twist & | twist, | ||
| const double & | t | ||
| ) | 
Starting from a Pose from A to B, apply a Twist with reference frame A and reference point B, during a time t.
Definition at line 95 of file tf_kdl.cpp.
| void tf::matrixEigenToTF | ( | const Eigen::Matrix3d & | e, | 
| tf::Matrix3x3 & | t | ||
| ) | 
Converts an Eigen Quaternion into a tf Matrix3x3.
Definition at line 43 of file tf_eigen.cpp.
| void tf::matrixTFToEigen | ( | const tf::Matrix3x3 & | t, | 
| Eigen::Matrix3d & | e | ||
| ) | 
Converts a tf Matrix3x3 into an Eigen Quaternion.
Definition at line 36 of file tf_eigen.cpp.
| void tf::poseEigenToTF | ( | const Eigen::Affine3d & | e, | 
| tf::Pose & | t | ||
| ) | 
Converts an Eigen Affine3d into a tf Transform.
Definition at line 60 of file tf_eigen.cpp.
| void tf::poseEigenToTF | ( | const Eigen::Isometry3d & | e, | 
| tf::Pose & | t | ||
| ) | 
Converts an Eigen Isometry3d into a tf Transform.
Definition at line 65 of file tf_eigen.cpp.
| void tf::poseKDLToTF | ( | const KDL::Frame & | k, | 
| tf::Pose & | t | ||
| ) | 
Converts a KDL Frame into a tf Pose.
Definition at line 43 of file tf_kdl.cpp.
| 
 | inline | 
| void tf::poseTFToEigen | ( | const tf::Pose & | t, | 
| Eigen::Affine3d & | e | ||
| ) | 
Converts a tf Pose into an Eigen Affine3d.
Definition at line 50 of file tf_eigen.cpp.
| void tf::poseTFToEigen | ( | const tf::Pose & | t, | 
| Eigen::Isometry3d & | e | ||
| ) | 
Converts a tf Pose into an Eigen Isometry3d.
Definition at line 55 of file tf_eigen.cpp.
| void tf::poseTFToKDL | ( | const tf::Pose & | t, | 
| KDL::Frame & | k | ||
| ) | 
Converts a tf Pose into a KDL Frame.
Definition at line 35 of file tf_kdl.cpp.
| 
 | inline | 
| void tf::quaternionEigenToTF | ( | const Eigen::Quaterniond & | e, | 
| tf::Quaternion & | t | ||
| ) | 
Converts an Eigen Quaternion into a tf Quaternion.
Definition at line 75 of file tf_eigen.cpp.
| void tf::quaternionKDLToTF | ( | const KDL::Rotation & | k, | 
| tf::Quaternion & | t | ||
| ) | 
Converts a tf Quaternion into a KDL Rotation.
Definition at line 56 of file tf_kdl.cpp.
| 
 | inline | 
Converts a tf Quaternion into a KDL Rotation.
| void tf::quaternionTFToEigen | ( | const tf::Quaternion & | t, | 
| Eigen::Quaterniond & | e | ||
| ) | 
Converts a tf Quaternion into an Eigen Quaternion.
Definition at line 70 of file tf_eigen.cpp.
| void tf::quaternionTFToKDL | ( | const tf::Quaternion & | t, | 
| KDL::Rotation & | k | ||
| ) | 
Converts a tf Quaternion into a KDL Rotation.
Definition at line 51 of file tf_kdl.cpp.
| 
 | inline | 
Converts a tf Quaternion into a KDL Rotation.
| void tf::transformEigenToTF | ( | const Eigen::Affine3d & | e, | 
| tf::Transform & | t | ||
| ) | 
Converts an Eigen Affine3d into a tf Transform.
Definition at line 121 of file tf_eigen.cpp.
| void tf::transformEigenToTF | ( | const Eigen::Isometry3d & | e, | 
| tf::Transform & | t | ||
| ) | 
Converts an Eigen Isometry3d into a tf Transform.
Definition at line 126 of file tf_eigen.cpp.
| void tf::transformKDLToTF | ( | const KDL::Frame & | k, | 
| tf::Transform & | t | ||
| ) | 
Converts a KDL Frame into a tf Transform.
Definition at line 71 of file tf_kdl.cpp.
| 
 | inline | 
| void tf::transformTFToEigen | ( | const tf::Transform & | t, | 
| Eigen::Affine3d & | e | ||
| ) | 
Converts a tf Transform into an Eigen Affine3d.
Definition at line 111 of file tf_eigen.cpp.
| void tf::transformTFToEigen | ( | const tf::Transform & | t, | 
| Eigen::Isometry3d & | e | ||
| ) | 
Converts a tf Transform into an Eigen Isometry3d.
Definition at line 116 of file tf_eigen.cpp.
| void tf::transformTFToKDL | ( | const tf::Transform & | t, | 
| KDL::Frame & | k | ||
| ) | 
Converts a tf Transform into a KDL Frame.
Definition at line 63 of file tf_kdl.cpp.
| 
 | inline | 
| void tf::vectorEigenToTF | ( | const Eigen::Vector3d & | e, | 
| tf::Vector3 & | t | ||
| ) | 
Converts an Eigen Vector3d into a tf Vector3.
Definition at line 138 of file tf_eigen.cpp.
| void tf::vectorKDLToTF | ( | const KDL::Vector & | k, | 
| tf::Vector3 & | t | ||
| ) | 
Converts a tf Vector3 into a KDL Vector.
Definition at line 86 of file tf_kdl.cpp.
| 
 | inline | 
| void tf::vectorTFToEigen | ( | const tf::Vector3 & | t, | 
| Eigen::Vector3d & | e | ||
| ) | 
Converts a tf Vector3 into an Eigen Vector3d.
Definition at line 131 of file tf_eigen.cpp.
| void tf::vectorTFToKDL | ( | const tf::Vector3 & | t, | 
| KDL::Vector & | k | ||
| ) | 
Converts a tf Vector3 into a KDL Vector.
Definition at line 79 of file tf_kdl.cpp.