tf2  master
tf2 maintains the relationship between coordinate frames in a tree structure buffered in time, and lets the user transform points, vectors, etc between any two coordinate frames at any desired point in time.
Namespaces | Classes | Typedefs | Enumerations | Functions | Variables
tf2 Namespace Reference

Namespaces

 impl
 

Classes

class  BufferCore
 A Class which provides coordinate transforms between any two frames in a system. More...
 
class  BufferCoreInterface
 Interface for providing coordinate transforms between any two frames in a system. More...
 
class  ConnectivityException
 An exception class to notify of no connection. More...
 
class  ExtrapolationException
 An exception class to notify that the requested value would have required extrapolation beyond current limits. More...
 
class  InvalidArgumentException
 An exception class to notify that one of the arguments is invalid. More...
 
class  LookupException
 An exception class to notify of bad frame number. More...
 
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  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 tf2 datatype equivilant of a MessageStamped. More...
 
class  StaticCache
 
class  tf2Vector4
 
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  TimeCacheInterface
 
class  TimeoutException
 An exception class to notify that a timeout has occured. 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...
 
struct  TransformDoubleData
 
class  TransformException
 A base class for all tf2 exceptions This inherits from ros::exception which inherits from std::runtime_exception. More...
 
struct  TransformFloatData
 for serialization More...
 
class  TransformStorage
 Storage for transforms and their parent. More...
 
struct  Vector3DoubleData
 
struct  Vector3FloatData
 

Typedefs

typedef std::pair< TimePoint, CompactFrameIDP_TimeAndFrameID
 
typedef uint32_t TransformableCallbackHandle
 
typedef uint64_t TransformableRequestHandle
 
using TimeCacheInterfacePtr = std::shared_ptr< TimeCacheInterface >
 
using Duration = std::chrono::nanoseconds
 
using TimePoint = std::chrono::time_point< std::chrono::system_clock, Duration >
 
using IDuration = std::chrono::duration< int, std::nano >
 
typedef uint32_t CompactFrameID
 

Enumerations

enum  TransformableResult { TransformAvailable, TransformFailure }
 
enum  TF2Error : std::uint8_t {
  TF2Error::NO_ERROR = 0, TF2Error::LOOKUP_ERROR = 1, TF2Error::CONNECTIVITY_ERROR = 2, TF2Error::EXTRAPOLATION_ERROR = 3,
  TF2Error::INVALID_ARGUMENT_ERROR = 4, TF2Error::TIMEOUT_ERROR = 5, TF2Error::TRANSFORM_ERROR = 6
}
 

Functions

template<class T >
void doTransform (const T &data_in, T &data_out, const geometry_msgs::msg::TransformStamped &transform)
 The templated function expected to be able to do a transform. More...
 
template<class T >
tf2::TimePoint getTimestamp (const T &t)
 Get the timestamp from data. More...
 
template<class T >
std::string getFrameId (const T &t)
 Get the frame_id from data. More...
 
template<class P >
tf2::TimePoint getTimestamp (const tf2::Stamped< P > &t)
 
template<class P >
std::string getFrameId (const tf2::Stamped< P > &t)
 
template<typename A , typename B >
toMsg (const A &a)
 
template<typename A , typename B >
void fromMsg (const A &, B &b)
 
template<class A , class B >
void convert (const A &a, B &b)
 
template<class A >
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)
 Equality operator between two matrices It will test all elements are equal.
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...
 
TF2SIMD_FORCE_INLINE Quaternion operator- (const Quaternion &q)
 Return the negative of a quaternion. More...
 
TF2SIMD_FORCE_INLINE Quaternion operator* (const Quaternion &q1, const Quaternion &q2)
 Return the product of two quaternions. More...
 
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)
 Calculate the dot product between two quaternions. More...
 
TF2SIMD_FORCE_INLINE tf2Scalar length (const Quaternion &q)
 Return the length of a quaternion. More...
 
TF2SIMD_FORCE_INLINE tf2Scalar angle (const Quaternion &q1, const Quaternion &q2)
 Return the half angle between two quaternions. More...
 
