This struct specifies the interface requirements of LocalizerT
, given the InputT
, MapT
and SummaryT
parameters of a relative localizer node. Please refer to the documentation of the expressions within the constraint to understand the API requirements better. The constraint expresses the constraints as static assertions, hence if the constraint is not satisfied, the compilation will not succeed. To be able to use the constraint, either include in the list of template parameters via the Requires
keyword as: Requires = LocalizerConstraint<T1, T2, T3>
or simply instantiate it anywhere in the code as LocalizerConstraint<T1, T2, T3> constraint{};
More...
#include <constraints.hpp>
|
template<typename Localizer > |
using | call_register = decltype(std::declval< Localizer >().register_measurement(std::declval< InputT >(), std::declval< geometry_msgs::msg::TransformStamped >(), std::declval< MapT >(), std::declval< SummaryT *const >())) |
| This expression requires a method that registers a measurement to the current map and returns the estimated pose of the vehicle and its validity. More...
|
|
template<typename LocalizerT, typename InputT, typename MapT, typename SummaryT = localization_common::OptimizedRegistrationSummary>
struct autoware::localization::localization_nodes::traits::LocalizerConstraint< LocalizerT, InputT, MapT, SummaryT >
This struct specifies the interface requirements of LocalizerT
, given the InputT
, MapT
and SummaryT
parameters of a relative localizer node. Please refer to the documentation of the expressions within the constraint to understand the API requirements better. The constraint expresses the constraints as static assertions, hence if the constraint is not satisfied, the compilation will not succeed. To be able to use the constraint, either include in the list of template parameters via the Requires
keyword as: Requires = LocalizerConstraint<T1, T2, T3>
or simply instantiate it anywhere in the code as LocalizerConstraint<T1, T2, T3> constraint{};
- Template Parameters
-
LocalizerT | |
InputT | |
MapT | |
SummaryT | |
◆ call_register
template<typename LocalizerT , typename InputT , typename MapT , typename SummaryT = localization_common::OptimizedRegistrationSummary>
template<typename Localizer >
This expression requires a method that registers a measurement to the current map and returns the estimated pose of the vehicle and its validity.
- Parameters
-
[in] | msg | Measurement message to register. |
[in] | transform_initial | Initial guess of the pose to initialize the localizer with in iterative processes like solving optimization problems. |
[in] | map | Map to register. |
[out] | summary | Raw pointer to the registration summary for optional summary filling. |
- Returns
- Pose estimate after registration.
◆ value
template<typename LocalizerT , typename InputT , typename MapT , typename SummaryT >
The documentation for this struct was generated from the following file: