Autoware.Auto
autoware::localization::ndt::transform_adapters Namespace Reference

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)
 

Function Documentation

◆ pose_to_transform() [1/4]

template<typename T >
void autoware::localization::ndt::transform_adapters::pose_to_transform ( const EigenPose< T > &  pose,
EigenTransform< T > &  transform 
)

◆ pose_to_transform() [2/4]

template<typename T >
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

Template Parameters
TEigen scalar type

◆ pose_to_transform() [3/4]

template<typename T >
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.

Template Parameters
TEigen scalar type

◆ pose_to_transform() [4/4]

template<typename PoseT , typename TransformT >
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.

Template Parameters
PoseTPose type.
TransformTTransform type.
Parameters
[in]posepose to convert
[out]transformresulting transform

◆ transform_to_pose() [1/3]

template<typename T >
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

Template Parameters
TEigen scalar type

◆ transform_to_pose() [2/3]

template<typename T >
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.

Template Parameters
TEigen scalar type

◆ transform_to_pose() [3/3]

template<typename PoseT , typename TransformT >
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.

Template Parameters
PoseTPose type.
TransformTTransform type.
Parameters
[in]transformresulting transform
[out]posepose to convert