|
Autoware.Auto
|
|
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... | |
|
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
| t_in | The point to transform, as a Point32 message. |
| t_out | The transformed point, as a Point32 message. |
| transform | The timestamped transform to apply, as a TransformStamped message. |
|
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
| t_in | The Quaternion32 message to transform. |
| t_out | The transformed Quaternion32 message. |
| transform | The timestamped transform to apply, as a TransformStamped message. |
|
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
| t_in | The BoundingBox message to transform. |
| t_out | The transformed BoundingBox message. |
| transform | The timestamped transform to apply, as a TransformStamped message. |
|
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.
| t_in | The BoundingBoxArray to transform, as a timestamped BoundingBoxArray message. |
| t_out | The transformed BoundingBoxArray, as a timestamped BoundingBoxArray message. |
| transform | The timestamped transform to apply, as a TransformStamped message. |
|
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.
| t | A timestamped BoundingBoxArray message to extract the frame ID from. |
|
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
| t | A timestamped BoundingBoxArray message to extract the timestamp from. |