TF2SIMD_FORCE_INLINE tf2Scalar angleShortestPath (const Quaternion &q1, const Quaternion &q2)
 Return the shortest angle between two quaternions. More...
 
TF2SIMD_FORCE_INLINE Quaternion inverse (const Quaternion &q)
 Return the inverse of a quaternion. More...
 
TF2SIMD_FORCE_INLINE Quaternion slerp (const Quaternion &q1, const Quaternion &q2, const tf2Scalar &t)
 Return the result of spherical linear interpolation betwen two quaternions. More...
 
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)
 Test if two transforms have all elements equal. More...
 
TF2SIMD_FORCE_INLINE Vector3 operator+ (const Vector3 &v1, const Vector3 &v2)
 Return the sum of two vectors (Point symantics) More...
 
TF2SIMD_FORCE_INLINE Vector3 operator* (const Vector3 &v1, const Vector3 &v2)
 Return the elementwise product of two vectors. More...
 
TF2SIMD_FORCE_INLINE Vector3 operator- (const Vector3 &v1, const Vector3 &v2)
 Return the difference between two vectors. More...
 
TF2SIMD_FORCE_INLINE Vector3 operator- (const Vector3 &v)
 Return the negative of the vector. More...
 
TF2SIMD_FORCE_INLINE Vector3 operator* (const Vector3 &v, const tf2Scalar &s)
 Return the vector scaled by s. More...
 
TF2SIMD_FORCE_INLINE Vector3 operator* (const tf2Scalar &s, const Vector3 &v)
 Return the vector scaled by s. More...
 
TF2SIMD_FORCE_INLINE Vector3 operator/ (const Vector3 &v, const tf2Scalar &s)
 Return the vector inversely scaled by s. More...
 
TF2SIMD_FORCE_INLINE Vector3 operator/ (const Vector3 &v1, const Vector3 &v2)
 Return the vector inversely scaled by s. More...
 
TF2SIMD_FORCE_INLINE tf2Scalar tf2Dot (const Vector3 &v1, const Vector3 &v2)
 Return the dot product between two vectors. More...
 
TF2SIMD_FORCE_INLINE tf2Scalar tf2Distance2 (const Vector3 &v1, const Vector3 &v2)
 Return the distance squared between two vectors. More...
 
TF2SIMD_FORCE_INLINE tf2Scalar tf2Distance (const Vector3 &v1, const Vector3 &v2)
 Return the distance between two vectors. More...
 
TF2SIMD_FORCE_INLINE tf2Scalar tf2Angle (const Vector3 &v1, const Vector3 &v2)
 Return the angle between two vectors. More...
 
TF2SIMD_FORCE_INLINE Vector3 tf2Cross (const Vector3 &v1, const Vector3 &v2)
 Return the cross product of two vectors. More...
 
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)
 Return the linear interpolation between two vectors. More...
 
TF2SIMD_FORCE_INLINE void tf2SwapScalarEndian (const tf2Scalar &sourceVal, tf2Scalar &destVal)
 tf2SwapVector3Endian swaps vector endianness, useful for network and cross-platform serialization More...
 
TF2SIMD_FORCE_INLINE void tf2SwapVector3Endian (const Vector3 &sourceVec, Vector3 &destVec)
 tf2SwapVector3Endian swaps vector endianness, useful for network and cross-platform serialization More...
 
TF2SIMD_FORCE_INLINE void tf2UnSwapVector3Endian (Vector3 &vector)
 tf2UnSwapVector3Endian swaps vector endianness, useful for network and cross-platform serialization More...
 
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)
 
template<typename T >
bool operator== (const Stamped< T > &a, const Stamped< T > &b)
 Comparison Operator for Stamped datatypes. More...
 
template<class A >
void getEulerYPR (const A &a, double &yaw, double &pitch, double &roll)
 
template<class A >
double getYaw (const A &a)
 
template<class A >
getTransformIdentity ()
 

Variables

constexpr tf2::Duration TIMECACHE_DEFAULT_MAX_STORAGE_TIME = std::chrono::seconds(10)
 default value of 10 seconds storage More...
 

