Autoware.Auto
point_cloud_map.hpp
Go to the documentation of this file.
1 // Copyright 2020 the Autoware Foundation
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 POINT_CLOUD_MAPPING__POINT_CLOUD_MAP_HPP_
18 #define POINT_CLOUD_MAPPING__POINT_CLOUD_MAP_HPP_
19 
21 #include <sensor_msgs/msg/point_cloud2.hpp>
22 #include <sensor_msgs/point_cloud2_iterator.hpp>
24 #include <geometry_msgs/msg/pose_with_covariance_stamped.hpp>
27 #include <common/types.hpp>
29 #include <pcl/io/pcd_io.h>
30 #include <vector>
31 #include <string>
32 #include <unordered_map>
33 #include <utility>
34 
35 namespace autoware
36 {
37 namespace mapping
38 {
39 namespace point_cloud_mapping
40 {
41 
43 enum class MapUpdateType
44 {
45  NEW,
46  UPDATE,
48  NO_CHANGE
49 };
50 
52 struct POINT_CLOUD_MAPPING_PUBLIC MapUpdateSummary
53 {
55  std::size_t num_added_pts;
56 };
58 
59 enum class Requires {};
60 
64 template<typename LocalizerMapT>
66 {
67  using Cloud = sensor_msgs::msg::PointCloud2;
68 
72  template<typename Map>
73  using call_insert = decltype(std::declval<Map>().insert(std::declval<const Cloud &>()));
74 
76  template<typename Map>
77  using call_clear = decltype(std::declval<Map>().clear());
78 
79  static_assert(
81  "The map should provide a `insert(msg)` method to be used for mapping");
82  static_assert(
84  "The map should provide a `clear()` method to be used for mapping");
85 
86  static constexpr Requires value{};
87 };
88 
93 template<typename LocalizerMapT, Requires = LocalizationMapConstraint<LocalizerMapT>::value>
94 class POINT_CLOUD_MAPPING_PUBLIC DualVoxelMap
95 {
96 public:
97  static constexpr auto NUM_FIELDS{4U};
98  using Cloud = sensor_msgs::msg::PointCloud2;
99  using CloudConstIt = sensor_msgs::PointCloud2ConstIterator<float32_t>;
100 
105  explicit DualVoxelMap(
106  const perception::filters::voxel_grid::Config & grid_config,
107  const std::string & frame_id,
108  LocalizerMapT && localizer_map
109  )
110  : m_grid_config{grid_config}, m_frame_id{frame_id},
111  m_localizer_map{std::forward<LocalizerMapT>(localizer_map)} {}
112 
116  MapUpdateSummary update(const Cloud & observation)
117  {
118  if (observation.header.frame_id != m_frame_id) {
119  throw std::runtime_error("pointcloud map and the updates should be on the same frame");
120  }
121 
122  const auto check_not_end = [](const auto & its) {
123  return std::all_of(its.cbegin(), its.cend(), [](const auto & it) {return it != it.end();});
124  };
125 
127 
128  std::array<CloudConstIt, NUM_FIELDS> obs_its = {
129  CloudConstIt(observation, "x"),
130  CloudConstIt(observation, "y"),
131  CloudConstIt(observation, "z"),
132  CloudConstIt(observation, "intensity")
133  };
134 
135  ret.update_type = m_grid.empty() ? MapUpdateType::NEW : MapUpdateType::UPDATE;
136  auto obs_idx = 0U;
137  for (; check_not_end(obs_its); ++obs_idx) {
138  common::types::PointXYZIF pt{*obs_its[0], *obs_its[1], *obs_its[2], *obs_its[3]};
139  const auto pt_key = m_grid_config.index(pt);
140  if (m_grid.size() >= capacity() &&
141  m_grid.find(pt_key) == m_grid.end())
142  {
143  if (obs_idx == 0U) {
144  ret.update_type = MapUpdateType::NO_CHANGE;
145  } else {
146  ret.update_type = MapUpdateType::PARTIAL_UPDATE;
147  }
148  break;
149  }
150 
151  m_grid[pt_key].add_observation(pt);
152 
153  // Advance the iterators.
154  std::for_each(obs_its.begin(), obs_its.end(), [](auto & it) {++it;});
155  }
156  m_localizer_map.insert(observation);
157  ret.num_added_pts = obs_idx;
158  return ret;
159  }
160 
163  void write(const std::string & file_name_prefix) const
164  {
165  // TODO(yunus.caliskan) Remove dynamic allocations.
166  // pcl cloud is constructed here and the map is copied to it for sake
167  // of simplicity to be able to use the pcl library's pcd writer.
168  pcl::PointCloud<pcl::PointXYZI> cloud;
169  cloud.reserve(m_grid.size());
170  for (const auto & vx : m_grid) {
171  pcl::PointXYZI pt;
172  const auto & vx_pt = vx.second.get();
173  pt.x = vx_pt.x;
174  pt.y = vx_pt.y;
175  pt.z = vx_pt.z;
176  pt.intensity = vx_pt.intensity;
177  cloud.push_back(pt);
178  }
179  pcl::io::savePCDFile(file_name_prefix + ".pcd", cloud);
180  }
181 
183  std::size_t size() const noexcept
184  {
185  return m_grid.size();
186  }
188  std::size_t capacity() const noexcept
189  {
190  return m_grid_config.get_capacity();
191  }
193  void clear()
194  {
195  m_grid.clear();
196  m_localizer_map.clear();
197  }
199  const LocalizerMapT & localizer_map() const noexcept
200  {
201  return m_localizer_map;
202  }
204  const std::string & frame_id() const noexcept
205  {
206  return m_frame_id;
207  }
208 
210  bool empty()
211  {
212  return m_grid.empty();
213  }
214 
215 private:
217  std::unordered_map<uint64_t,
219  std::string m_frame_id;
220  LocalizerMapT m_localizer_map;
221 };
222 } // namespace point_cloud_mapping
223 } // namespace mapping
224 } // namespace autoware
225 
226 #endif // POINT_CLOUD_MAPPING__POINT_CLOUD_MAP_HPP_
autoware::mapping::point_cloud_mapping::DualVoxelMap::write
void write(const std::string &file_name_prefix) const
Definition: point_cloud_map.hpp:163
autoware::mapping::point_cloud_mapping::MapUpdateType
MapUpdateType
Enum representing the type of update the observation has caused in the map.
Definition: point_cloud_map.hpp:43
autoware::mapping::point_cloud_mapping::MapUpdateType::PARTIAL_UPDATE
@ PARTIAL_UPDATE
autoware::mapping::point_cloud_mapping::MapUpdateType::UPDATE
@ UPDATE
autoware::mapping::point_cloud_mapping::MapUpdateSummary::num_added_pts
std::size_t num_added_pts
Definition: point_cloud_map.hpp:55
types.hpp
This file includes common type definition.
autoware::mapping::point_cloud_mapping::DualVoxelMap::DualVoxelMap
DualVoxelMap(const perception::filters::voxel_grid::Config &grid_config, const std::string &frame_id, LocalizerMapT &&localizer_map)
Definition: point_cloud_map.hpp:105
autoware::mapping::point_cloud_mapping::DualVoxelMap::empty
bool empty()
Get if the map is empty.
Definition: point_cloud_map.hpp:210
autoware::mapping::point_cloud_mapping::LocalizationMapConstraint::Cloud
sensor_msgs::msg::PointCloud2 Cloud
Definition: point_cloud_map.hpp:67
voxel_grid.hpp
This file defines the voxel grid data structure for downsampling point clouds.
autoware::mapping::point_cloud_mapping::LocalizationMapConstraint::value
static constexpr Requires value
Definition: point_cloud_map.hpp:86
autoware::mapping::point_cloud_mapping::DualVoxelMap::CloudConstIt
sensor_msgs::PointCloud2ConstIterator< float32_t > CloudConstIt
Definition: point_cloud_map.hpp:99
visibility_control.hpp
autoware::mapping::point_cloud_mapping::DualVoxelMap::localizer_map
const LocalizerMapT & localizer_map() const noexcept
Get the localizer map.
Definition: point_cloud_map.hpp:199
autoware::common::types::PointXYZIF
Definition: types.hpp:56
autoware::mapping::point_cloud_mapping::DualVoxelMap
Definition: point_cloud_map.hpp:94
autoware::mapping::point_cloud_mapping::LocalizationMapConstraint
This class encapsulates the static assertions that express the interface requirements of a localizer ...
Definition: point_cloud_map.hpp:65
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::mapping::point_cloud_mapping::LocalizationMapConstraint::call_clear
decltype(std::declval< Map >().clear()) call_clear
This expression requires a method that clears the map.
Definition: point_cloud_map.hpp:77
autoware::mapping::point_cloud_mapping::DualVoxelMap::size
std::size_t size() const noexcept
Size of the voxel grid.
Definition: point_cloud_map.hpp:183
autoware::mapping::point_cloud_mapping::MapUpdateSummary
Struct containing information on the attempt to push a new observation to a map.
Definition: point_cloud_map.hpp:52
autoware::mapping::point_cloud_mapping::DualVoxelMap::frame_id
const std::string & frame_id() const noexcept
Get the frame ID of the map.
Definition: point_cloud_map.hpp:204
autoware::mapping::point_cloud_mapping::DualVoxelMap::capacity
std::size_t capacity() const noexcept
Capacity of the voxel grid.
Definition: point_cloud_map.hpp:188
autoware::mapping::point_cloud_mapping::MapUpdateType::NO_CHANGE
@ NO_CHANGE
autoware::mapping::point_cloud_mapping::MapUpdateSummary::update_type
MapUpdateType update_type
Definition: point_cloud_map.hpp:54
autoware::common::types::float32_t
float float32_t
Definition: types.hpp:45
autoware::perception::filters::voxel_grid::Config
A configuration class for the VoxelGrid data structure, also includes some helper functionality for c...
Definition: perception/filters/voxel_grid/include/voxel_grid/config.hpp:52
crtp.hpp
This file includes common helper functions.
time_utils.hpp
autoware::mapping::point_cloud_mapping::DualVoxelMap::update
MapUpdateSummary update(const Cloud &observation)
Definition: point_cloud_map.hpp:116
autoware::perception::filters::voxel_grid::CentroidVoxel
A specialization of the Voxel class, accumulates points to a moving centroid.
Definition: voxels.hpp:115
autoware::mapping::point_cloud_mapping::MapUpdateType::NEW
@ NEW
autoware::mapping::point_cloud_mapping::DualVoxelMap::Cloud
sensor_msgs::msg::PointCloud2 Cloud
Definition: point_cloud_map.hpp:98
autoware::mapping::point_cloud_mapping::DualVoxelMap::clear
void clear()
Clear the voxel grid.
Definition: point_cloud_map.hpp:193
template_utils.hpp
autoware::mapping::point_cloud_mapping::Requires
Requires
Definition: point_cloud_map.hpp:59
autoware::mapping::point_cloud_mapping::LocalizationMapConstraint::call_insert
decltype(std::declval< Map >().insert(std::declval< const Cloud & >())) call_insert
This expression requires a method that inserts a given pointcloud2 message into the map.
Definition: point_cloud_map.hpp:73