Namespaces | |
filter_failure_reasons | |
Classes | |
class | Matrix3x3 |
The Matrix3x3 class implements a 3x3 rotation matrix, to perform linear algebra in combination with Quaternion, Transform and Vector3. Make sure to only include a pure orthogonal matrix without scaling. More... | |
struct | Matrix3x3DoubleData |
for serialization More... | |
struct | Matrix3x3FloatData |
for serialization More... | |
class | MessageFilter |
Follows the patterns set by the message_filters package to implement a filter which only passes messages through once there is transform data available. More... | |
class | MessageFilterBase |
class | Quaternion |
The Quaternion implements quaternion to perform linear algebra rotations in combination with Matrix3x3, Vector3 and Transform. More... | |
class | Stamped |
The data type which will be cross compatable with geometry_msgs This is the tf datatype equivilant of a MessageStamped. More... | |
class | StampedTransform |
The Stamped Transform datatype used by tf. More... | |
class | tfVector4 |
class | TimeCache |
A class to keep a sorted linked list in time This builds and maintains a list of timestamped data. And provides lookup functions to get data out as a function of time. More... | |
class | Transform |
The Transform class supports rigid transforms with only translation and rotation and no scaling/shear. It can be used in combination with Vector3, Quaternion and Matrix3x3 linear algebra classes. More... | |
class | TransformBroadcaster |
This class provides an easy way to publish coordinate frame transform information. It will handle all the messaging and stuffing of messages. And the function prototypes lay out all the necessary data needed for each message. More... | |
struct | TransformDoubleData |
class | Transformer |
A Class which provides coordinate transforms between any two frames in a system. More... | |
struct | TransformFloatData |
for serialization More... | |
class | TransformListener |
This class inherits from Transformer and automatically subscribes to ROS transform messages. More... | |
struct | TransformLists |
An internal representation of transform chains. More... | |
class | TransformStorage |
Storage for transforms and their parent. More... | |
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 { NO_ERROR = 0, LOOKUP_ERROR, CONNECTIVITY_ERROR, EXTRAPOLATION_ERROR } |
enum | ExtrapolationMode { ONE_VALUE, INTERPOLATE, EXTRAPOLATE_BACK, EXTRAPOLATE_FORWARD } |
Functions | |
TFSIMD_FORCE_INLINE tfScalar | angle (const Quaternion &q1, const Quaternion &q2) |
Return the half angle between two quaternions. More... | |
TFSIMD_FORCE_INLINE tfScalar | angleShortestPath (const Quaternion &q1, const Quaternion &q2) |
Return the shortest angle between two quaternions. More... | |
void | assertQuaternionValid (const tf::Quaternion &q) |
Throw InvalidArgument if quaternion is malformed. More... | |
void | assertQuaternionValid (const geometry_msgs::Quaternion &q) |
Throw InvalidArgument if quaternion is malformed. More... | |
ATTRIBUTE_ALIGNED16 (class) QuadWord | |
The QuadWord class is base class for Vector3 and Quaternion. Some issues under PS3 Linux with IBM 2.1 SDK, gcc compiler prevent from using aligned quadword. More... | |
static tf::Quaternion | createIdentityQuaternion () |
construct an Identity Quaternion More... | |
static tf::Quaternion | createQuaternionFromRPY (double roll, double pitch, double yaw) |
construct a Quaternion from Fixed angles More... | |
static Quaternion | createQuaternionFromYaw (double yaw) |
construct a Quaternion from yaw only More... | |
static geometry_msgs::Quaternion | createQuaternionMsgFromRollPitchYaw (double roll, double pitch, double yaw) |
construct a Quaternion Message from Fixed angles More... | |
static geometry_msgs::Quaternion | createQuaternionMsgFromYaw (double yaw) |
construct a Quaternion Message from yaw only More... | |
TFSIMD_FORCE_INLINE tfScalar | dot (const Quaternion &q1, const Quaternion &q2) |
Calculate the dot product between two quaternions. More... | |
std::string | getPrefixParam (ros::NodeHandle &nh) |
Get the tf_prefix from the parameter server. More... | |
static double | getYaw (const Quaternion &bt_q) |
Helper function for getting yaw from a Quaternion. More... | |
static double | getYaw (const geometry_msgs::Quaternion &msg_q) |
Helper function for getting yaw from a Quaternion message. More... | |
TFSIMD_FORCE_INLINE Quaternion | inverse (const Quaternion &q) |
Return the inverse of a quaternion. More... | |
TFSIMD_FORCE_INLINE tfScalar | length (const Quaternion &q) |
Return the length of a quaternion. More... | |
TFSIMD_FORCE_INLINE Vector3 | lerp (const Vector3 &v1, const Vector3 &v2, const tfScalar &t) |
Return the linear interpolation between two vectors. More... | |
TFSIMD_FORCE_INLINE Vector3 | operator* (const Vector3 &v1, const Vector3 &v2) |
Return the elementwise product of two vectors. More... | |
TFSIMD_FORCE_INLINE Quaternion | operator* (const Quaternion &q1, const Quaternion &q2) |
Return the product of two quaternions. More... | |
TFSIMD_FORCE_INLINE Quaternion | operator* (const Quaternion &q, const Vector3 &w) |
TFSIMD_FORCE_INLINE Vector3 | operator* (const Vector3 &v, const tfScalar &s) |
Return the vector scaled by s. More... | |
TFSIMD_FORCE_INLINE Quaternion | operator* (const Vector3 &w, const Quaternion &q) |
TFSIMD_FORCE_INLINE Vector3 | operator* (const tfScalar &s, const Vector3 &v) |
Return the vector scaled by s. More... | |
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) |
Return the sum of two vectors (Point symantics) More... | |
TFSIMD_FORCE_INLINE Quaternion | operator- (const Quaternion &q) |
Return the negative of a quaternion. More... | |
TFSIMD_FORCE_INLINE Vector3 | operator- (const Vector3 &v1, const Vector3 &v2) |
Return the difference between two vectors. More... | |
TFSIMD_FORCE_INLINE Vector3 | operator- (const Vector3 &v) |
Return the negative of the vector. More... | |
TFSIMD_FORCE_INLINE Vector3 | operator/ (const Vector3 &v, const tfScalar &s) |
Return the vector inversely scaled by s. More... | |
TFSIMD_FORCE_INLINE Vector3 | operator/ (const Vector3 &v1, const Vector3 &v2) |
Return the vector inversely scaled by s. More... | |
template<typename T > | |
bool | operator== (const Stamped< T > &a, const Stamped< T > &b) |
Comparison Operator for Stamped datatypes. More... | |
static bool | operator== (const StampedTransform &a, const StampedTransform &b) |
Comparison operator for StampedTransform. More... | |
TFSIMD_FORCE_INLINE bool | operator== (const Transform &t1, const Transform &t2) |
Test if two transforms have all elements equal. More... | |
TFSIMD_FORCE_INLINE bool | operator== (const Matrix3x3 &m1, const Matrix3x3 &m2) |
Equality operator between two matrices It will test all elements are equal. More... | |
static void | pointMsgToTF (const geometry_msgs::Point &msg_v, Point &bt_v) |
convert Point msg to Point More... | |
static void | pointStampedMsgToTF (const geometry_msgs::PointStamped &msg, Stamped< Point > &bt) |
convert PointStamped msg to Stamped<Point> More... | |
static void | pointStampedTFToMsg (const Stamped< Point > &bt, geometry_msgs::PointStamped &msg) |
convert Stamped<Point> to PointStamped msg More... | |
static void | pointTFToMsg (const Point &bt_v, geometry_msgs::Point &msg_v) |
convert Point to Point msg More... | |
static void | poseMsgToTF (const geometry_msgs::Pose &msg, Pose &bt) |
convert Pose msg to Pose More... | |
static void | poseStampedMsgToTF (const geometry_msgs::PoseStamped &msg, Stamped< Pose > &bt) |
convert PoseStamped msg to Stamped<Pose> More... | |
static void | poseStampedTFToMsg (const Stamped< Pose > &bt, geometry_msgs::PoseStamped &msg) |
convert Stamped<Pose> to PoseStamped msg More... | |
static void | poseTFToMsg (const Pose &bt, geometry_msgs::Pose &msg) |
convert Pose to Pose msg More... | |
static void | quaternionMsgToTF (const geometry_msgs::Quaternion &msg, Quaternion &bt) |
convert Quaternion msg to Quaternion More... | |
static void | quaternionStampedMsgToTF (const geometry_msgs::QuaternionStamped &msg, Stamped< Quaternion > &bt) |
convert QuaternionStamped msg to Stamped<Quaternion> More... | |
static void | quaternionStampedTFToMsg (const Stamped< Quaternion > &bt, geometry_msgs::QuaternionStamped &msg) |
convert Stamped<Quaternion> to QuaternionStamped msg More... | |
static void | quaternionTFToMsg (const Quaternion &bt, geometry_msgs::Quaternion &msg) |
convert Quaternion to Quaternion msg More... | |
TFSIMD_FORCE_INLINE Vector3 | quatRotate (const Quaternion &rotation, const Vector3 &v) |
ROS_DEPRECATED std::string | remap (const std::string &frame_id) |
resolve names More... | |
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) |
resolve tf names More... | |
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) |
Return the result of spherical linear interpolation betwen two quaternions. More... | |
std::string | strip_leading_slash (const std::string &frame_name) |
TFSIMD_FORCE_INLINE tfScalar | tfAngle (const Vector3 &v1, const Vector3 &v2) |
Return the angle between two vectors. More... | |
TFSIMD_FORCE_INLINE Vector3 | tfCross (const Vector3 &v1, const Vector3 &v2) |
Return the cross product of two vectors. More... | |
TFSIMD_FORCE_INLINE tfScalar | tfDistance (const Vector3 &v1, const Vector3 &v2) |
Return the distance between two vectors. More... | |
TFSIMD_FORCE_INLINE tfScalar | tfDistance2 (const Vector3 &v1, const Vector3 &v2) |
Return the distance squared between two vectors. More... | |
TFSIMD_FORCE_INLINE tfScalar | tfDot (const Vector3 &v1, const Vector3 &v2) |
Return the dot product between two vectors. More... | |
TFSIMD_FORCE_INLINE void | tfPlaneSpace1 (const Vector3 &n, Vector3 &p, Vector3 &q) |
TFSIMD_FORCE_INLINE void | tfSwapScalarEndian (const tfScalar &sourceVal, tfScalar &destVal) |
tfSwapVector3Endian swaps vector endianness, useful for network and cross-platform serialization More... | |
TFSIMD_FORCE_INLINE void | tfSwapVector3Endian (const Vector3 &sourceVec, Vector3 &destVec) |
tfSwapVector3Endian swaps vector endianness, useful for network and cross-platform serialization More... | |
TFSIMD_FORCE_INLINE tfScalar | tfTriple (const Vector3 &v1, const Vector3 &v2, const Vector3 &v3) |
TFSIMD_FORCE_INLINE void | tfUnSwapVector3Endian (Vector3 &vector) |
tfUnSwapVector3Endian swaps vector endianness, useful for network and cross-platform serialization More... | |
static void | transformMsgToTF (const geometry_msgs::Transform &msg, Transform &bt) |
convert Transform msg to Transform More... | |
static void | transformStampedMsgToTF (const geometry_msgs::TransformStamped &msg, StampedTransform &bt) |
convert TransformStamped msg to tf::StampedTransform More... | |
static void | transformStampedTFToMsg (const StampedTransform &bt, geometry_msgs::TransformStamped &msg) |
convert tf::StampedTransform to TransformStamped msg More... | |
static void | transformTFToMsg (const Transform &bt, geometry_msgs::Transform &msg) |
convert Transform to Transform msg More... | |
static void | vector3MsgToTF (const geometry_msgs::Vector3 &msg_v, Vector3 &bt_v) |
convert Vector3 msg to Vector3 More... | |
static void | vector3StampedMsgToTF (const geometry_msgs::Vector3Stamped &msg, Stamped< Vector3 > &bt) |
convert Vector3Stamped msg to Stamped<Vector3> More... | |
static void | vector3StampedTFToMsg (const Stamped< Vector3 > &bt, geometry_msgs::Vector3Stamped &msg) |
convert Stamped<Vector3> to Vector3Stamped msg More... | |
static void | vector3TFToMsg (const Vector3 &bt_v, geometry_msgs::Vector3 &msg_v) |
convert Vector3 to Vector3 msg More... | |
Variables | |
static const double | QUATERNION_TOLERANCE = 0.1f |
typedef uint32_t tf::CompactFrameID |
Definition at line 50 of file time_cache.h.
Definition at line 43 of file exceptions.h.
Definition at line 44 of file exceptions.h.
Definition at line 75 of file message_filter.h.
Definition at line 45 of file exceptions.h.
Definition at line 42 of file exceptions.h.
typedef std::pair<ros::Time, CompactFrameID> tf::P_TimeAndFrameID |
Definition at line 51 of file time_cache.h.
typedef tf::Vector3 tf::Point |
Definition at line 49 of file transform_datatypes.h.
typedef tf::Transform tf::Pose |
Definition at line 50 of file transform_datatypes.h.
Definition at line 41 of file exceptions.h.
enum tf::ErrorValues |
Enumerator | |
---|---|
ONE_VALUE | |
INTERPOLATE | |
EXTRAPOLATE_BACK | |
EXTRAPOLATE_FORWARD |
Definition at line 47 of file time_cache.h.
TFSIMD_FORCE_INLINE tfScalar tf::angle | ( | const Quaternion & | q1, |
const Quaternion & | q2 | ||
) |
Return the half angle between two quaternions.
Definition at line 407 of file Quaternion.h.
TFSIMD_FORCE_INLINE tfScalar tf::angleShortestPath | ( | const Quaternion & | q1, |
const Quaternion & | q2 | ||
) |
Return the shortest angle between two quaternions.
Definition at line 414 of file Quaternion.h.
|
inline |
|
inline |
tf::ATTRIBUTE_ALIGNED16 | ( | class | ) |
The QuadWord class is base class for Vector3 and Quaternion. Some issues under PS3 Linux with IBM 2.1 SDK, gcc compiler prevent from using aligned quadword.
Return the x value
Return the y value
Return the z value
Set the x value
Set the y value
Set the z value
Set the w value
Return the x value
Return the y value
Return the z value
Return the w value
operator tfScalar*() replaces operator[], using implicit conversion. We added operator != and operator == to avoid pointer comparisons.
Set x,y,z and zero w
x | Value of x |
y | Value of y |
z | Value of z |
Set the values
x | Value of x |
y | Value of y |
z | Value of z |
w | Value of w |
No initialization constructor
Three argument constructor (zeros w)
x | Value of x |
y | Value of y |
z | Value of z |
Initializing constructor
x | Value of x |
y | Value of y |
z | Value of z |
w | Value of w |
Set each element to the max of the current values and the values of another QuadWord
other | The other QuadWord to compare with |
Set each element to the min of the current values and the values of another QuadWord
other | The other QuadWord to compare with |
No initialization constructor
Constructor from scalars
x | X value |
y | Y value |
z | Z value |
Add a vector to this one
The | vector to add to this one |
Sutfract a vector from this one
The | vector to sutfract |
Scale the vector
s | Scale factor |
Inversely scale the vector
s | Scale factor to divide by |
Return the dot product
v | The other vector in the dot product |
Return the length of the vector squared
Return the length of the vector
Return the distance squared between the ends of this and another vector This is symantically treating the vector like a point
Return the distance between the ends of this and another vector This is symantically treating the vector like a point
Normalize this vector x^2 + y^2 + z^2 = 1
Return a normalized version of this vector
Rotate this vector
wAxis | The axis to rotate about |
angle | The angle to rotate by |
Return the angle between this and another vector
v | The other vector |
Return a vector will the absolute values of each element
Return the cross product between this and another vector
v | The other vector |
Return the axis with the smallest value Note return values are 0,1,2 for x, y, or z
Return the axis with the largest value Note return values are 0,1,2 for x, y, or z
Return the linear interpolation between this and another vector
v | The other vector |
t | The ration of this to v (t = 0 => return this, t=1 => return other) |
Elementwise multiply this vector by the other
v | The other vector |
Return the x value
Return the y value
Return the z value
Set the x value
Set the y value
Set the z value
Set the w value
Return the x value
Return the y value
Return the z value
Return the w value
operator tfScalar*() replaces operator[], using implicit conversion. We added operator != and operator == to avoid pointer comparisons.
Set each element to the max of the current values and the values of another Vector3
other | The other Vector3 to compare with |
Set each element to the min of the current values and the values of another Vector3
other | The other Vector3 to compare with |
No initialization constructor
Constructor from scalars
x | X value |
y | Y value |
z | Z value |
Add a vector to this one
The | vector to add to this one |
Sutfract a vector from this one
The | vector to sutfract |
Scale the vector
s | Scale factor |
Inversely scale the vector
s | Scale factor to divide by |
Return the dot product
v | The other vector in the dot product |
Return the length of the vector squared
Return the length of the vector
Return the distance squared between the ends of this and another vector This is symantically treating the vector like a point
Return the distance between the ends of this and another vector This is symantically treating the vector like a point
Normalize this vector x^2 + y^2 + z^2 = 1
Return a normalized version of this vector
Rotate this vector
wAxis | The axis to rotate about |
angle | The angle to rotate by |
Return the angle between this and another vector
v | The other vector |
Return a vector will the absolute values of each element
Return the cross product between this and another vector
v | The other vector |
Return the axis with the smallest value Note return values are 0,1,2 for x, y, or z
Return the axis with the largest value Note return values are 0,1,2 for x, y, or z
Return the linear interpolation between this and another vector
v | The other vector |
t | The ration of this to v (t = 0 => return this, t=1 => return other) |
Elementwise multiply this vector by the other
v | The other vector |
Return the x value
Return the y value
Return the z value
Set the x value
Set the y value
Set the z value
Set the w value
Return the x value
Return the y value
Return the z value
Return the w value
operator tfScalar*() replaces operator[], using implicit conversion. We added operator != and operator == to avoid pointer comparisons.
Set each element to the max of the current values and the values of another Vector3
other | The other Vector3 to compare with |
Set each element to the min of the current values and the values of another Vector3
other | The other Vector3 to compare with |
Definition at line 34 of file QuadWord.h.
|
inlinestatic |
construct an Identity Quaternion
Definition at line 193 of file transform_datatypes.h.
|
inlinestatic |
construct a Quaternion from Fixed angles
roll | The roll about the X axis |
pitch | The pitch about the Y axis |
yaw | The yaw about the Z axis |
Definition at line 150 of file transform_datatypes.h.
|
inlinestatic |
construct a Quaternion from yaw only
yaw | The yaw about the Z axis |
Definition at line 160 of file transform_datatypes.h.
|
inlinestatic |
construct a Quaternion Message from Fixed angles
roll | The roll about the X axis |
pitch | The pitch about the Y axis |
yaw | The yaw about the Z axis |
Definition at line 184 of file transform_datatypes.h.
|
inlinestatic |
construct a Quaternion Message from yaw only
yaw | The yaw about the Z axis |
Definition at line 170 of file transform_datatypes.h.
TFSIMD_FORCE_INLINE tfScalar tf::dot | ( | const Quaternion & | q1, |
const Quaternion & | q2 | ||
) |
Calculate the dot product between two quaternions.
Definition at line 392 of file Quaternion.h.
|
inline |
Get the tf_prefix from the parameter server.
nh | The node handle to use to lookup the parameter. |
Definition at line 55 of file transform_listener.h.
|
inlinestatic |
Helper function for getting yaw from a Quaternion.
Definition at line 131 of file transform_datatypes.h.
|
inlinestatic |
Helper function for getting yaw from a Quaternion message.
Definition at line 138 of file transform_datatypes.h.
TFSIMD_FORCE_INLINE Quaternion tf::inverse | ( | const Quaternion & | q | ) |
Return the inverse of a quaternion.
Definition at line 421 of file Quaternion.h.
TFSIMD_FORCE_INLINE tfScalar tf::length | ( | const Quaternion & | q | ) |
Return the length of a quaternion.
Definition at line 400 of file Quaternion.h.
TFSIMD_FORCE_INLINE Vector3 tf::lerp | ( | const Vector3 & | v1, |
const Vector3 & | v2, | ||
const tfScalar & | t | ||
) |
TFSIMD_FORCE_INLINE Vector3 tf::operator* | ( | const Vector3 & | v1, |
const Vector3 & | v2 | ||
) |
TFSIMD_FORCE_INLINE Quaternion tf::operator* | ( | const Quaternion & | q1, |
const Quaternion & | q2 | ||
) |
Return the product of two quaternions.
Definition at line 365 of file Quaternion.h.
TFSIMD_FORCE_INLINE Quaternion tf::operator* | ( | const Quaternion & | q, |
const Vector3 & | w | ||
) |
Definition at line 373 of file Quaternion.h.
TFSIMD_FORCE_INLINE Vector3 tf::operator* | ( | const Vector3 & | v, |
const tfScalar & | s | ||
) |
TFSIMD_FORCE_INLINE Quaternion tf::operator* | ( | const Vector3 & | w, |
const Quaternion & | q | ||
) |
Definition at line 382 of file Quaternion.h.
TFSIMD_FORCE_INLINE Vector3 tf::operator* | ( | const tfScalar & | s, |
const Vector3 & | v | ||
) |
TFSIMD_FORCE_INLINE Vector3 tf::operator* | ( | const Matrix3x3 & | m, |
const Vector3 & | v | ||
) |
Definition at line 604 of file Matrix3x3.h.
TFSIMD_FORCE_INLINE Vector3 tf::operator* | ( | const Vector3 & | v, |
const Matrix3x3 & | m | ||
) |
Definition at line 611 of file Matrix3x3.h.
TFSIMD_FORCE_INLINE Matrix3x3 tf::operator* | ( | const Matrix3x3 & | m1, |
const Matrix3x3 & | m2 | ||
) |
Definition at line 617 of file Matrix3x3.h.
TFSIMD_FORCE_INLINE Vector3 tf::operator+ | ( | const Vector3 & | v1, |
const Vector3 & | v2 | ||
) |
TFSIMD_FORCE_INLINE Quaternion tf::operator- | ( | const Quaternion & | q | ) |
Return the negative of a quaternion.
Definition at line 356 of file Quaternion.h.
TFSIMD_FORCE_INLINE Vector3 tf::operator- | ( | const Vector3 & | v1, |
const Vector3 & | v2 | ||
) |
TFSIMD_FORCE_INLINE Vector3 tf::operator- | ( | const Vector3 & | v | ) |
TFSIMD_FORCE_INLINE Vector3 tf::operator/ | ( | const Vector3 & | v, |
const tfScalar & | s | ||
) |
TFSIMD_FORCE_INLINE Vector3 tf::operator/ | ( | const Vector3 & | v1, |
const Vector3 & | v2 | ||
) |
Comparison Operator for Stamped datatypes.
Definition at line 75 of file transform_datatypes.h.
|
inlinestatic |
Comparison operator for StampedTransform.
Definition at line 99 of file transform_datatypes.h.
TFSIMD_FORCE_INLINE bool tf::operator== | ( | const Transform & | t1, |
const Transform & | t2 | ||
) |
Test if two transforms have all elements equal.
Definition at line 243 of file Transform.h.
TFSIMD_FORCE_INLINE bool tf::operator== | ( | const Matrix3x3 & | m1, |
const Matrix3x3 & | m2 | ||
) |
Equality operator between two matrices It will test all elements are equal.
Definition at line 642 of file Matrix3x3.h.
|
inlinestatic |
convert Point msg to Point
Definition at line 221 of file transform_datatypes.h.
|
inlinestatic |
convert PointStamped msg to Stamped<Point>
Definition at line 226 of file transform_datatypes.h.
|
inlinestatic |
convert Stamped<Point> to PointStamped msg
Definition at line 229 of file transform_datatypes.h.
|
inlinestatic |
convert Point to Point msg
Definition at line 223 of file transform_datatypes.h.
|
inlinestatic |
convert Pose msg to Pose
Definition at line 248 of file transform_datatypes.h.
|
inlinestatic |
convert PoseStamped msg to Stamped<Pose>
Definition at line 255 of file transform_datatypes.h.
|
inlinestatic |
convert Stamped<Pose> to PoseStamped msg
Definition at line 258 of file transform_datatypes.h.
|
inlinestatic |
convert Pose to Pose msg
Definition at line 251 of file transform_datatypes.h.
|
inlinestatic |
convert Quaternion msg to Quaternion
Definition at line 105 of file transform_datatypes.h.
|
inlinestatic |
convert QuaternionStamped msg to Stamped<Quaternion>
Definition at line 201 of file transform_datatypes.h.
|
inlinestatic |
convert Stamped<Quaternion> to QuaternionStamped msg
Definition at line 204 of file transform_datatypes.h.
|
inlinestatic |
convert Quaternion to Quaternion msg
Definition at line 115 of file transform_datatypes.h.
TFSIMD_FORCE_INLINE Vector3 tf::quatRotate | ( | const Quaternion & | rotation, |
const Vector3 & | v | ||
) |
Definition at line 438 of file Quaternion.h.
std::string tf::remap | ( | const std::string & | frame_id | ) |
resolve names
Definition at line 36 of file transform_listener.cpp.
|
inlinestatic |
std::string tf::resolve | ( | const std::string & | prefix, |
const std::string & | frame_name | ||
) |
TFSIMD_FORCE_INLINE Quaternion tf::shortestArcQuat | ( | const Vector3 & | v0, |
const Vector3 & | v1 | ||
) |
Definition at line 446 of file Quaternion.h.
TFSIMD_FORCE_INLINE Quaternion tf::shortestArcQuatNormalize2 | ( | Vector3 & | v0, |
Vector3 & | v1 | ||
) |
Definition at line 465 of file Quaternion.h.
TFSIMD_FORCE_INLINE Quaternion tf::slerp | ( | const Quaternion & | q1, |
const Quaternion & | q2, | ||
const tfScalar & | t | ||
) |
Return the result of spherical linear interpolation betwen two quaternions.
q1 | The first quaternion |
q2 | The second quaternion |
t | The ration between q1 and q2. t = 0 return q1, t=1 returns q2 Slerp assumes constant velocity between positions. |
Definition at line 432 of file Quaternion.h.
std::string tf::strip_leading_slash | ( | const std::string & | frame_name | ) |
TFSIMD_FORCE_INLINE tfScalar tf::tfAngle | ( | const Vector3 & | v1, |
const Vector3 & | v2 | ||
) |
TFSIMD_FORCE_INLINE Vector3 tf::tfCross | ( | const Vector3 & | v1, |
const Vector3 & | v2 | ||
) |
TFSIMD_FORCE_INLINE tfScalar tf::tfDistance | ( | const Vector3 & | v1, |
const Vector3 & | v2 | ||
) |
TFSIMD_FORCE_INLINE tfScalar tf::tfDistance2 | ( | const Vector3 & | v1, |
const Vector3 & | v2 | ||
) |
TFSIMD_FORCE_INLINE tfScalar tf::tfDot | ( | const Vector3 & | v1, |
const Vector3 & | v2 | ||
) |
TFSIMD_FORCE_INLINE void tf::tfPlaneSpace1 | ( | const Vector3 & | n, |
Vector3 & | p, | ||
Vector3 & | q | ||
) |
TFSIMD_FORCE_INLINE void tf::tfSwapScalarEndian | ( | const tfScalar & | sourceVal, |
tfScalar & | destVal | ||
) |
TFSIMD_FORCE_INLINE void tf::tfSwapVector3Endian | ( | const Vector3 & | sourceVec, |
Vector3 & | destVec | ||
) |
TFSIMD_FORCE_INLINE tfScalar tf::tfTriple | ( | const Vector3 & | v1, |
const Vector3 & | v2, | ||
const Vector3 & | v3 | ||
) |
TFSIMD_FORCE_INLINE void tf::tfUnSwapVector3Endian | ( | Vector3 & | vector | ) |
|
inlinestatic |
convert Transform msg to Transform
Definition at line 234 of file transform_datatypes.h.
|
inlinestatic |
convert TransformStamped msg to tf::StampedTransform
Definition at line 241 of file transform_datatypes.h.
|
inlinestatic |
convert tf::StampedTransform to TransformStamped msg
Definition at line 244 of file transform_datatypes.h.
|
inlinestatic |
convert Transform to Transform msg
Definition at line 237 of file transform_datatypes.h.
|
inlinestatic |
convert Vector3 msg to Vector3
Definition at line 208 of file transform_datatypes.h.
|
inlinestatic |
convert Vector3Stamped msg to Stamped<Vector3>
Definition at line 213 of file transform_datatypes.h.
|
inlinestatic |
convert Stamped<Vector3> to Vector3Stamped msg
Definition at line 216 of file transform_datatypes.h.
|
inlinestatic |
convert Vector3 to Vector3 msg
Definition at line 210 of file transform_datatypes.h.
|
static |
Definition at line 52 of file transform_datatypes.h.