moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
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>
51
53{
54
55OccupancyMapMonitor::OccupancyMapMonitor(const rclcpp::Node::SharedPtr& node, double map_resolution)
56 : OccupancyMapMonitor{ std::make_unique<OccupancyMapMonitorMiddlewareHandle>(node, map_resolution, ""), nullptr }
57{
58}
59
60OccupancyMapMonitor::OccupancyMapMonitor(const rclcpp::Node::SharedPtr& node,
61 const std::shared_ptr<tf2_ros::Buffer>& tf_buffer,
62 const std::string& map_frame, double map_resolution)
63 : OccupancyMapMonitor{ std::make_unique<OccupancyMapMonitorMiddlewareHandle>(node, map_resolution, map_frame),
64 tf_buffer }
65{
66}
67
68OccupancyMapMonitor::OccupancyMapMonitor(std::unique_ptr<MiddlewareHandle> middleware_handle,
69 const std::shared_ptr<tf2_ros::Buffer>& tf_buffer)
70 : middleware_handle_{ std::move(middleware_handle) }
71 , tf_buffer_{ tf_buffer }
72 , parameters_{ 0.0, "", {} }
73 , debug_info_{ false }
74 , mesh_handle_count_{ 0 }
75 , active_{ false }
76 , logger_(moveit::getLogger("moveit.ros.occupancy_map_monitor"))
77{
78 if (middleware_handle_ == nullptr)
79 {
80 throw std::invalid_argument("OccupancyMapMonitor cannot be constructed with nullptr MiddlewareHandle");
81 }
82
83 // Get the parameters
84 parameters_ = middleware_handle_->getParameters();
85
86 RCLCPP_DEBUG(logger_, "Using resolution = %lf m for building octomap", parameters_.map_resolution);
87
88 if (tf_buffer_ != nullptr && parameters_.map_frame.empty())
89 {
90 RCLCPP_WARN(logger_, "No target frame specified for Octomap. No transforms will be applied to received data.");
91 }
92 if (tf_buffer_ == nullptr && !parameters_.map_frame.empty())
93 {
94 RCLCPP_WARN(logger_, "Target frame specified but no TF instance (buffer) specified."
95 "No transforms will be applied to received data.");
96 }
97
98 tree_ = std::make_shared<collision_detection::OccMapTree>(parameters_.map_resolution);
99 tree_const_ = tree_;
100
101 for (const auto& [sensor_name, sensor_type] : parameters_.sensor_plugins)
102 {
103 auto occupancy_map_updater = middleware_handle_->loadOccupancyMapUpdater(sensor_type);
104
105 // Verify the updater was loaded
106 if (occupancy_map_updater == nullptr)
107 {
108 RCLCPP_ERROR_STREAM(logger_, "Failed to load sensor: `" << sensor_name << "` of type: `" << sensor_type << '`');
109 continue;
110 }
111
112 // Pass a pointer to the monitor to the updater
113 occupancy_map_updater->setMonitor(this);
114
115 // This part is done in the middleware handle because it needs the node
116 middleware_handle_->initializeOccupancyMapUpdater(occupancy_map_updater);
117
118 // Load the params in the updater
119 if (!occupancy_map_updater->setParams(sensor_name))
120 {
121 RCLCPP_ERROR_STREAM(logger_, "Failed to configure updater of type " << occupancy_map_updater->getType());
122 continue;
123 }
124
125 // Add the successfully initialized updater
126 addUpdater(occupancy_map_updater);
127 }
128
129 /* advertise a service for loading octomaps from disk */
130 auto save_map_service_callback = [this](const std::shared_ptr<rmw_request_id_t>& request_header,
131 const std::shared_ptr<moveit_msgs::srv::SaveMap::Request>& request,
132 const std::shared_ptr<moveit_msgs::srv::SaveMap::Response>& response) -> bool {
133 return saveMapCallback(request_header, request, response);
134 };
135
136 auto load_map_service_callback = [this](const std::shared_ptr<rmw_request_id_t>& request_header,
137 const std::shared_ptr<moveit_msgs::srv::LoadMap::Request>& request,
138 const std::shared_ptr<moveit_msgs::srv::LoadMap::Response>& response) -> bool {
139 return loadMapCallback(request_header, request, response);
140 };
141
142 middleware_handle_->createSaveMapService(save_map_service_callback);
143 middleware_handle_->createLoadMapService(load_map_service_callback);
144}
145
146void OccupancyMapMonitor::addUpdater(const OccupancyMapUpdaterPtr& updater)
147{
148 if (updater)
149 {
150 map_updaters_.push_back(updater);
151 updater->publishDebugInformation(debug_info_);
152 if (map_updaters_.size() > 1)
153 {
154 mesh_handles_.resize(map_updaters_.size());
155 // when we had one updater only, we passed directly the transform cache callback to that updater
156 if (map_updaters_.size() == 2)
157 {
158 map_updaters_[0]->setTransformCacheCallback(
159 [this](const std::string& frame, const rclcpp::Time& stamp, ShapeTransformCache& cache) {
160 return getShapeTransformCache(0, frame, stamp, cache);
161 });
162 map_updaters_[1]->setTransformCacheCallback(
163 [this](const std::string& frame, const rclcpp::Time& stamp, ShapeTransformCache& cache) {
164 return getShapeTransformCache(1, frame, stamp, cache);
165 });
166 }
167 else
168 {
169 map_updaters_.back()->setTransformCacheCallback(
170 [this, i = map_updaters_.size() - 1](const std::string& frame, const rclcpp::Time& stamp,
171 ShapeTransformCache& cache) {
172 return getShapeTransformCache(i, frame, stamp, cache);
173 });
174 }
175 }
176 else
177 updater->setTransformCacheCallback(transform_cache_callback_);
178 }
179 else
180 RCLCPP_ERROR(logger_, "nullptr updater was specified");
181}
182
183void OccupancyMapMonitor::publishDebugInformation(bool flag)
184{
185 debug_info_ = flag;
186 for (OccupancyMapUpdaterPtr& map_updater : map_updaters_)
187 map_updater->publishDebugInformation(debug_info_);
188}
189
190void 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
196ShapeHandle 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
216void 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
234void 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 {
239 map_updaters_[0]->setTransformCacheCallback(transform_callback);
240 }
241 else
242 {
243 transform_cache_callback_ = transform_callback;
244 }
245}
246
247bool OccupancyMapMonitor::getShapeTransformCache(std::size_t index, const std::string& target_frame,
248 const rclcpp::Time& target_time, ShapeTransformCache& cache) const
249{
250 if (transform_cache_callback_)
251 {
252 ShapeTransformCache temp_cache;
253 if (transform_cache_callback_(target_frame, target_time, temp_cache))
254 {
255 for (std::pair<const ShapeHandle, Eigen::Isometry3d>& it : temp_cache)
256 {
257 std::map<ShapeHandle, ShapeHandle>::const_iterator jt = mesh_handles_[index].find(it.first);
258 if (jt == mesh_handles_[index].end())
259 {
260 rclcpp::Clock steady_clock(RCL_STEADY_TIME);
261#pragma GCC diagnostic push
262#pragma GCC diagnostic ignored "-Wold-style-cast"
263 RCLCPP_ERROR_THROTTLE(logger_, steady_clock, 1000, "Incorrect mapping of mesh handles");
264#pragma GCC diagnostic pop
265 return false;
266 }
267 else
268 cache[jt->second] = it.second;
269 }
270 return true;
271 }
272 else
273 return false;
274 }
275 else
276 return false;
277}
278
279bool OccupancyMapMonitor::saveMapCallback(const std::shared_ptr<rmw_request_id_t>& /* unused */,
280 const std::shared_ptr<moveit_msgs::srv::SaveMap::Request>& request,
281 const std::shared_ptr<moveit_msgs::srv::SaveMap::Response>& response)
282{
283 RCLCPP_INFO(logger_, "Writing map to %s", request->filename.c_str());
284 tree_->lockRead();
285 try
286 {
287 response->success = tree_->writeBinary(request->filename);
288 }
289 catch (...)
290 {
291 response->success = false;
292 }
293 tree_->unlockRead();
294 return true;
295}
296
297bool OccupancyMapMonitor::loadMapCallback(const std::shared_ptr<rmw_request_id_t>& /* unused */,
298 const std::shared_ptr<moveit_msgs::srv::LoadMap::Request>& request,
299 const std::shared_ptr<moveit_msgs::srv::LoadMap::Response>& response)
300{
301 RCLCPP_INFO(logger_, "Reading map from %s", request->filename.c_str());
302
303 /* load the octree from disk */
304 tree_->lockWrite();
305 try
306 {
307 response->success = tree_->readBinary(request->filename);
308 }
309 catch (...)
310 {
311 RCLCPP_ERROR(logger_, "Failed to load map from file");
312 response->success = false;
313 }
314 tree_->unlockWrite();
315
316 if (response->success)
317 tree_->triggerUpdateCallback();
318
319 return true;
320}
321
322void OccupancyMapMonitor::startMonitor()
323{
324 active_ = true;
325 /* initialize all of the occupancy map updaters */
326 for (OccupancyMapUpdaterPtr& map_updater : map_updaters_)
327 map_updater->start();
328}
329
330void OccupancyMapMonitor::stopMonitor()
331{
332 active_ = false;
333 for (OccupancyMapUpdaterPtr& map_updater : map_updaters_)
334 map_updater->stop();
335}
336
337OccupancyMapMonitor::~OccupancyMapMonitor()
338{
339 stopMonitor();
340}
341} // 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.
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition logger.cpp:79
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