Detailed Description

Author
Tully Foote

Typedef Documentation

◆ P_TimeAndFrameID

◆ TransformableCallbackHandle

◆ TransformableRequestHandle

◆ TimeCacheInterfacePtr

◆ Duration

◆ TimePoint

◆ IDuration

◆ CompactFrameID

typedef uint32_t tf2::CompactFrameID

Enumeration Type Documentation

◆ TransformableResult

Enumerator
TransformAvailable 
TransformFailure 

◆ TF2Error

enum tf2::TF2Error : std::uint8_t
strong
Enumerator
NO_ERROR 
LOOKUP_ERROR 
CONNECTIVITY_ERROR 
EXTRAPOLATION_ERROR 
INVALID_ARGUMENT_ERROR 
TIMEOUT_ERROR 
TRANSFORM_ERROR 

Function Documentation

◆ doTransform()

template<class T >
void tf2::doTransform ( const T &  data_in,
T &  data_out,
const geometry_msgs::msg::TransformStamped &  transform 
)

The templated function expected to be able to do a transform.

This is the method which tf2 will use to try to apply a transform for any given datatype.

Parameters
data_inThe data to be transformed.
data_outA reference to the output data. Note this can point to data in and the method should be mutation safe.
transformThe transform to apply to data_in to fill data_out.

This method needs to be implemented by client library developers

◆ getTimestamp() [1/2]

template<class T >
tf2::TimePoint tf2::getTimestamp ( const T &  t)

Get the timestamp from data.

Parameters
tThe data input.
Returns
The timestamp associated with the data.

◆ getFrameId() [1/2]

template<class T >
std::string tf2::getFrameId ( const T &  t)

Get the frame_id from data.

Parameters
tThe data input.
Returns
The frame_id associated with the data.

◆ getTimestamp() [2/2]

template<class P >
tf2::TimePoint tf2::getTimestamp ( const tf2::Stamped< P > &  t)

◆ getFrameId() [2/2]

template<class P >
std::string tf2::getFrameId ( const tf2::Stamped< P > &  t)

◆ toMsg()

template<typename A , typename B >
B tf2::toMsg ( const A &  a)

Function that converts from one type to a ROS message type. It has to be implemented by each data type in tf2_* (except ROS messages) as it is used in the "convert" function.

Parameters
aan object of whatever type
Returns
the conversion as a ROS message

◆ fromMsg()

template<typename A , typename B >
void tf2::fromMsg ( const A &  ,
B &  b 
)

Function that converts from a ROS message type to another type. It has to be implemented by each data type in tf2_* (except ROS messages) as it is used in the "convert" function.

Parameters
aa ROS message to convert from
bthe object to convert to

◆ convert() [1/2]

template<class A , class B >
void tf2::convert ( const A &  a,
B &  b 
)

Function that converts any type to any type (messages or not). Matching toMsg and from Msg conversion functions need to exist. If they don't exist or do not apply (for example, if your two classes are ROS messages), just write a specialization of the function.

Parameters
aan object to convert from
bthe object to convert to

◆ convert() [2/2]

template<class A >
void tf2::convert ( const A &  a1,
A &  a2 
)

◆ operator*() [1/9]

TF2SIMD_FORCE_INLINE Vector3 tf2::operator* ( const Matrix3x3 m,
const Vector3 &  v 
)

◆ operator*() [2/9]

TF2SIMD_FORCE_INLINE Vector3 tf2::operator* ( const Vector3 &  v,
const Matrix3x3 m 
)

◆ operator*() [3/9]

TF2SIMD_FORCE_INLINE Matrix3x3 tf2::operator* ( const Matrix3x3 m1,
const Matrix3x3 m2 
)

◆ operator==() [1/3]

TF2SIMD_FORCE_INLINE bool tf2::operator== ( const Matrix3x3 m1,
const Matrix3x3 m2 
)

Equality operator between two matrices It will test all elements are equal.

◆ ATTRIBUTE_ALIGNED16()

