Go to the documentation of this file.
17 #ifndef NDT__CONSTRAINTS_HPP_
18 #define NDT__CONSTRAINTS_HPP_
22 #include <type_traits>
27 namespace localization
37 template<
typename MapT>
43 template<
typename Map>
48 template<
typename Map>
49 using call_stamp = decltype(std::declval<Map>().stamp());
53 const std::string &>::
value,
54 "The map should provide a `frame_id()` method");
58 std::chrono::system_clock::time_point>::
value,
59 "The map should provide a `stamp()` method");
66 template<
typename MapT>
70 using Voxel =
typename MapT::Voxel;
77 template<
typename Map>
78 using call_cell = decltype(std::declval<Map>().cell(std::declval<const Point &>()));
82 template<
typename Map>
88 "The map should provide a `cell(...)` method");
93 "The map should provide a `cell_size()` method");
108 #endif // NDT__CONSTRAINTS_HPP_
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
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
Definition: template_utils.hpp:51
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
static constexpr Requires value
Definition: ndt/include/ndt/constraints.hpp:95
This constraint expresses the map interface requirements for the localizer.
Definition: ndt/include/ndt/constraints.hpp:38
Requires
Definition: ndt/include/ndt/constraints.hpp:31
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
std::vector< VoxelView< Voxel > > VoxelViewVector
Definition: ndt/include/ndt/constraints.hpp:71
geometry_msgs::msg::Point32 PointXYZ
Definition: perception/filters/voxel_grid/include/voxel_grid/config.hpp:47
static constexpr Requires value
Definition: ndt/include/ndt/constraints.hpp:61
This constraint expresses the map interface requirements for the localizer.
Definition: ndt/include/ndt/constraints.hpp:67
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
Eigen::Vector3d Point
Definition: ndt/include/ndt/constraints.hpp:72
typename MapT::Voxel Voxel
The map type should expose the voxel type.
Definition: ndt/include/ndt/constraints.hpp:70