Autoware.Auto
autoware::localization::localization_common::RelativeLocalizerBase< InputMsgT, MapMsgT, RegistrationSummaryT > Class Template Referenceabstract

#include <localizer_base.hpp>

Public Types

using PoseWithCovarianceStamped = geometry_msgs::msg::PoseWithCovarianceStamped
 
using Transform = geometry_msgs::msg::TransformStamped
 
using RegistrationSummary = RegistrationSummaryT
 
using InputMsg = InputMsgT
 
using MapMsg = MapMsgT
 

Public Member Functions

RegistrationSummaryT register_measurement (const InputMsgT &msg, const Transform &transform_initial, PoseWithCovarianceStamped &pose_out)
 
void set_map (const MapMsgT &msg)
 
void insert_to_map (const MapMsgT &msg)
 
virtual const std::string & map_frame_id () const noexcept=0
 Get the frame id of the current map. More...
 
virtual std::chrono::system_clock::time_point map_stamp () const noexcept=0
 Get the timestamp of the current map. More...
 
bool map_valid () const noexcept
 
RelativeLocalizerBaseoperator= (RelativeLocalizerBase &&other)=delete
 
virtual ~RelativeLocalizerBase ()=default
 

Protected Member Functions

virtual void set_map_impl (const MapMsgT &msg)=0
 set_map implementation. More...
 
virtual void insert_to_map_impl (const MapMsgT &)
 insert_to_map implementation. More...
 
virtual void on_bad_map (std::exception_ptr eptr)
 Action to take on failure to set a new map. More...
 
virtual void on_bad_map_insertion (std::exception_ptr eptr)
 Action to take on failure to insert to the map. More...
 
virtual RegistrationSummaryT register_measurement_impl (const InputMsgT &msg, const Transform &transform_initial, PoseWithCovarianceStamped &pose_out)=0
 register_measurement(...) implementation. More...
 
void set_map_valid () noexcept
 Set current map as valid. More...
 
void set_map_invalid () noexcept
 Set current map as invalid. More...
 
virtual void on_register_without_map ()
 Action to take when a measurement is attempted to be set without a valid map. More...
 

Detailed Description

template<typename InputMsgT, typename MapMsgT, typename RegistrationSummaryT>
class autoware::localization::localization_common::RelativeLocalizerBase< InputMsgT, MapMsgT, RegistrationSummaryT >

The base class for relative localizers.

Template Parameters
InputMsgTMessage type that will be registered against a map.
MapMsgTMap type.
RegistrationSummaryTStruct that contains the registration summary.

Member Typedef Documentation

◆ InputMsg

template<typename InputMsgT , typename MapMsgT , typename RegistrationSummaryT >
using autoware::localization::localization_common::RelativeLocalizerBase< InputMsgT, MapMsgT, RegistrationSummaryT >::InputMsg = InputMsgT

◆ MapMsg

template<typename InputMsgT , typename MapMsgT , typename RegistrationSummaryT >
using autoware::localization::localization_common::RelativeLocalizerBase< InputMsgT, MapMsgT, RegistrationSummaryT >::MapMsg = MapMsgT

◆ PoseWithCovarianceStamped

template<typename InputMsgT , typename MapMsgT , typename RegistrationSummaryT >
using autoware::localization::localization_common::RelativeLocalizerBase< InputMsgT, MapMsgT, RegistrationSummaryT >::PoseWithCovarianceStamped = geometry_msgs::msg::PoseWithCovarianceStamped

◆ RegistrationSummary

template<typename InputMsgT , typename MapMsgT , typename RegistrationSummaryT >
using autoware::localization::localization_common::RelativeLocalizerBase< InputMsgT, MapMsgT, RegistrationSummaryT >::RegistrationSummary = RegistrationSummaryT

◆ Transform

template<typename InputMsgT , typename MapMsgT , typename RegistrationSummaryT >
using autoware::localization::localization_common::RelativeLocalizerBase< InputMsgT, MapMsgT, RegistrationSummaryT >::Transform = geometry_msgs::msg::TransformStamped

Constructor & Destructor Documentation

◆ ~RelativeLocalizerBase()

template<typename InputMsgT , typename MapMsgT , typename RegistrationSummaryT >
virtual autoware::localization::localization_common::RelativeLocalizerBase< InputMsgT, MapMsgT, RegistrationSummaryT >::~RelativeLocalizerBase ( )
virtualdefault