tf2::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.

tf2::Vector3 can be used to represent 3D points and vectors. It has an un-used w component to suit 16-byte alignment when tf2::Vector3 is stored in containers. This extra component can be used by derived classes (Quaternion?) or by user Ideally, this class should be replaced by a platform optimized TF2SIMD version that keeps the data in registers

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 tf2Scalar*() replaces operator[], using implicit conversion. We added operator != and operator == to avoid pointer comparisons.

Set x,y,z and zero w

Parameters
xValue of x
yValue of y
zValue of z

Set the values

Parameters
xValue of x
yValue of y
zValue of z
wValue of w

No initialization constructor

Three argument constructor (zeros w)

Parameters
xValue of x
yValue of y
zValue of z

Initializing constructor

Parameters
xValue of x
yValue of y
zValue of z
wValue of w

Set each element to the max of the current values and the values of another QuadWord

Parameters
otherThe other QuadWord to compare with

Set each element to the min of the current values and the values of another QuadWord

Parameters
otherThe other QuadWord to compare with

No initialization constructor

Constructor from scalars

Parameters
xX value
yY value
zZ value

Add a vector to this one

Parameters
Thevector to add to this one

Sutf2ract a vector from this one

Parameters
Thevector to sutf2ract

Scale the vector

Parameters
sScale factor

Inversely scale the vector

Parameters
sScale factor to divide by

Return the dot product

Parameters
vThe 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

Parameters
wAxisThe axis to rotate about
angleThe angle to rotate by

Return the angle between this and another vector

Parameters
vThe other vector

Return a vector will the absolute values of each element

Return the cross product between this and another vector

Parameters
vThe 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

Parameters
vThe other vector
tThe ration of this to v (t = 0 => return this, t=1 => return other)

Elementwise multiply this vector by the other

Parameters
vThe 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 tf2Scalar*() 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

Parameters
otherThe other Vector3 to compare with

Set each element to the min of the current values and the values of another Vector3

Parameters
otherThe other Vector3 to compare with

No initialization constructor

Constructor from scalars

Parameters
xX value
yY value
zZ value

Add a vector to this one

Parameters
Thevector to add to this one

Sutf2ract a vector from this one

Parameters
Thevector to sutf2ract

Scale the vector

Parameters
sScale factor

Inversely scale the vector

Parameters
sScale factor to divide by

Return the dot product

Parameters
vThe 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

Parameters
wAxisThe axis to rotate about
angleThe angle to rotate by

Return the angle between this and another vector

Parameters
vThe other vector

Return a vector will the absolute values of each element

Return the cross product between this and another vector

Parameters
vThe 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

Parameters
vThe other vector
tThe ration of this to v (t = 0 => return this, t=1 => return other)

Elementwise multiply this vector by the other

Parameters
vThe 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 tf2Scalar*() 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

Parameters
otherThe other Vector3 to compare with

Set each element to the min of the current values and the values of another Vector3

Parameters
otherThe other Vector3 to compare with

◆ operator-() [1/3]

TF2SIMD_FORCE_INLINE Quaternion tf2::operator- ( const Quaternion q)

Return the negative of a quaternion.

◆ operator*() [4/9]

TF2SIMD_FORCE_INLINE Quaternion tf2::operator* ( const Quaternion q1,
const Quaternion q2 
)

Return the product of two quaternions.

◆ operator*() [5/9]

TF2SIMD_FORCE_INLINE Quaternion tf2::operator* ( const Quaternion q,
const Vector3 &  w 
)

◆ operator*() [6/9]

TF2SIMD_FORCE_INLINE Quaternion tf2::operator* ( const Vector3 &  w,
const Quaternion q 
)

◆ dot()

TF2SIMD_FORCE_INLINE tf2Scalar tf2::dot ( const Quaternion q1,
const Quaternion q2 
)

Calculate the dot product between two quaternions.

◆ length()

TF2SIMD_FORCE_INLINE tf2Scalar tf2::length ( const Quaternion q)

Return the length of a quaternion.

◆ angle()

