Autoware.Auto
ndt/include/ndt/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 NDT__CONSTRAINTS_HPP_
18 #define NDT__CONSTRAINTS_HPP_
19 
21 #include <string>
22 #include <type_traits>
23 #include <vector>
24 
25 namespace autoware
26 {
27 namespace localization
28 {
29 namespace ndt
30 {
31 enum class Requires {};
32 
33 namespace traits
34 {
37 template<typename MapT>
39 {
43  template<typename Map>
44  using call_frame_id = decltype(std::declval<Map>().frame_id());
45 
48  template<typename Map>
49  using call_stamp = decltype(std::declval<Map>().stamp());
50 
51  static_assert(
53  const std::string &>::value,
54  "The map should provide a `frame_id()` method");
55 
56  static_assert(
58  std::chrono::system_clock::time_point>::value,
59  "The map should provide a `stamp()` method");
60 
61  static constexpr Requires value{};
62 };
63 
66 template<typename MapT>
68 {
70  using Voxel = typename MapT::Voxel;
71  using VoxelViewVector = std::vector<VoxelView<Voxel>>;
72  using Point = Eigen::Vector3d;
73 
74 
77  template<typename Map>
78  using call_cell = decltype(std::declval<Map>().cell(std::declval<const Point &>()));
79 
82  template<typename Map>
83  using call_cell_size = decltype(std::declval<Map>().cell_size());
84 
85  static_assert(
87  const VoxelViewVector &>::value,
88  "The map should provide a `cell(...)` method");
89 
90  static_assert(
93  "The map should provide a `cell_size()` method");
94 
95  static constexpr Requires value{};
96 };
97 
98 // Define static members
99 template<typename T>
101 template<typename T>
103 } // namespace traits
104 } // namespace ndt
105 } // namespace localization
106 } // namespace autoware
107 
108 #endif // NDT__CONSTRAINTS_HPP_
autoware::localization::ndt::traits::LocalizationMapConstraint::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: ndt/include/ndt/constraints.hpp:44
autoware::localization::ndt::traits::LocalizationMapConstraint::call_stamp
decltype(std::declval< Map >().stamp()) call_stamp
This expression requires a method that returns the (std::chrono) timestamp of the.
Definition: ndt/include/ndt/constraints.hpp:49
autoware::common::helper_functions::expression_valid_with_return
Definition: template_utils.hpp:51
autoware::localization::ndt::traits::P2DNDTOptimizationMapConstraint::call_cell_size
decltype(std::declval< Map >().cell_size()) call_cell_size
This expression requires a method that returns the (std::chrono) timestamp of the.
Definition: ndt/include/ndt/constraints.hpp:83
autoware::localization::ndt::traits::P2DNDTOptimizationMapConstraint::value
static constexpr Requires value
Definition: ndt/include/ndt/constraints.hpp:95
autoware::localization::ndt::traits::LocalizationMapConstraint
This constraint expresses the map interface requirements for the localizer.
Definition: ndt/include/ndt/constraints.hpp:38
autoware::localization::ndt::Requires
Requires
Definition: ndt/include/ndt/constraints.hpp:31
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
autoware::localization::ndt::traits::P2DNDTOptimizationMapConstraint::VoxelViewVector
std::vector< VoxelView< Voxel > > VoxelViewVector
Definition: ndt/include/ndt/constraints.hpp:71
autoware::perception::filters::voxel_grid::PointXYZ
geometry_msgs::msg::Point32 PointXYZ
Definition: perception/filters/voxel_grid/include/voxel_grid/config.hpp:47
autoware::localization::ndt::traits::LocalizationMapConstraint::value
static constexpr Requires value
Definition: ndt/include/ndt/constraints.hpp:61
autoware::localization::ndt::traits::P2DNDTOptimizationMapConstraint
This constraint expresses the map interface requirements for the localizer.
Definition: ndt/include/ndt/constraints.hpp:67
autoware::localization::ndt::traits::P2DNDTOptimizationMapConstraint::call_cell
decltype(std::declval< Map >().cell(std::declval< const Point & >())) call_cell
This expression requires a method that looks up the cells at the given location.
Definition: ndt/include/ndt/constraints.hpp:78
autoware::localization::ndt::traits::P2DNDTOptimizationMapConstraint::Point
Eigen::Vector3d Point
Definition: ndt/include/ndt/constraints.hpp:72
autoware::localization::ndt::traits::P2DNDTOptimizationMapConstraint::Voxel
typename MapT::Voxel Voxel
The map type should expose the voxel type.
Definition: ndt/include/ndt/constraints.hpp:70
template_utils.hpp