Member Function Documentation

◆ insert_to_map()

template<typename InputMsgT , typename MapMsgT , typename RegistrationSummaryT >
void autoware::localization::localization_common::RelativeLocalizerBase< InputMsgT, MapMsgT, RegistrationSummaryT >::insert_to_map ( const MapMsgT &  msg)
inline

Insert an increment to the map.

Parameters
msgData to insert to the map.

◆ insert_to_map_impl()

◆ map_frame_id()

◆ map_stamp()

◆ map_valid()

template<typename InputMsgT , typename MapMsgT , typename RegistrationSummaryT >
bool autoware::localization::localization_common::RelativeLocalizerBase< InputMsgT, MapMsgT, RegistrationSummaryT >::map_valid ( ) const
inlinenoexcept

◆ on_bad_map()

template<typename InputMsgT , typename MapMsgT , typename RegistrationSummaryT >
virtual void autoware::localization::localization_common::RelativeLocalizerBase< InputMsgT, MapMsgT, RegistrationSummaryT >::on_bad_map ( std::exception_ptr  eptr)
inlineprotectedvirtual

Action to take on failure to set a new map.

◆ on_bad_map_insertion()

template<typename InputMsgT , typename MapMsgT , typename RegistrationSummaryT >
virtual void autoware::localization::localization_common::RelativeLocalizerBase< InputMsgT, MapMsgT, RegistrationSummaryT >::on_bad_map_insertion ( std::exception_ptr  eptr)
inlineprotectedvirtual

Action to take on failure to insert to the map.

◆ on_register_without_map()

template<typename InputMsgT , typename MapMsgT , typename RegistrationSummaryT >
virtual void autoware::localization::localization_common::RelativeLocalizerBase< InputMsgT, MapMsgT, RegistrationSummaryT >::on_register_without_map ( )
inlineprotectedvirtual

Action to take when a measurement is attempted to be set without a valid map.

◆ operator=()

template<typename InputMsgT , typename MapMsgT , typename RegistrationSummaryT >
RelativeLocalizerBase& autoware::localization::localization_common::RelativeLocalizerBase< InputMsgT, MapMsgT, RegistrationSummaryT >::operator= ( RelativeLocalizerBase< InputMsgT, MapMsgT, RegistrationSummaryT > &&  other)
delete

◆ register_measurement()

template<typename InputMsgT , typename MapMsgT , typename RegistrationSummaryT >
RegistrationSummaryT autoware::localization::localization_common::RelativeLocalizerBase< InputMsgT, MapMsgT, RegistrationSummaryT >::register_measurement ( const InputMsgT &  msg,
const Transform transform_initial,
PoseWithCovarianceStamped pose_out 
)
inline

Registers a measurement to the current map and returns the estimated pose of the vehicle and its validity.

Parameters
[in]msgMeasurement message to register.
[in]transform_initialInitial guess of the pose to initialize the localizer with in iterative processes like solving optimization problems.
[out]pose_outReference to the resulting pose estimate after registration.
Returns
Registration summary. This is implementation defined.
Exceptions
Ifthe result is invalid and cannot be used. Defined in the implementation.

◆ register_measurement_impl()

◆ set_map()

template<typename InputMsgT , typename MapMsgT , typename RegistrationSummaryT >
void autoware::localization::localization_common::RelativeLocalizerBase< InputMsgT, MapMsgT, RegistrationSummaryT >::set_map ( const MapMsgT &  msg)
inline

Set map.

Parameters
msgMap message.

◆ set_map_impl()

◆ set_map_invalid()

template<typename InputMsgT , typename MapMsgT , typename RegistrationSummaryT >
void autoware::localization::localization_common::RelativeLocalizerBase< InputMsgT, MapMsgT, RegistrationSummaryT >::set_map_invalid ( )
inlineprotectednoexcept

Set current map as invalid.

◆ set_map_valid()

template<typename InputMsgT , typename MapMsgT , typename RegistrationSummaryT >
void autoware::localization::localization_common::RelativeLocalizerBase< InputMsgT, MapMsgT, RegistrationSummaryT >::set_map_valid ( )
inlineprotectednoexcept

Set current map as valid.


The documentation for this class was generated from the following file: