|
| __attribute__ ((deprecated)) static inline std |
|
class tf::Vector3 | __attribute__ ((aligned(16))) |
|
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 tf::Quaternion &q) |
|
void | assertQuaternionValid (const geometry_msgs::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) |
|
TFSIMD_FORCE_INLINE Vector3 | operator* (const Vector3 &v1, const Vector3 &v2) |
|
TFSIMD_FORCE_INLINE Quaternion | operator* (const Quaternion &q1, const Quaternion &q2) |
|
TFSIMD_FORCE_INLINE Quaternion | operator* (const Quaternion &q, const Vector3 &w) |
|
TFSIMD_FORCE_INLINE Quaternion | operator* (const Vector3 &w, const Quaternion &q) |
|
TFSIMD_FORCE_INLINE Vector3 | operator* (const Vector3 &v, const tfScalar &s) |
|
TFSIMD_FORCE_INLINE Vector3 | operator* (const tfScalar &s, const Vector3 &v) |
|
TFSIMD_FORCE_INLINE Vector3 | operator* (const Matrix3x3 &m, const Vector3 &v) |
|
TFSIMD_FORCE_INLINE Vector3 | operator* (const Vector3 &v, const Matrix3x3 &m) |
|
TFSIMD_FORCE_INLINE Matrix3x3 | operator* (const Matrix3x3 &m1, const Matrix3x3 &m2) |
|
TFSIMD_FORCE_INLINE Vector3 | operator+ (const Vector3 &v1, const Vector3 &v2) |
|
TFSIMD_FORCE_INLINE Vector3 | operator- (const Vector3 &v) |
|
TFSIMD_FORCE_INLINE Quaternion | operator- (const Quaternion &q) |
|
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) |
|
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) |
|
TFSIMD_FORCE_INLINE bool | operator== (const Matrix3x3 &m1, const Matrix3x3 &m2) |
|
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) |
|
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) |
|
static void | poseTFToMsg (const Pose &bt, geometry_msgs::Pose &msg) |
|
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) |
|
static void | quaternionTFToMsg (const Quaternion &bt, geometry_msgs::Quaternion &msg) |
|
TFSIMD_FORCE_INLINE Vector3 | quatRotate (const Quaternion &rotation, const Vector3 &v) |
|
std::string | remap (const std::string &frame_id) __attribute__((deprecated)) |
|
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) |
|
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) |
|
static void | transformTFToMsg (const Transform &bt, geometry_msgs::Transform &msg) |
|
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) |
|