moveit2
The MoveIt Motion Planning Framework for ROS 2.
occupancy_map_monitor.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan, Jon Binney */
36 
40 #include <moveit_msgs/srv/load_map.hpp>
41 #include <moveit_msgs/srv/save_map.hpp>
42 #include <rclcpp/clock.hpp>
43 #include <rclcpp/logger.hpp>
44 #include <rclcpp/logging.hpp>
45 #include <rclcpp/node.hpp>
46 #include <memory>
47 #include <string>
48 #include <utility>
49 #include <vector>
50 
51 namespace occupancy_map_monitor
52 {
53 namespace
54 {
55 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ros.occupancy_map_monitor");
56 }
57 
58 OccupancyMapMonitor::OccupancyMapMonitor(const rclcpp::Node::SharedPtr& node, double map_resolution)
59  : OccupancyMapMonitor{ std::make_unique<OccupancyMapMonitorMiddlewareHandle>(node, map_resolution, ""), nullptr }
60 {
61 }
62 
63 OccupancyMapMonitor::OccupancyMapMonitor(const rclcpp::Node::SharedPtr& node,
64  const std::shared_ptr<tf2_ros::Buffer>& tf_buffer,
65  const std::string& map_frame, double map_resolution)
66  : OccupancyMapMonitor{ std::make_unique<OccupancyMapMonitorMiddlewareHandle>(node, map_resolution, map_frame),
67  tf_buffer }
68 {
69 }
70 
71 OccupancyMapMonitor::OccupancyMapMonitor(std::unique_ptr<MiddlewareHandle> middleware_handle,
72  const std::shared_ptr<tf2_ros::Buffer>& tf_buffer)
73  : middleware_handle_{ std::move(middleware_handle) }
74  , tf_buffer_{ tf_buffer }
75  , parameters_{ 0.0, "", {} }
76  , debug_info_{ false }
77  , mesh_handle_count_{ 0 }
78  , active_{ false }
79 {
80  if (middleware_handle_ == nullptr)
81  {
82  throw std::invalid_argument("OccupancyMapMonitor cannot be constructed with nullptr MiddlewareHandle");
83  }
84 
85  // Get the parameters
86  parameters_ = middleware_handle_->getParameters();
87 
88  RCLCPP_DEBUG(LOGGER, "Using resolution = %lf m for building octomap", parameters_.map_resolution);
89 
90  if (tf_buffer_ != nullptr && parameters_.map_frame.empty())
91  {
92  RCLCPP_WARN(LOGGER, "No target frame specified for Octomap. No transforms will be applied to received data.");
93  }
94  if (tf_buffer_ == nullptr && !parameters_.map_frame.empty())
95  {
96  RCLCPP_WARN(LOGGER, "Target frame specified but no TF instance (buffer) specified."
97  "No transforms will be applied to received data.");
98  }
99 
100  tree_ = std::make_shared<collision_detection::OccMapTree>(parameters_.map_resolution);
101  tree_const_ = tree_;
102 
103  for (const auto& [sensor_name, sensor_type] : parameters_.sensor_plugins)
104  {
105  auto occupancy_map_updater = middleware_handle_->loadOccupancyMapUpdater(sensor_type);
106 
107  // Verify the updater was loaded
108  if (occupancy_map_updater == nullptr)
109  {
110  RCLCPP_ERROR_STREAM(LOGGER, "Failed to load sensor: `" << sensor_name << "` of type: `" << sensor_type << "`");
111  continue;
112  }
113 
114  // Pass a pointer to the monitor to the updater
115  occupancy_map_updater->setMonitor(this);
116 
117  // This part is done in the middleware handle because it needs the node
118  middleware_handle_->initializeOccupancyMapUpdater(occupancy_map_updater);
119 
120  // Load the params in the updater
121  if (!occupancy_map_updater->setParams(sensor_name))
122  {
123  RCLCPP_ERROR_STREAM(LOGGER, "Failed to configure updater of type " << occupancy_map_updater->getType());
124  continue;
125  }
126 
127  // Add the successfully initialized updater
128  addUpdater(occupancy_map_updater);
129  }
130 
131  /* advertise a service for loading octomaps from disk */
132  auto save_map_service_callback = [this](const std::shared_ptr<rmw_request_id_t>& request_header,
133  const std::shared_ptr<moveit_msgs::srv::SaveMap::Request>& request,
134  const std::shared_ptr<moveit_msgs::srv::SaveMap::Response>& response) -> bool {
135  return saveMapCallback(request_header, request, response);
136  };
137 
138  auto load_map_service_callback = [this](const std::shared_ptr<rmw_request_id_t>& request_header,
139  const std::shared_ptr<moveit_msgs::srv::LoadMap::Request>& request,
140  const std::shared_ptr<moveit_msgs::srv::LoadMap::Response>& response) -> bool {
141  return loadMapCallback(request_header, request, response);
142  };
143 
144  middleware_handle_->createSaveMapService(save_map_service_callback);
145  middleware_handle_->createLoadMapService(load_map_service_callback);
146 }
147 
148 void OccupancyMapMonitor::addUpdater(const OccupancyMapUpdaterPtr& updater)
149 {
150  if (updater)
151  {
152  map_updaters_.push_back(updater);
153  updater->publishDebugInformation(debug_info_);
154  if (map_updaters_.size() > 1)
155  {
156  mesh_handles_.resize(map_updaters_.size());
157  // when we had one updater only, we passed directly the transform cache callback to that updater
158  if (map_updaters_.size() == 2)
159  {
160  map_updaters_[0]->setTransformCacheCallback(
161  [this](const std::string& frame, const rclcpp::Time& stamp, ShapeTransformCache& cache) {
162  return getShapeTransformCache(0, frame, stamp, cache);
163  });
164  map_updaters_[1]->setTransformCacheCallback(
165  [this](const std::string& frame, const rclcpp::Time& stamp, ShapeTransformCache& cache) {
166  return getShapeTransformCache(1, frame, stamp, cache);
167  });
168  }
169  else
170  map_updaters_.back()->setTransformCacheCallback(
171  [this, i = map_updaters_.size() - 1](const std::string& frame, const rclcpp::Time& stamp,
172  ShapeTransformCache& cache) {
173  return getShapeTransformCache(i, frame, stamp, cache);
174  });
175  }
176  else
177  updater->setTransformCacheCallback(transform_cache_callback_);
178  }
179  else
180  RCLCPP_ERROR(LOGGER, "nullptr updater was specified");
181 }
182 
183 void OccupancyMapMonitor::publishDebugInformation(bool flag)
184 {
185  debug_info_ = flag;
186  for (OccupancyMapUpdaterPtr& map_updater : map_updaters_)
187  map_updater->publishDebugInformation(debug_info_);
188 }
189 
190 void OccupancyMapMonitor::setMapFrame(const std::string& frame)
191 {
192  std::lock_guard<std::mutex> _(parameters_lock_); // we lock since an updater could specify a new frame for us
193  parameters_.map_frame = frame;
194 }
195 
196 ShapeHandle OccupancyMapMonitor::excludeShape(const shapes::ShapeConstPtr& shape)
197 {
198  // if we have just one updater, remove the additional level of indirection
199  if (map_updaters_.size() == 1)
200  return map_updaters_[0]->excludeShape(shape);
201 
202  ShapeHandle h = 0;
203  for (std::size_t i = 0; i < map_updaters_.size(); ++i)
204  {
205  ShapeHandle mh = map_updaters_[i]->excludeShape(shape);
206  if (mh)
207  {
208  if (h == 0)
209  h = ++mesh_handle_count_;
210  mesh_handles_[i][h] = mh;
211  }
212  }
213  return h;
214 }
215 
216 void OccupancyMapMonitor::forgetShape(ShapeHandle handle)
217 {
218  // if we have just one updater, remove the additional level of indirection
219  if (map_updaters_.size() == 1)
220  {
221  map_updaters_[0]->forgetShape(handle);
222  return;
223  }
224 
225  for (std::size_t i = 0; i < map_updaters_.size(); ++i)
226  {
227  std::map<ShapeHandle, ShapeHandle>::const_iterator it = mesh_handles_[i].find(handle);
228  if (it == mesh_handles_[i].end())
229  continue;
230  map_updaters_[i]->forgetShape(it->second);
231  }
232 }
233 
234 void OccupancyMapMonitor::setTransformCacheCallback(const TransformCacheProvider& transform_callback)
235 {
236  // if we have just one updater, we connect it directly to the transform provider
237  if (map_updaters_.size() == 1)
238  map_updaters_[0]->setTransformCacheCallback(transform_callback);
239  else
240  transform_cache_callback_ = transform_callback;
241 }
242 
243 bool OccupancyMapMonitor::getShapeTransformCache(std::size_t index, const std::string& target_frame,
244  const rclcpp::Time& target_time, ShapeTransformCache& cache) const
245 {
246  if (transform_cache_callback_)
247  {
248  ShapeTransformCache temp_cache;
249  if (transform_cache_callback_(target_frame, target_time, temp_cache))
250  {
251  for (std::pair<const ShapeHandle, Eigen::Isometry3d>& it : temp_cache)
252  {
253  std::map<ShapeHandle, ShapeHandle>::const_iterator jt = mesh_handles_[index].find(it.first);
254  if (jt == mesh_handles_[index].end())
255  {
256  rclcpp::Clock steady_clock(RCL_STEADY_TIME);
257  RCLCPP_ERROR_THROTTLE(LOGGER, steady_clock, 1000, "Incorrect mapping of mesh handles");
258  return false;
259  }
260  else
261  cache[jt->second] = it.second;
262  }
263  return true;
264  }
265  else
266  return false;
267  }
268  else
269  return false;
270 }
271 
272 bool OccupancyMapMonitor::saveMapCallback(const std::shared_ptr<rmw_request_id_t>& /* unused */,
273  const std::shared_ptr<moveit_msgs::srv::SaveMap::Request>& request,
274  const std::shared_ptr<moveit_msgs::srv::SaveMap::Response>& response)
275 {
276  RCLCPP_INFO(LOGGER, "Writing map to %s", request->filename.c_str());
277  tree_->lockRead();
278  try
279  {
280  response->success = tree_->writeBinary(request->filename);
281  }
282  catch (...)
283  {
284  response->success = false;
285  }
286  tree_->unlockRead();
287  return true;
288 }
289 
290 bool OccupancyMapMonitor::loadMapCallback(const std::shared_ptr<rmw_request_id_t>& /* unused */,
291  const std::shared_ptr<moveit_msgs::srv::LoadMap::Request>& request,
292  const std::shared_ptr<moveit_msgs::srv::LoadMap::Response>& response)
293 {
294  RCLCPP_INFO(LOGGER, "Reading map from %s", request->filename.c_str());
295 
296  /* load the octree from disk */
297  tree_->lockWrite();
298  try
299  {
300  response->success = tree_->readBinary(request->filename);
301  }
302  catch (...)
303  {
304  RCLCPP_ERROR(LOGGER, "Failed to load map from file");
305  response->success = false;
306  }
307  tree_->unlockWrite();
308 
309  if (response->success)
310  tree_->triggerUpdateCallback();
311 
312  return true;
313 }
314 
315 void OccupancyMapMonitor::startMonitor()
316 {
317  active_ = true;
318  /* initialize all of the occupancy map updaters */
319  for (OccupancyMapUpdaterPtr& map_updater : map_updaters_)
320  map_updater->start();
321 }
322 
323 void OccupancyMapMonitor::stopMonitor()
324 {
325  active_ = false;
326  for (OccupancyMapUpdaterPtr& map_updater : map_updaters_)
327  map_updater->stop();
328 }
329 
330 OccupancyMapMonitor::~OccupancyMapMonitor()
331 {
332  stopMonitor();
333 }
334 } // namespace occupancy_map_monitor
This class contains the ros interfaces for OccupancyMapMontior.
OccupancyMapMonitor(std::unique_ptr< MiddlewareHandle > middleware_handle, const std::shared_ptr< tf2_ros::Buffer > &tf_buffer)
Occupancy map monitor constructor with the MiddlewareHandle.
std::function< bool(const std::string &, const rclcpp::Time &, ShapeTransformCache &)> TransformCacheProvider
std::map< ShapeHandle, Eigen::Isometry3d, std::less< ShapeHandle >, Eigen::aligned_allocator< std::pair< const ShapeHandle, Eigen::Isometry3d > > > ShapeTransformCache
const rclcpp::Logger LOGGER
Definition: async_test.h:31