Autoware.Auto
tf2 Namespace Reference

Functions

template<>
void doTransform (const geometry_msgs::msg::Point32 &t_in, geometry_msgs::msg::Point32 &t_out, const geometry_msgs::msg::TransformStamped &transform)
 Apply a geometry_msgs TransformStamped to an geometry_msgs Point32 type. This function is a specialization of the doTransform template defined in tf2/convert.h. More...
 
template<>
void doTransform (const autoware_auto_msgs::msg::Quaternion32 &t_in, autoware_auto_msgs::msg::Quaternion32 &t_out, const geometry_msgs::msg::TransformStamped &transform)
 Apply a geometry_msgs TransformStamped to an autoware_auto_msgs Quaternion32 type. This function is a specialization of the doTransform template defined in tf2/convert.h. More...
 
template<>
void doTransform (const BoundingBox &t_in, BoundingBox &t_out, const geometry_msgs::msg::TransformStamped &transform)
 Apply a geometry_msgs TransformStamped to an autoware_auto_msgs BoundingBox type. This function is a specialization of the doTransform template defined in tf2/convert.h. More...
 
template<>
tf2::TimePoint getTimestamp (const BoundingBoxArray &t)
 Extract a timestamp from the header of a BoundingBoxArray message. This function is a specialization of the getTimestamp template defined in tf2/convert.h. More...
 
template<>
std::string getFrameId (const BoundingBoxArray &t)
 Extract a frame ID from the header of a BoundingBoxArray message. This function is a specialization of the getFrameId template defined in tf2/convert.h. More...
 
template<>
void doTransform (const BoundingBoxArray &t_in, BoundingBoxArray &t_out, const geometry_msgs::msg::TransformStamped &transform)
 Apply a geometry_msgs TransformStamped to an autoware_auto_msgs BoundingBoxArray type. This function is a specialization of the doTransform template defined in tf2/convert.h. More...
 

Function Documentation

◆ doTransform() [1/4]

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

Apply a geometry_msgs TransformStamped to an autoware_auto_msgs Quaternion32 type. This function is a specialization of the doTransform template defined in tf2/convert.h.

Quaternion32

Parameters
t_inThe Quaternion32 message to transform.
t_outThe transformed Quaternion32 message.
transformThe timestamped transform to apply, as a TransformStamped message.

◆ doTransform() [2/4]

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

Apply a geometry_msgs TransformStamped to an autoware_auto_msgs BoundingBox type. This function is a specialization of the doTransform template defined in tf2/convert.h.

BoundingBox

Parameters
t_inThe BoundingBox message to transform.
t_outThe transformed BoundingBox message.
transformThe timestamped transform to apply, as a TransformStamped message.

◆ doTransform() [3/4]

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

Apply a geometry_msgs TransformStamped to an autoware_auto_msgs BoundingBoxArray type. This function is a specialization of the doTransform template defined in tf2/convert.h.

Parameters
t_inThe BoundingBoxArray to transform, as a timestamped BoundingBoxArray message.
t_outThe transformed BoundingBoxArray, as a timestamped BoundingBoxArray message.
transformThe timestamped transform to apply, as a TransformStamped message.

◆ doTransform() [4/4]

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

Apply a geometry_msgs TransformStamped to an geometry_msgs Point32 type. This function is a specialization of the doTransform template defined in tf2/convert.h.

Point32

Parameters
t_inThe point to transform, as a Point32 message.
t_outThe transformed point, as a Point32 message.
transformThe timestamped transform to apply, as a TransformStamped message.

◆ getFrameId()

template<>
std::string tf2::getFrameId ( const BoundingBoxArray t)
inline

Extract a frame ID from the header of a BoundingBoxArray message. This function is a specialization of the getFrameId template defined in tf2/convert.h.

Parameters
tA timestamped BoundingBoxArray message to extract the frame ID from.
Returns
A string containing the frame ID of the message.

◆ getTimestamp()

template<>
tf2::TimePoint tf2::getTimestamp ( const BoundingBoxArray t)
inline

Extract a timestamp from the header of a BoundingBoxArray message. This function is a specialization of the getTimestamp template defined in tf2/convert.h.

BoundingBoxArray

Parameters
tA timestamped BoundingBoxArray message to extract the timestamp from.
Returns
The timestamp of the message.