TF2SIMD_FORCE_INLINE tf2Scalar tf2::angle ( const Quaternion q1,
const Quaternion q2 
)

Return the half angle between two quaternions.

◆ angleShortestPath()

TF2SIMD_FORCE_INLINE tf2Scalar tf2::angleShortestPath ( const Quaternion q1,
const Quaternion q2 
)

Return the shortest angle between two quaternions.

◆ inverse()

TF2SIMD_FORCE_INLINE Quaternion tf2::inverse ( const Quaternion q)

Return the inverse of a quaternion.

◆ slerp()

TF2SIMD_FORCE_INLINE Quaternion tf2::slerp ( const Quaternion q1,
const Quaternion q2,
const tf2Scalar t 
)

Return the result of spherical linear interpolation betwen two quaternions.

Parameters
q1The first quaternion
q2The second quaternion
tThe ration between q1 and q2. t = 0 return q1, t=1 returns q2 Slerp assumes constant velocity between positions.

◆ quatRotate()

TF2SIMD_FORCE_INLINE Vector3 tf2::quatRotate ( const Quaternion rotation,
const Vector3 &  v 
)

◆ shortestArcQuat()

TF2SIMD_FORCE_INLINE Quaternion tf2::shortestArcQuat ( const Vector3 &  v0,
const Vector3 &  v1 
)

◆ shortestArcQuatNormalize2()

TF2SIMD_FORCE_INLINE Quaternion tf2::shortestArcQuatNormalize2 ( Vector3 &  v0,
Vector3 &  v1 
)

◆ operator==() [2/3]

TF2SIMD_FORCE_INLINE bool tf2::operator== ( const Transform t1,
const Transform t2 
)

Test if two transforms have all elements equal.

◆ operator+()

TF2SIMD_FORCE_INLINE Vector3 tf2::operator+ ( const Vector3 &  v1,
const Vector3 &  v2 
)

Return the sum of two vectors (Point symantics)

◆ operator*() [7/9]

TF2SIMD_FORCE_INLINE Vector3 tf2::operator* ( const Vector3 &  v1,
const Vector3 &  v2 
)

Return the elementwise product of two vectors.

◆ operator-() [2/3]

TF2SIMD_FORCE_INLINE Vector3 tf2::operator- ( const Vector3 &  v1,
const Vector3 &  v2 
)

Return the difference between two vectors.

◆ operator-() [3/3]

TF2SIMD_FORCE_INLINE Vector3 tf2::operator- ( const Vector3 &  v)

Return the negative of the vector.

◆ operator*() [8/9]

TF2SIMD_FORCE_INLINE Vector3 tf2::operator* ( const Vector3 &  v,
const tf2Scalar s 
)

Return the vector scaled by s.

◆ operator*() [9/9]

TF2SIMD_FORCE_INLINE Vector3 tf2::operator* ( const tf2Scalar s,
const Vector3 &  v 
)

Return the vector scaled by s.

◆ operator/() [1/2]

TF2SIMD_FORCE_INLINE Vector3 tf2::operator/ ( const Vector3 &  v,
const tf2Scalar s 
)

Return the vector inversely scaled by s.

◆ operator/() [2/2]

TF2SIMD_FORCE_INLINE Vector3 tf2::operator/ ( const Vector3 &  v1,
const Vector3 &  v2 
)

Return the vector inversely scaled by s.

◆ tf2Dot()

TF2SIMD_FORCE_INLINE tf2Scalar tf2::tf2Dot ( const Vector3 &  v1,
const Vector3 &  v2 
)

Return the dot product between two vectors.

◆ tf2Distance2()

TF2SIMD_FORCE_INLINE tf2Scalar tf2::tf2Distance2 ( const Vector3 &  v1,
const Vector3 &  v2 
)

Return the distance squared between two vectors.

◆ tf2Distance()

TF2SIMD_FORCE_INLINE tf2Scalar tf2::tf2Distance ( const Vector3 &  v1,
const Vector3 &  v2 
)

Return the distance between two vectors.

◆ tf2Angle()

