Go to the documentation of this file.
17 #ifndef LOCALIZATION_NODES__CONSTRAINTS_HPP_
18 #define LOCALIZATION_NODES__CONSTRAINTS_HPP_
22 #include <type_traits>
27 namespace localization
29 namespace localization_nodes
48 template<
typename MapT,
typename MapMsgT>
54 template<
typename Map>
55 using call_set = decltype(std::declval<Map>().set(std::declval<const MapMsgT &>()));
60 template<
typename Map>
65 template<
typename Map>
66 using call_valid = decltype(std::declval<Map>().valid());
70 "The map should provide a `set(msg)` method");
73 const std::string &>::
value,
74 "The map should provide a `frame_id()` method");
77 "The map should provide a `valid(msg)` method");
93 template<
typename LocalizerT,
typename InputT,
typename MapT,
105 template<
typename Localizer>
106 using call_register = decltype(std::declval<Localizer>().register_measurement(
107 std::declval<InputT>(),
108 std::declval<geometry_msgs::msg::TransformStamped>(),
109 std::declval<MapT>(),
110 std::declval<SummaryT * const>())
116 "The localizer should provide a valid `register_measurement(...)` method.");
120 template<
typename MapT,
typename MapMsgT>
122 template<
typename LocalizerT,
typename InputT,
typename MapT,
typename SummaryT>
128 #endif // LOCALIZATION_NODES__CONSTRAINTS_HPP_
This struct specifies the interface requirements of MapT given MapMsgT parameter of a relative locali...
Definition: localization_nodes/include/localization_nodes/constraints.hpp:49
Definition: template_utils.hpp:51
Requires
Helper class for concepts-like API.
Definition: localization_nodes/include/localization_nodes/constraints.hpp:32
This struct specifies the interface requirements of LocalizerT, given the InputT, MapT and SummaryT p...
Definition: localization_nodes/include/localization_nodes/constraints.hpp:95
Definition: optimized_registration_summary.hpp:32
decltype(std::declval< Map >().valid()) call_valid
This expression requires a method that returns the validity of the map.
Definition: localization_nodes/include/localization_nodes/constraints.hpp:66
decltype(std::declval< Localizer >().register_measurement(std::declval< InputT >(), std::declval< geometry_msgs::msg::TransformStamped >(), std::declval< MapT >(), std::declval< SummaryT *const >())) call_register
This expression requires a method that registers a measurement to the current map and returns the est...
Definition: localization_nodes/include/localization_nodes/constraints.hpp:111
static constexpr Requires value
Definition: localization_nodes/include/localization_nodes/constraints.hpp:78
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
Definition: template_utils.hpp:34
decltype(std::declval< Map >().set(std::declval< const MapMsgT & >())) call_set
This expression requires a method that sets the map for a given message that contains the data.
Definition: localization_nodes/include/localization_nodes/constraints.hpp:55
decltype(std::declval< Map >().frame_id()) call_frame_id
This expression requires a method that returns a const reference to the frame ID of the map.
Definition: localization_nodes/include/localization_nodes/constraints.hpp:61
static constexpr Requires value
Definition: localization_nodes/include/localization_nodes/constraints.hpp:117