|
void | doTransform (const T &data_in, T &data_out, const geometry_msgs::msg::TransformStamped &transform) |
|
tf2::TimePoint | getTimestamp (const T &t) |
|
std::string | getFrameId (const T &t) |
|
tf2::TimePoint | getTimestamp (const tf2::Stamped< P > &t) |
|
std::string | getFrameId (const tf2::Stamped< P > &t) |
|
B | toMsg (const A &a) |
|
void | fromMsg (const A &, B &b) |
|
void | convert (const A &a, B &b) |
|
void | convert (const A &a1, A &a2) |
|
TF2SIMD_FORCE_INLINE Vector3 | operator* (const Matrix3x3 &m, const Vector3 &v) |
|
TF2SIMD_FORCE_INLINE Vector3 | operator* (const Vector3 &v, const Matrix3x3 &m) |
|
TF2SIMD_FORCE_INLINE Matrix3x3 | operator* (const Matrix3x3 &m1, const Matrix3x3 &m2) |
|
TF2SIMD_FORCE_INLINE bool | operator== (const Matrix3x3 &m1, const Matrix3x3 &m2) |
|
| ATTRIBUTE_ALIGNED16 (class) QuadWord |
|
TF2SIMD_FORCE_INLINE Quaternion | operator- (const Quaternion &q) |
|
TF2SIMD_FORCE_INLINE Quaternion | operator* (const Quaternion &q1, const Quaternion &q2) |
|
TF2SIMD_FORCE_INLINE Quaternion | operator* (const Quaternion &q, const Vector3 &w) |
|
TF2SIMD_FORCE_INLINE Quaternion | operator* (const Vector3 &w, const Quaternion &q) |
|
TF2SIMD_FORCE_INLINE tf2Scalar | dot (const Quaternion &q1, const Quaternion &q2) |
|
TF2SIMD_FORCE_INLINE tf2Scalar | length (const Quaternion &q) |
|
TF2SIMD_FORCE_INLINE tf2Scalar | angle (const Quaternion &q1, const Quaternion &q2) |
|
TF2SIMD_FORCE_INLINE tf2Scalar | angleShortestPath (const Quaternion &q1, const Quaternion &q2) |
|
TF2SIMD_FORCE_INLINE Quaternion | inverse (const Quaternion &q) |
|
TF2SIMD_FORCE_INLINE Quaternion | slerp (const Quaternion &q1, const Quaternion &q2, const tf2Scalar &t) |
|
TF2SIMD_FORCE_INLINE Vector3 | quatRotate (const Quaternion &rotation, const Vector3 &v) |
|
TF2SIMD_FORCE_INLINE Quaternion | shortestArcQuat (const Vector3 &v0, const Vector3 &v1) |
|
TF2SIMD_FORCE_INLINE Quaternion | shortestArcQuatNormalize2 (Vector3 &v0, Vector3 &v1) |
|
TF2SIMD_FORCE_INLINE bool | operator== (const Transform &t1, const Transform &t2) |
|
TF2SIMD_FORCE_INLINE Vector3 | operator+ (const Vector3 &v1, const Vector3 &v2) |
|
TF2SIMD_FORCE_INLINE Vector3 | operator* (const Vector3 &v1, const Vector3 &v2) |
|
TF2SIMD_FORCE_INLINE Vector3 | operator- (const Vector3 &v1, const Vector3 &v2) |
|
TF2SIMD_FORCE_INLINE Vector3 | operator- (const Vector3 &v) |
|
TF2SIMD_FORCE_INLINE Vector3 | operator* (const Vector3 &v, const tf2Scalar &s) |
|
TF2SIMD_FORCE_INLINE Vector3 | operator* (const tf2Scalar &s, const Vector3 &v) |
|
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 tf2Scalar | tf2Dot (const Vector3 &v1, const Vector3 &v2) |
|
TF2SIMD_FORCE_INLINE tf2Scalar | tf2Distance2 (const Vector3 &v1, const Vector3 &v2) |
|
TF2SIMD_FORCE_INLINE tf2Scalar | tf2Distance (const Vector3 &v1, const Vector3 &v2) |
|
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 | tf2Triple (const Vector3 &v1, const Vector3 &v2, const Vector3 &v3) |
|
TF2SIMD_FORCE_INLINE Vector3 | lerp (const Vector3 &v1, const Vector3 &v2, const tf2Scalar &t) |
|
TF2SIMD_FORCE_INLINE void | tf2SwapScalarEndian (const tf2Scalar &sourceVal, tf2Scalar &destVal) |
|
TF2SIMD_FORCE_INLINE void | tf2SwapVector3Endian (const Vector3 &sourceVec, Vector3 &destVec) |
|
TF2SIMD_FORCE_INLINE void | tf2UnSwapVector3Endian (Vector3 &vector) |
|
TF2SIMD_FORCE_INLINE void | tf2PlaneSpace1 (const Vector3 &n, Vector3 &p, Vector3 &q) |
|
TimePoint | get_now () |
|
Duration | durationFromSec (double t_sec) |
|
TimePoint | timeFromSec (double t_sec) |
|
double | durationToSec (const tf2::Duration &input) |
|
double | timeToSec (const TimePoint &timepoint) |
|
std::string | displayTimePoint (const TimePoint &stamp) |
|
bool | operator== (const Stamped< T > &a, const Stamped< T > &b) |
|
void | getEulerYPR (const A &a, double &yaw, double &pitch, double &roll) |
|
double | getYaw (const A &a) |
|
A | getTransformIdentity () |
|
KDL::Frame | transformToKDL (const geometry_msgs::msg::TransformStamped &t) |
| Convert a timestamped transform to the equivalent KDL data type. More...
|
|
geometry_msgs::msg::TransformStamped | kdlToTransform (const KDL::Frame &k) |
| Convert an KDL Frame to the equivalent geometry_msgs message type. More...
|
|
template<> |
void | doTransform (const tf2::Stamped< KDL::Vector > &t_in, tf2::Stamped< KDL::Vector > &t_out, const geometry_msgs::msg::TransformStamped &transform) |
| Apply a geometry_msgs TransformStamped to an KDL-specific Vector type. This function is a specialization of the doTransform template defined in tf2/convert.h. More...
|
|
geometry_msgs::msg::PointStamped | toMsg (const tf2::Stamped< KDL::Vector > &in) |
| Convert a stamped KDL Vector type to a PointStamped message. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
|
|
void | fromMsg (const geometry_msgs::msg::PointStamped &msg, tf2::Stamped< KDL::Vector > &out) |
| Convert a PointStamped message type to a stamped KDL-specific Vector type. This function is a specialization of the fromMsg template defined in tf2/convert.h. More...
|
|
template<> |
void | doTransform (const tf2::Stamped< KDL::Twist > &t_in, tf2::Stamped< KDL::Twist > &t_out, const geometry_msgs::msg::TransformStamped &transform) |
| Apply a geometry_msgs TransformStamped to an KDL-specific Twist type. This function is a specialization of the doTransform template defined in tf2/convert.h. More...
|
|
geometry_msgs::msg::TwistStamped | toMsg (const tf2::Stamped< KDL::Twist > &in) |
| Convert a stamped KDL Twist type to a TwistStamped message. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
|
|
void | fromMsg (const geometry_msgs::msg::TwistStamped &msg, tf2::Stamped< KDL::Twist > &out) |
| Convert a TwistStamped message type to a stamped KDL-specific Twist type. This function is a specialization of the fromMsg template defined in tf2/convert.h. More...
|
|
template<> |
void | doTransform (const tf2::Stamped< KDL::Wrench > &t_in, tf2::Stamped< KDL::Wrench > &t_out, const geometry_msgs::msg::TransformStamped &transform) |
| Apply a geometry_msgs TransformStamped to an KDL-specific Wrench type. This function is a specialization of the doTransform template defined in tf2/convert.h. More...
|
|
geometry_msgs::msg::WrenchStamped | toMsg (const tf2::Stamped< KDL::Wrench > &in) |
| Convert a stamped KDL Wrench type to a WrenchStamped message. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
|
|
void | fromMsg (const geometry_msgs::msg::WrenchStamped &msg, tf2::Stamped< KDL::Wrench > &out) |
| Convert a WrenchStamped message type to a stamped KDL-specific Wrench type. This function is a specialization of the fromMsg template defined in tf2/convert.h. More...
|
|
template<> |
void | doTransform (const tf2::Stamped< KDL::Frame > &t_in, tf2::Stamped< KDL::Frame > &t_out, const geometry_msgs::msg::TransformStamped &transform) |
| Apply a geometry_msgs TransformStamped to a KDL-specific Frame data type. This function is a specialization of the doTransform template defined in tf2/convert.h. More...
|
|
geometry_msgs::msg::Pose | toMsg (const KDL::Frame &in) |
| Convert a stamped KDL Frame type to a Pose message. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
|
|
void | fromMsg (const geometry_msgs::msg::Pose &msg, KDL::Frame &out) |
| Convert a Pose message type to a KDL Frame. This function is a specialization of the fromMsg template defined in tf2/convert.h. More...
|
|
geometry_msgs::msg::PoseStamped | toMsg (const tf2::Stamped< KDL::Frame > &in) |
| Convert a stamped KDL Frame type to a Pose message. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
|
|
void | fromMsg (const geometry_msgs::msg::PoseStamped &msg, tf2::Stamped< KDL::Frame > &out) |
| Convert a Pose message transform type to a stamped KDL Frame. This function is a specialization of the fromMsg template defined in tf2/convert.h. More...
|
|