Functions | |
geometry_msgs::Pose | addDelta (const geometry_msgs::Pose &pose, const geometry_msgs::Twist &twist, const double &t) __attribute__((deprecated)) |
Starting from a Pose from A to B, apply a Twist with reference frame A and reference point B, during a time t. | |
void | PoseKDLToMsg (const KDL::Frame &t, geometry_msgs::Pose &p) |
Converts a KDL Frame into a Pose message. | |
void | PoseKDLToTF (const KDL::Frame &frame, tf::Pose &pose) |
Converts a KDL Frame into a tf Pose. | |
void | PoseMsgToKDL (const geometry_msgs::Pose &p, KDL::Frame &t) |
Converts a Pose message into a KDL Frame. | |
void | PoseTFToKDL (const tf::Pose &pose, KDL::Frame &frame) |
Converts a tf Pose into a KDL Frame. | |
void | RotationEigenToTF (const Eigen::eigen2_Quaterniond &k, tf::Quaternion &t) |
Converts an Eigen Quaternion into a tf Quaternion. | |
void | RotationTFToEigen (const tf::Quaternion &t, Eigen::eigen2_Quaterniond &k) |
Converts a tf Quaternion into an Eigen Quaternion. | |
void | RotationTFToKDL (const tf::Quaternion &t, KDL::Rotation &k) |
Converts a tf Quaternion into a KDL Rotation. | |
void | TransformEigenToTF (const Eigen::eigen2_Transform3d &k, tf::Transform &t) |
Converts an Eigen eigen2_Transform3d into a tf Transform. | |
void | TransformKDLToTF (const KDL::Frame &k, tf::Transform &t) |
Converts a KDL Frame into a tf Transform. | |
void | TransformTFToEigen (const tf::Transform &t, Eigen::eigen2_Transform3d &k) |
Converts a tf eigen2_Transform into an Eigen Transform3d. | |
void | TransformTFToKDL (const tf::Transform &t, KDL::Frame &k) |
Converts a tf Transform into a KDL Frame. | |
void | TwistKDLToMsg (const KDL::Twist &t, geometry_msgs::Twist &m) |
Converts a KDL Twist into a Twist message. | |
void | TwistMsgToKDL (const geometry_msgs::Twist &m, KDL::Twist &t) |
Converts a Twist message into a KDL Twist. | |
void | VectorEigenToTF (const Eigen::Vector3d &k, tf::Vector3 &t) |
Converts an Eigen Vector3d into a tf Vector3. | |
void | VectorTFToEigen (const tf::Vector3 &t, Eigen::Vector3d &k) |
Converts a tf Vector3 into an Eigen Vector3d. | |
void | VectorTFToKDL (const tf::Vector3 &t, KDL::Vector &k) |
Converts a tf Vector3 into a KDL Vector. |
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 109 of file tf_kdl.cpp.
void tf::PoseKDLToMsg | ( | const KDL::Frame & | t, | |
geometry_msgs::Pose & | p | |||
) |
Converts a KDL Frame into a Pose message.
Definition at line 102 of file tf_kdl.cpp.
void tf::PoseKDLToTF | ( | const KDL::Frame & | frame, | |
tf::Pose & | pose | |||
) |
Converts a KDL Frame into a tf Pose.
Definition at line 67 of file tf_kdl.cpp.
void tf::PoseMsgToKDL | ( | const geometry_msgs::Pose & | p, | |
KDL::Frame & | t | |||
) |
Converts a Pose message into a KDL Frame.
Definition at line 95 of file tf_kdl.cpp.
void tf::PoseTFToKDL | ( | const tf::Pose & | pose, | |
KDL::Frame & | frame | |||
) |
Converts a tf Pose into a KDL Frame.
Definition at line 59 of file tf_kdl.cpp.
void tf::RotationEigenToTF | ( | const Eigen::eigen2_Quaterniond & | k, | |
tf::Quaternion & | t | |||
) |
Converts an Eigen Quaternion into a tf Quaternion.
Definition at line 53 of file tf_eigen.cpp.
void tf::RotationTFToEigen | ( | const tf::Quaternion & | t, | |
Eigen::eigen2_Quaterniond & | k | |||
) |
Converts a tf Quaternion into an Eigen Quaternion.
Definition at line 47 of file tf_eigen.cpp.
void tf::RotationTFToKDL | ( | const tf::Quaternion & | t, | |
KDL::Rotation & | k | |||
) |
Converts a tf Quaternion into a KDL Rotation.
Definition at line 38 of file tf_kdl.cpp.
void tf::TransformEigenToTF | ( | const Eigen::eigen2_Transform3d & | k, | |
tf::Transform & | t | |||
) |
Converts an Eigen eigen2_Transform3d into a tf Transform.
Definition at line 78 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 51 of file tf_kdl.cpp.
void tf::TransformTFToEigen | ( | const tf::Transform & | t, | |
Eigen::eigen2_Transform3d & | k | |||
) |
Converts a tf eigen2_Transform into an Eigen Transform3d.
Definition at line 61 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 43 of file tf_kdl.cpp.
void tf::TwistKDLToMsg | ( | const KDL::Twist & | t, | |
geometry_msgs::Twist & | m | |||
) |
Converts a KDL Twist into a Twist message.
Definition at line 75 of file tf_kdl.cpp.
void tf::TwistMsgToKDL | ( | const geometry_msgs::Twist & | m, | |
KDL::Twist & | t | |||
) |
Converts a Twist message into a KDL Twist.
Definition at line 85 of file tf_kdl.cpp.
void tf::VectorEigenToTF | ( | const Eigen::Vector3d & | k, | |
tf::Vector3 & | t | |||
) |
Converts an Eigen Vector3d into a tf Vector3.
Definition at line 40 of file tf_eigen.cpp.
void tf::VectorTFToEigen | ( | const tf::Vector3 & | t, | |
Eigen::Vector3d & | k | |||
) |
Converts a tf Vector3 into an Eigen Vector3d.
Definition at line 33 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 33 of file tf_kdl.cpp.