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>
33 namespace point_cloud_mapping
37 template<
typename Derived>
45 template<
typename MapRepresentationT>
46 bool ready(
const MapRepresentationT & map)
const noexcept
48 return this->
impl().ready_(map);
56 template<
typename MapRepresentationT>
57 bool ready_(
const MapRepresentationT & map)
const noexcept
59 return map.size() >= map.capacity();
65 template<
typename Derived>
74 std::string
get(
const std::string & base_prefix)
const noexcept
76 return this->
impl().get_(base_prefix);
85 std::string get_(
const std::string & base_prefix)
const noexcept;
91 #endif // POINT_CLOUD_MAPPING__POLICIES_HPP_
std::string get(const std::string &base_prefix) const noexcept
Definition: policies.hpp:74
Trigger map writing when map reaches its capacity.
Definition: policies.hpp:53
Definition: policies.hpp:38
bool ready(const MapRepresentationT &map) const noexcept
Definition: policies.hpp:46
bool ready_(const MapRepresentationT &map) const noexcept
Definition: policies.hpp:57
Definition: policies.hpp:66
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:81