|
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) |
|
void | doTransform (const T &data_in, T &data_out, const geometry_msgs::TransformStamped &transform) |
|
template<> |
void | doTransform (const geometry_msgs::Point &t_in, geometry_msgs::Point &t_out, const geometry_msgs::TransformStamped &transform) |
| Apply a geometry_msgs TransformStamped to an geometry_msgs Point type. This function is a specialization of the doTransform template defined in tf2/convert.h. More...
|
|
template<> |
void | doTransform (const geometry_msgs::PointStamped &t_in, geometry_msgs::PointStamped &t_out, const geometry_msgs::TransformStamped &transform) |
| Apply a geometry_msgs TransformStamped to an stamped geometry_msgs Point type. This function is a specialization of the doTransform template defined in tf2/convert.h. More...
|
|
template<> |
void | doTransform (const geometry_msgs::Quaternion &t_in, geometry_msgs::Quaternion &t_out, const geometry_msgs::TransformStamped &transform) |
| Apply a geometry_msgs TransformStamped to an geometry_msgs Quaternion type. This function is a specialization of the doTransform template defined in tf2/convert.h. More...
|
|
template<> |
void | doTransform (const geometry_msgs::QuaternionStamped &t_in, geometry_msgs::QuaternionStamped &t_out, const geometry_msgs::TransformStamped &transform) |
| Apply a geometry_msgs TransformStamped to an stamped geometry_msgs Quaternion type. This function is a specialization of the doTransform template defined in tf2/convert.h. More...
|
|
template<> |
void | doTransform (const geometry_msgs::Pose &t_in, geometry_msgs::Pose &t_out, const geometry_msgs::TransformStamped &transform) |
| Apply a geometry_msgs TransformStamped to an geometry_msgs Pose type. This function is a specialization of the doTransform template defined in tf2/convert.h. More...
|
|
template<> |
void | doTransform (const geometry_msgs::PoseStamped &t_in, geometry_msgs::PoseStamped &t_out, const geometry_msgs::TransformStamped &transform) |
| Apply a geometry_msgs TransformStamped to an stamped geometry_msgs Pose type. This function is a specialization of the doTransform template defined in tf2/convert.h. More...
|
|
template<> |
void | doTransform (const geometry_msgs::PoseWithCovarianceStamped &t_in, geometry_msgs::PoseWithCovarianceStamped &t_out, const geometry_msgs::TransformStamped &transform) |
| Apply a geometry_msgs TransformStamped to an geometry_msgs PoseWithCovarianceStamped type. This function is a specialization of the doTransform template defined in tf2/convert.h. More...
|
|
template<> |
void | doTransform (const geometry_msgs::TransformStamped &t_in, geometry_msgs::TransformStamped &t_out, const geometry_msgs::TransformStamped &transform) |
| Apply a geometry_msgs TransformStamped to an geometry_msgs Transform type. This function is a specialization of the doTransform template defined in tf2/convert.h. More...
|
|
template<> |
void | doTransform (const geometry_msgs::Vector3 &t_in, geometry_msgs::Vector3 &t_out, const geometry_msgs::TransformStamped &transform) |
| Apply a geometry_msgs TransformStamped to an geometry_msgs Vector type. This function is a specialization of the doTransform template defined in tf2/convert.h. More...
|
|
template<> |
void | doTransform (const geometry_msgs::Vector3Stamped &t_in, geometry_msgs::Vector3Stamped &t_out, const geometry_msgs::TransformStamped &transform) |
| Apply a geometry_msgs TransformStamped to an stamped geometry_msgs Vector type. This function is a specialization of the doTransform template defined in tf2/convert.h. More...
|
|
template<> |
void | doTransform (const geometry_msgs::Wrench &t_in, geometry_msgs::Wrench &t_out, const geometry_msgs::TransformStamped &transform) |
|
template<> |
void | doTransform (const geometry_msgs::WrenchStamped &t_in, geometry_msgs::WrenchStamped &t_out, const geometry_msgs::TransformStamped &transform) |
|
void | fromMsg (const A &, B &b) |
|
void | fromMsg (const geometry_msgs::Vector3 &in, tf2::Vector3 &out) |
| Convert a Vector3 message to its equivalent tf2 representation. This function is a specialization of the fromMsg template defined in tf2/convert.h. More...
|
|
void | fromMsg (const geometry_msgs::Vector3Stamped &msg, geometry_msgs::Vector3Stamped &out) |
| Trivial "conversion" function for Vector3 message type. This function is a specialization of the fromMsg template defined in tf2/convert.h. More...
|
|
void | fromMsg (const geometry_msgs::Vector3Stamped &msg, tf2::Stamped< tf2::Vector3 > &out) |
| Convert a Vector3Stamped message to its equivalent tf2 representation. This function is a specialization of the fromMsg template defined in tf2/convert.h. More...
|
|
void | fromMsg (const geometry_msgs::Point &in, tf2::Vector3 &out) |
| Convert a Vector3 message to its equivalent tf2 representation. This function is a specialization of the fromMsg template defined in tf2/convert.h. More...
|
|
void | fromMsg (const geometry_msgs::PointStamped &msg, geometry_msgs::PointStamped &out) |
| Trivial "conversion" function for Point message 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< tf2::Vector3 > &out) |
| Convert a PointStamped message to its equivalent tf2 representation. This function is a specialization of the fromMsg template defined in tf2/convert.h. More...
|
|
void | fromMsg (const geometry_msgs::Quaternion &in, tf2::Quaternion &out) |
| Convert a Quaternion message to its equivalent tf2 representation. This function is a specialization of the fromMsg template defined in tf2/convert.h. More...
|
|
void | fromMsg (const geometry_msgs::QuaternionStamped &msg, geometry_msgs::QuaternionStamped &out) |
| Trivial "conversion" function for Quaternion message type. This function is a specialization of the fromMsg template defined in tf2/convert.h. More...
|
|
void | fromMsg (const geometry_msgs::QuaternionStamped &in, tf2::Stamped< tf2::Quaternion > &out) |
| Convert a QuaternionStamped message to its equivalent tf2 representation. This function is a specialization of the fromMsg template defined in tf2/convert.h. More...
|
|
void | fromMsg (const geometry_msgs::Pose &in, tf2::Transform &out) |
| Convert a geometry_msgs Pose message to an equivalent tf2 Transform type. More...
|
|
void | fromMsg (const geometry_msgs::PoseStamped &msg, geometry_msgs::PoseStamped &out) |
| Trivial "conversion" function for Pose message type. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
|
|
void | fromMsg (const geometry_msgs::PoseStamped &msg, tf2::Stamped< tf2::Transform > &out) |
| Convert a PoseStamped message to its equivalent tf2 representation. This function is a specialization of the fromMsg template defined in tf2/convert.h. More...
|
|
void | fromMsg (const geometry_msgs::PoseWithCovarianceStamped &msg, geometry_msgs::PoseWithCovarianceStamped &out) |
| Trivial "conversion" function for PoseWithCovarianceStamped message type. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
|
|
void | fromMsg (const geometry_msgs::PoseWithCovarianceStamped &msg, tf2::Stamped< tf2::Transform > &out) |
| Convert a PoseWithCovarianceStamped message to its equivalent tf2 representation. This function is a specialization of the fromMsg template defined in tf2/convert.h. More...
|
|
void | fromMsg (const geometry_msgs::Transform &in, tf2::Transform &out) |
| Convert a Transform message to its equivalent tf2 representation. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
|
|
void | fromMsg (const geometry_msgs::TransformStamped &msg, geometry_msgs::TransformStamped &out) |
| Convert a TransformStamped message to its equivalent tf2 representation. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
|
|
void | fromMsg (const geometry_msgs::TransformStamped &msg, tf2::Stamped< tf2::Transform > &out) |
| Convert a TransformStamped message to its equivalent tf2 representation. This function is a specialization of the fromMsg template defined in tf2/convert.h. More...
|
|
void | fromMsg (const geometry_msgs::WrenchStamped &msg, geometry_msgs::WrenchStamped &out) |
|
void | fromMsg (const geometry_msgs::WrenchStamped &msg, tf2::Stamped< boost::array< tf2::Vector3, 2 > > &out) |
|
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) |
|
template<> |
const std::string & | getFrameId (const geometry_msgs::Vector3Stamped &t) |
| Extract a frame ID from the header of a Vector message. This function is a specialization of the getFrameId template defined in tf2/convert.h. More...
|
|
template<> |
const std::string & | getFrameId (const geometry_msgs::PointStamped &t) |
| Extract a frame ID from the header of a Point message. This function is a specialization of the getFrameId template defined in tf2/convert.h. More...
|
|
template<> |
const std::string & | getFrameId (const geometry_msgs::QuaternionStamped &t) |
| Extract a frame ID from the header of a Quaternion message. This function is a specialization of the getFrameId template defined in tf2/convert.h. More...
|
|
template<> |
const std::string & | getFrameId (const geometry_msgs::PoseStamped &t) |
| Extract a frame ID from the header of a Pose message. This function is a specialization of the getFrameId template defined in tf2/convert.h. More...
|
|
template<> |
const std::string & | getFrameId (const geometry_msgs::PoseWithCovarianceStamped &t) |
| Extract a frame ID from the header of a PoseWithCovarianceStamped message. This function is a specialization of the getFrameId template defined in tf2/convert.h. More...
|
|
template<> |
const std::string & | getFrameId (const geometry_msgs::TransformStamped &t) |
| Extract a frame ID from the header of a Transform message. This function is a specialization of the getFrameId template defined in tf2/convert.h. More...
|
|
template<> |
const std::string & | getFrameId (const geometry_msgs::WrenchStamped &t) |
|
const ros::Time & | getTimestamp (const T &t) |
|
const ros::Time & | getTimestamp (const tf2::Stamped< P > &t) |
|
template<> |
const ros::Time & | getTimestamp (const geometry_msgs::Vector3Stamped &t) |
| Extract a timestamp from the header of a Vector message. This function is a specialization of the getTimestamp template defined in tf2/convert.h. More...
|
|
template<> |
const ros::Time & | getTimestamp (const geometry_msgs::PointStamped &t) |
| Extract a timestamp from the header of a Point message. This function is a specialization of the getTimestamp template defined in tf2/convert.h. More...
|
|
template<> |
const ros::Time & | getTimestamp (const geometry_msgs::QuaternionStamped &t) |
| Extract a timestamp from the header of a Quaternion message. This function is a specialization of the getTimestamp template defined in tf2/convert.h. More...
|
|
template<> |
const ros::Time & | getTimestamp (const geometry_msgs::PoseStamped &t) |
| Extract a timestamp from the header of a Pose message. This function is a specialization of the getTimestamp template defined in tf2/convert.h. More...
|
|
template<> |
const ros::Time & | getTimestamp (const geometry_msgs::PoseWithCovarianceStamped &t) |
| Extract a timestamp from the header of a PoseWithCovarianceStamped message. This function is a specialization of the getTimestamp template defined in tf2/convert.h. More...
|
|
template<> |
const ros::Time & | getTimestamp (const geometry_msgs::TransformStamped &t) |
| Extract a timestamp from the header of a Transform message. This function is a specialization of the getTimestamp template defined in tf2/convert.h. More...
|
|
template<> |
const ros::Time & | getTimestamp (const geometry_msgs::WrenchStamped &t) |
|
A | getTransformIdentity () |
|
double | getYaw (const A &a) |
|
KDL::Frame | gmTransformToKDL (const geometry_msgs::TransformStamped &t) __attribute__((deprecated)) |
| Convert a TransformStamped message to a KDL frame. More...
|
|
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 Vector3 &v1, const Vector3 &v2) |
|
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 Vector3 | operator* (const Vector3 &v, const tf2Scalar &s) |
|
TF2SIMD_FORCE_INLINE Vector3 | operator* (const tf2Scalar &s, const Vector3 &v) |
|
TF2SIMD_FORCE_INLINE Quaternion | operator* (const Vector3 &w, const Quaternion &q) |
|
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 Vector3 | operator+ (const Vector3 &v1, const Vector3 &v2) |
|
TF2SIMD_FORCE_INLINE Vector3 | operator- (const Vector3 &v) |
|
TF2SIMD_FORCE_INLINE Quaternion | operator- (const Quaternion &q) |
|
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) |
|
bool | operator== (const Stamped< T > &a, const Stamped< T > &b) |
|
TF2SIMD_FORCE_INLINE bool | operator== (const Transform &t1, const Transform &t2) |
|
TF2SIMD_FORCE_INLINE bool | operator== (const Matrix3x3 &m1, const Matrix3x3 &m2) |
|
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::Vector3 | toMsg (const tf2::Vector3 &in) |
| Convert a tf2 Vector3 type to its equivalent geometry_msgs representation. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
|
|
geometry_msgs::Vector3Stamped | toMsg (const geometry_msgs::Vector3Stamped &in) |
| Trivial "conversion" function for Vector3 message type. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
|
|
geometry_msgs::Vector3Stamped | toMsg (const tf2::Stamped< tf2::Vector3 > &in) |
| Convert as stamped tf2 Vector3 type to its equivalent geometry_msgs representation. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
|
|
geometry_msgs::Point & | toMsg (const tf2::Vector3 &in, geometry_msgs::Point &out) |
| Convert a tf2 Vector3 type to its equivalent geometry_msgs representation. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
|
|
geometry_msgs::PointStamped | toMsg (const geometry_msgs::PointStamped &in) |
| Trivial "conversion" function for Point message type. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
|
|
geometry_msgs::PointStamped | toMsg (const tf2::Stamped< tf2::Vector3 > &in, geometry_msgs::PointStamped &out) |
| Convert as stamped tf2 Vector3 type to its equivalent geometry_msgs representation. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
|
|
geometry_msgs::Quaternion | toMsg (const tf2::Quaternion &in) |
| Convert a tf2 Quaternion type to its equivalent geometry_msgs representation. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
|
|
geometry_msgs::QuaternionStamped | toMsg (const geometry_msgs::QuaternionStamped &in) |
| Trivial "conversion" function for Quaternion message type. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
|
|
geometry_msgs::QuaternionStamped | toMsg (const tf2::Stamped< tf2::Quaternion > &in) |
| Convert as stamped tf2 Quaternion type to its equivalent geometry_msgs representation. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
|
|
geometry_msgs::Pose & | toMsg (const tf2::Transform &in, geometry_msgs::Pose &out) |
| Convert a tf2 Transform type to an equivalent geometry_msgs Pose message. More...
|
|
geometry_msgs::PoseStamped | toMsg (const geometry_msgs::PoseStamped &in) |
| Trivial "conversion" function for Pose message type. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
|
|
geometry_msgs::PoseStamped | toMsg (const tf2::Stamped< tf2::Transform > &in, geometry_msgs::PoseStamped &out) |
| Convert as stamped tf2 Pose type to its equivalent geometry_msgs representation. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
|
|
geometry_msgs::PoseWithCovarianceStamped | toMsg (const geometry_msgs::PoseWithCovarianceStamped &in) |
| Trivial "conversion" function for PoseWithCovarianceStamped message type. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
|
|
geometry_msgs::PoseWithCovarianceStamped | toMsg (const tf2::Stamped< tf2::Transform > &in, geometry_msgs::PoseWithCovarianceStamped &out) |
| Convert as stamped tf2 PoseWithCovarianceStamped type to its equivalent geometry_msgs representation. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
|
|
geometry_msgs::Transform | toMsg (const tf2::Transform &in) |
| Convert a tf2 Transform type to its equivalent geometry_msgs representation. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
|
|
geometry_msgs::TransformStamped | toMsg (const geometry_msgs::TransformStamped &in) |
| Trivial "conversion" function for Transform message type. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
|
|
geometry_msgs::TransformStamped | toMsg (const tf2::Stamped< tf2::Transform > &in) |
| Convert as stamped tf2 Transform type to its equivalent geometry_msgs representation. This function is a specialization of the toMsg template defined in tf2/convert.h. More...
|
|
geometry_msgs::WrenchStamped | toMsg (const geometry_msgs::WrenchStamped &in) |
|
geometry_msgs::WrenchStamped | toMsg (const tf2::Stamped< boost::array< tf2::Vector3, 2 > > &in, geometry_msgs::WrenchStamped &out) |
|
geometry_msgs::PoseWithCovariance::_covariance_type | transformCovariance (const geometry_msgs::PoseWithCovariance::_covariance_type &cov_in, const tf2::Transform &transform) |
| Transform the covariance matrix of a PoseWithCovarianceStamped message to a new frame. More...
|
|
void | transformMsgToTF2 (const geometry_msgs::Transform &msg, tf2::Transform &tf2) |
|
void | transformTF2ToMsg (const tf2::Transform &tf2, geometry_msgs::Transform &msg) |
|
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::TransformStamped &msg, ros::Time stamp, const std::string &frame_id, const std::string &child_frame_id) |
|