TF2SIMD_FORCE_INLINE tf2Scalar tf2::tf2Angle ( const Vector3 &  v1,
const Vector3 &  v2 
)

Return the angle between two vectors.

◆ tf2Cross()

TF2SIMD_FORCE_INLINE Vector3 tf2::tf2Cross ( const Vector3 &  v1,
const Vector3 &  v2 
)

Return the cross product of two vectors.

◆ tf2Triple()

TF2SIMD_FORCE_INLINE tf2Scalar tf2::tf2Triple ( const Vector3 &  v1,
const Vector3 &  v2,
const Vector3 &  v3 
)

◆ lerp()

TF2SIMD_FORCE_INLINE Vector3 tf2::lerp ( const Vector3 &  v1,
const Vector3 &  v2,
const tf2Scalar t 
)

Return the linear interpolation between two vectors.

Parameters
v1One vector
v2The other vector
tThe ration of this to v (t = 0 => return v1, t=1 => return v2)

◆ tf2SwapScalarEndian()

TF2SIMD_FORCE_INLINE void tf2::tf2SwapScalarEndian ( const tf2Scalar sourceVal,
tf2Scalar destVal 
)

tf2SwapVector3Endian swaps vector endianness, useful for network and cross-platform serialization

◆ tf2SwapVector3Endian()

TF2SIMD_FORCE_INLINE void tf2::tf2SwapVector3Endian ( const Vector3 &  sourceVec,
Vector3 &  destVec 
)

tf2SwapVector3Endian swaps vector endianness, useful for network and cross-platform serialization

◆ tf2UnSwapVector3Endian()

TF2SIMD_FORCE_INLINE void tf2::tf2UnSwapVector3Endian ( Vector3 &  vector)

tf2UnSwapVector3Endian swaps vector endianness, useful for network and cross-platform serialization

◆ tf2PlaneSpace1()

TF2SIMD_FORCE_INLINE void tf2::tf2PlaneSpace1 ( const Vector3 &  n,
Vector3 &  p,
Vector3 &  q 
)

◆ get_now()

TimePoint tf2::get_now ( )
inline

◆ durationFromSec()

Duration tf2::durationFromSec ( double  t_sec)
inline

◆ timeFromSec()

TimePoint tf2::timeFromSec ( double  t_sec)
inline

◆ durationToSec()

double tf2::durationToSec ( const tf2::Duration input)
inline

◆ timeToSec()

double tf2::timeToSec ( const TimePoint timepoint)
inline

◆ displayTimePoint()

std::string tf2::displayTimePoint ( const TimePoint stamp)

◆ operator==() [3/3]

template<typename T >
bool tf2::operator== ( const Stamped< T > &  a,
const Stamped< T > &  b 
)

Comparison Operator for Stamped datatypes.

◆ getEulerYPR()

template<class A >
void tf2::getEulerYPR ( const A &  a,
double &  yaw,
double &  pitch,
double &  roll 
)

Return the yaw, pitch, roll of anything that can be converted to a tf2::Quaternion The conventions are the usual ROS ones defined in tf2/LineMath/Matrix3x3.h

Parameters
athe object to get data from (it represents a rotation/quaternion)
yawyaw
pitchpitch
rollroll

◆ getYaw()

template<class A >
double tf2::getYaw ( const A &  a)

Return the yaw of anything that can be converted to a tf2::Quaternion The conventions are the usual ROS ones defined in tf2/LineMath/Matrix3x3.h This function is a specialization of getEulerYPR and is useful for its wide-spread use in navigation

Parameters
athe object to get data from (it represents a rotation/quaternion)
yawyaw

◆ getTransformIdentity()

template<class A >
A tf2::getTransformIdentity ( )

Return the identity for any type that can be converted to a tf2::Transform

Returns
an object of class A that is an identity transform

Variable Documentation

◆ TIMECACHE_DEFAULT_MAX_STORAGE_TIME

constexpr tf2::Duration tf2::TIMECACHE_DEFAULT_MAX_STORAGE_TIME = std::chrono::seconds(10)
constexpr

default value of 10 seconds storage