Go to the documentation of this file.
17 #ifndef POINT_CLOUD_MAPPING__POLICIES_HPP_
18 #define POINT_CLOUD_MAPPING__POLICIES_HPP_
22 #include <sensor_msgs/msg/point_cloud2.hpp>
24 #include <tf2_sensor_msgs/tf2_sensor_msgs.h>
34 namespace point_cloud_mapping
38 template<
typename Derived>
46 template<
typename MapRepresentationT>
47 bool ready(
const MapRepresentationT & map)
const noexcept
49 return this->
impl().ready_(map);
57 template<
typename MapRepresentationT>
58 bool ready_(
const MapRepresentationT & map)
const noexcept
60 return map.size() >= map.capacity();
66 template<
typename Derived>
75 std::string
get(
const std::string & base_prefix)
const noexcept
77 return this->
impl().get_(base_prefix);
86 std::string get_(
const std::string & base_prefix)
const noexcept;
92 #endif // POINT_CLOUD_MAPPING__POLICIES_HPP_
std::string get(const std::string &base_prefix) const noexcept
Definition: policies.hpp:75
Trigger map writing when map reaches its capacity.
Definition: policies.hpp:54
This class defines common functions and classes to work with pointclouds.
Definition: policies.hpp:39
bool ready(const MapRepresentationT &map) const noexcept
Definition: policies.hpp:47
bool ready_(const MapRepresentationT &map) const noexcept
Definition: policies.hpp:58
Definition: policies.hpp:67
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
const Derived & impl() const
Definition: crtp.hpp:32
Prefix generator that adds the current time stamp to the end of the base prefix.
Definition: policies.hpp:82