tf2_bullet  master
Bullet binding for tf2.
Namespaces | Classes | Typedefs | Enumerations | Functions | Variables
tf2 Namespace Reference

Namespaces

 impl
 

Classes

class  BufferCore
 
class  BufferCoreInterface
 
class  ConnectivityException
 
class  ExtrapolationException
 
class  InvalidArgumentException
 
class  LookupException
 
class  Matrix3x3
 
struct  Matrix3x3DoubleData
 
struct  Matrix3x3FloatData
 
class  Quaternion
 
class  Stamped
 
class  StaticCache
 
class  tf2Vector4
 
class  TimeCache
 
class  TimeCacheInterface
 
class  TimeoutException
 
class  Transform
 
struct  TransformDoubleData
 
class  TransformException
 
struct  TransformFloatData
 
class  TransformStorage
 
struct  Vector3DoubleData
 
struct  Vector3FloatData
 

Typedefs

typedef std::pair< TimePoint, CompactFrameIDP_TimeAndFrameID
 
typedef uint32_t TransformableCallbackHandle
 
typedef uint64_t TransformableRequestHandle
 
typedef std::shared_ptr< TimeCacheInterfaceTimeCacheInterfacePtr
 
typedef std::chrono::nanoseconds Duration
 
typedef std::chrono::time_point< std::chrono::system_clock, DurationTimePoint
 
typedef std::chrono::duration< int, std::nanoIDuration
 
typedef uint32_t CompactFrameID
 

Enumerations

enum  TransformableResult
 
enum  TF2Error {
  TF2Error::NO_ERROR, TF2Error::LOOKUP_ERROR, TF2Error::CONNECTIVITY_ERROR, TF2Error::EXTRAPOLATION_ERROR,
  TF2Error::INVALID_ARGUMENT_ERROR, TF2Error::TIMEOUT_ERROR, TF2Error::TRANSFORM_ERROR
}
 

Functions

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)
 
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)
 
getTransformIdentity ()
 
btTransform transformToBullet (const geometry_msgs::msg::TransformStamped &t)
 Convert a timestamped transform to the equivalent Bullet data type. More...
 
template<>
void doTransform (const tf2::Stamped< btVector3 > &t_in, tf2::Stamped< btVector3 > &t_out, const geometry_msgs::msg::TransformStamped &transform)
 Apply a geometry_msgs TransformStamped to a Bullet-specific Vector3 type. This function is a specialization of the doTransform template defined in tf2/convert.h. More...
 
geometry_msgs::msg::PointStamped toMsg (const tf2::Stamped< btVector3 > &in)
 Convert a stamped Bullet Vector3 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< btVector3 > &out)
 Convert a PointStamped message type to a stamped Bullet-specific Vector3 type. This function is a specialization of the fromMsg template defined in tf2/convert.h. More...
 
template<>
void doTransform (const tf2::Stamped< btTransform > &t_in, tf2::Stamped< btTransform > &t_out, const geometry_msgs::msg::TransformStamped &transform)
 Apply a geometry_msgs TransformStamped to a Bullet-specific Transform data type. This function is a specialization of the doTransform template defined in tf2/convert.h. More...
 

Variables

 TransformAvailable
 
 TransformFailure
 
constexpr tf2::Duration TIMECACHE_DEFAULT_MAX_STORAGE_TIME
 

Detailed Description

Author
Wim Meeussen

Function Documentation

◆ transformToBullet()

btTransform tf2::transformToBullet ( const geometry_msgs::msg::TransformStamped &  t)
inline

Convert a timestamped transform to the equivalent Bullet data type.

Parameters
tThe transform to convert, as a geometry_msgs TransformedStamped message.
Returns
The transform message converted to a Bullet btTransform.

◆ doTransform() [1/2]

template<>
void tf2::doTransform ( const tf2::Stamped< btVector3 > &  t_in,
tf2::Stamped< btVector3 > &  t_out,
const geometry_msgs::msg::TransformStamped &  transform 
)
inline

Apply a geometry_msgs TransformStamped to a Bullet-specific Vector3 type. This function is a specialization of the doTransform template defined in tf2/convert.h.

Parameters
t_inThe vector to transform, as a timestamped Bullet btVector3 data type.
t_outThe transformed vector, as a timestamped Bullet btVector3 data type.
transformThe timestamped transform to apply, as a TransformStamped message.

◆ toMsg()

geometry_msgs::msg::PointStamped tf2::toMsg ( const tf2::Stamped< btVector3 > &  in)
inline

Convert a stamped Bullet Vector3 type to a PointStamped message. This function is a specialization of the toMsg template defined in tf2/convert.h.

Parameters
inThe timestamped Bullet btVector3 to convert.
Returns
The vector converted to a PointStamped message.

◆ fromMsg()

void tf2::fromMsg ( const geometry_msgs::msg::PointStamped &  msg,
tf2::Stamped< btVector3 > &  out 
)
inline

Convert a PointStamped message type to a stamped Bullet-specific Vector3 type. This function is a specialization of the fromMsg template defined in tf2/convert.h.

Parameters
msgThe PointStamped message to convert.
outThe point converted to a timestamped Bullet Vector3.

◆ doTransform() [2/2]

template<>
void tf2::doTransform ( const tf2::Stamped< btTransform > &  t_in,
tf2::Stamped< btTransform > &  t_out,
const geometry_msgs::msg::TransformStamped &  transform 
)
inline

Apply a geometry_msgs TransformStamped to a Bullet-specific Transform data type. This function is a specialization of the doTransform template defined in tf2/convert.h.

Parameters
t_inThe frame to transform, as a timestamped Bullet btTransform.
t_outThe transformed frame, as a timestamped Bullet btTransform.
transformThe timestamped transform to apply, as a TransformStamped message.