This struct specifies the interface requirements of MapT
given MapMsgT
parameter of a relative localizer node instantiation. 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 = MapConstraint<T1, T2>
or simply instantiate it anywhere in the code as MapConstraint<T1, T2> constraint{};
More...
#include <constraints.hpp>
|
template<typename Map > |
using | call_set = decltype(std::declval< Map >().set(std::declval< const MapMsgT & >())) |
| This expression requires a method that sets the map for a given message that contains the data. More...
|
|
template<typename Map > |
using | call_frame_id = decltype(std::declval< Map >().frame_id()) |
| This expression requires a method that returns a const reference to the frame ID of the map. More...
|
|
template<typename Map > |
using | call_valid = decltype(std::declval< Map >().valid()) |
| This expression requires a method that returns the validity of the map. More...
|
|
template<typename MapT, typename MapMsgT>
struct autoware::localization::localization_nodes::traits::MapConstraint< MapT, MapMsgT >
This struct specifies the interface requirements of MapT
given MapMsgT
parameter of a relative localizer node instantiation. 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 = MapConstraint<T1, T2>
or simply instantiate it anywhere in the code as MapConstraint<T1, T2> constraint{};
- Template Parameters
-
MapT | Localization map type. |
MapMsgT | Serialized map message type. |
◆ call_frame_id
template<typename MapT , typename MapMsgT >
template<typename Map >
This expression requires a method that returns a const reference to the frame ID of the map.
- Returns
- Map frame ID.
◆ call_set
template<typename MapT , typename MapMsgT >
template<typename Map >
This expression requires a method that sets the map for a given message that contains the data.
- Parameters
-
[in] | msg | Message instance containing the map data. |
◆ call_valid
template<typename MapT , typename MapMsgT >
template<typename Map >
This expression requires a method that returns the validity of the map.
- Returns
- True if the map is valid and usable.
◆ value
template<typename MapT , typename MapMsgT >
The documentation for this struct was generated from the following file: