Autoware.Auto
localization_nodes/include/localization_nodes/constraints.hpp
Go to the documentation of this file.
1 // Copyright 2021 Apex.AI, Inc.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 //    http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 //
15 // Co-developed by Tier IV, Inc. and Apex.AI, Inc.
16 
17 #ifndef LOCALIZATION_NODES__CONSTRAINTS_HPP_
18 #define LOCALIZATION_NODES__CONSTRAINTS_HPP_
19 
22 #include <type_traits>
23 #include <string>
24 
25 namespace autoware
26 {
27 namespace localization
28 {
29 namespace localization_nodes
30 {
32 enum class Requires
33 {
34  Dummy
35 };
36 namespace traits
37 {
48 template<typename MapT, typename MapMsgT>
50 {
54  template<typename Map>
55  using call_set = decltype(std::declval<Map>().set(std::declval<const MapMsgT &>()));
56 
60  template<typename Map>
61  using call_frame_id = decltype(std::declval<Map>().frame_id());
62 
65  template<typename Map>
66  using call_valid = decltype(std::declval<Map>().valid());
67 
68  static_assert(
70  "The map should provide a `set(msg)` method");
71  static_assert(
73  const std::string &>::value,
74  "The map should provide a `frame_id()` method");
75  static_assert(
77  "The map should provide a `valid(msg)` method");
78  static constexpr Requires value{};
79 };
80 
93 template<typename LocalizerT, typename InputT, typename MapT,
96 {
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>())
111  );
112 
113  static_assert(
115  call_register, LocalizerT, geometry_msgs::msg::PoseWithCovarianceStamped>::value,
116  "The localizer should provide a valid `register_measurement(...)` method.");
117  static constexpr Requires value{};
118 };
119 // External definition of static members:
120 template<typename MapT, typename MapMsgT>
122 template<typename LocalizerT, typename InputT, typename MapT, typename SummaryT>
124 } // namespace traits
125 } // namespace localization_nodes
126 } // namespace localization
127 } // namespace autoware
128 #endif // LOCALIZATION_NODES__CONSTRAINTS_HPP_
autoware::localization::localization_nodes::traits::MapConstraint
This struct specifies the interface requirements of MapT given MapMsgT parameter of a relative locali...
Definition: localization_nodes/include/localization_nodes/constraints.hpp:49
autoware::common::helper_functions::expression_valid_with_return
Definition: template_utils.hpp:51
autoware::localization::localization_nodes::Requires
Requires
Helper class for concepts-like API.
Definition: localization_nodes/include/localization_nodes/constraints.hpp:32
autoware::localization::localization_nodes::traits::LocalizerConstraint
This struct specifies the interface requirements of LocalizerT, given the InputT, MapT and SummaryT p...
Definition: localization_nodes/include/localization_nodes/constraints.hpp:95
autoware::localization::localization_common::OptimizedRegistrationSummary
Definition: optimized_registration_summary.hpp:32
autoware::localization::localization_nodes::traits::MapConstraint::call_valid
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
autoware::localization::localization_nodes::traits::LocalizerConstraint::call_register
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
autoware::localization::localization_nodes::traits::MapConstraint::value
static constexpr Requires value
Definition: localization_nodes/include/localization_nodes/constraints.hpp:78
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
autoware::common::helper_functions::expression_valid
Definition: template_utils.hpp:34
autoware::localization::localization_nodes::traits::MapConstraint::call_set
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
template_utils.hpp
autoware::localization::localization_nodes::traits::MapConstraint::call_frame_id
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
autoware::localization::localization_nodes::traits::LocalizerConstraint::value
static constexpr Requires value
Definition: localization_nodes/include/localization_nodes/constraints.hpp:117
optimized_registration_summary.hpp
autoware::localization::localization_nodes::Requires::Dummy
@ Dummy