|
Autoware.Auto
|
|
Functions | |
| template<typename PoseT , typename TransformT > | |
| void | pose_to_transform (const PoseT &pose, TransformT &transform) |
| template<typename PoseT , typename TransformT > | |
| void | transform_to_pose (const TransformT &transform, PoseT &pose) |
| template<typename T > | |
| void | pose_to_transform (const EigenPose< T > &pose, EigenTransform< T > &transform) |
| template<typename T > | |
| void | pose_to_transform (const EigenPose< T > &pose, RosTransform &transform) |
| template<typename T > | |
| void | pose_to_transform (const EigenPose< T > &pose, RosPose &ros_pose) |
| template<typename T > | |
| void | transform_to_pose (const RosTransform &transform, EigenPose< T > &pose) |
| template<typename T > | |
| void | transform_to_pose (const RosPose &ros_pose, EigenPose< T > &pose) |
| void autoware::localization::ndt::transform_adapters::pose_to_transform | ( | const EigenPose< T > & | pose, |
| EigenTransform< T > & | transform | ||
| ) |
| void autoware::localization::ndt::transform_adapters::pose_to_transform | ( | const EigenPose< T > & | pose, |
| RosPose & | ros_pose | ||
| ) |
Specialization to convert from the eigen pose to the ros pose type. pose_to_transform template is used as conversion to RosPose is identical to conversion to RosTransform
| T | Eigen scalar type |
| void autoware::localization::ndt::transform_adapters::pose_to_transform | ( | const EigenPose< T > & | pose, |
| RosTransform & | transform | ||
| ) |
Specialization to convert from the eigen pose to the ros transform type.
| T | Eigen scalar type |
| void autoware::localization::ndt::transform_adapters::pose_to_transform | ( | const PoseT & | pose, |
| TransformT & | transform | ||
| ) |
Template function to convert a 6D pose to a transformation matrix. This function should be specialized and implemented for the supported types.
| PoseT | Pose type. |
| TransformT | Transform type. |
| [in] | pose | pose to convert |
| [out] | transform | resulting transform |
| void autoware::localization::ndt::transform_adapters::transform_to_pose | ( | const RosPose & | ros_pose, |
| EigenPose< T > & | pose | ||
| ) |
Specialization to convert from the ros pose type to an eigen one. transform_to_pose template is used as conversion from RosPose is identical to conversion from RosTransform
| T | Eigen scalar type |
| void autoware::localization::ndt::transform_adapters::transform_to_pose | ( | const RosTransform & | transform, |
| EigenPose< T > & | pose | ||
| ) |
Specialization to convert from the ros pose type to an eigen one.
| T | Eigen scalar type |
| void autoware::localization::ndt::transform_adapters::transform_to_pose | ( | const TransformT & | transform, |
| PoseT & | pose | ||
| ) |
Template function to convert a 6D pose to a transformation matrix. This function should be specialized and implemented for the supported types.
| PoseT | Pose type. |
| TransformT | Transform type. |
| [in] | transform | resulting transform |
| [out] | pose | pose to convert |