moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
occupancy_map_monitor.h
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
37#pragma once
38
41#include <moveit_msgs/srv/load_map.hpp>
42#include <moveit_msgs/srv/save_map.hpp>
43
44#include <rclcpp/rclcpp.hpp>
45#include <tf2_ros/buffer.h>
46
47#include <functional>
48#include <memory>
49#include <mutex>
50#include <string>
51#include <utility>
52#include <vector>
53
55{
57{
58public:
63 {
65 std::string map_frame;
66 std::vector<std::pair<std::string, std::string>> sensor_plugins;
67 };
68
73 {
74 public:
75 using SaveMapServiceCallback = std::function<bool(const std::shared_ptr<rmw_request_id_t> request_header,
76 const std::shared_ptr<moveit_msgs::srv::SaveMap::Request> request,
77 std::shared_ptr<moveit_msgs::srv::SaveMap::Response> response)>;
78 using LoadMapServiceCallback = std::function<bool(const std::shared_ptr<rmw_request_id_t> request_header,
79 const std::shared_ptr<moveit_msgs::srv::LoadMap::Request> request,
80 std::shared_ptr<moveit_msgs::srv::LoadMap::Response> response)>;
81
85 virtual ~MiddlewareHandle() = default;
86
92 virtual Parameters getParameters() const = 0;
93
101 virtual OccupancyMapUpdaterPtr loadOccupancyMapUpdater(const std::string& sensor_plugin) = 0;
102
108 virtual void initializeOccupancyMapUpdater(OccupancyMapUpdaterPtr occupancy_map_updater) = 0;
109
116
123 };
124
131 OccupancyMapMonitor(std::unique_ptr<MiddlewareHandle> middleware_handle,
132 const std::shared_ptr<tf2_ros::Buffer>& tf_buffer);
133
142 OccupancyMapMonitor(const rclcpp::Node::SharedPtr& node, const std::shared_ptr<tf2_ros::Buffer>& tf_buffer,
143 const std::string& map_frame = "", double map_resolution = 0.0);
144
151 OccupancyMapMonitor(const rclcpp::Node::SharedPtr& node, double map_resolution = 0.0);
152
157
161 void startMonitor();
162
166 void stopMonitor();
167
171 {
172 return tree_;
173 }
174
178 {
179 return tree_const_;
180 }
181
187 const std::string& getMapFrame() const
188 {
189 return parameters_.map_frame;
190 }
191
197 void setMapFrame(const std::string& frame);
198
204 double getMapResolution() const
205 {
206 return parameters_.map_resolution;
207 }
208
214 const std::shared_ptr<tf2_ros::Buffer>& getTFClient() const
215 {
216 return tf_buffer_;
217 }
218
224 void addUpdater(const OccupancyMapUpdaterPtr& updater);
225
233 ShapeHandle excludeShape(const shapes::ShapeConstPtr& shape);
234
240 void forgetShape(ShapeHandle handle);
241
247 void setUpdateCallback(const std::function<void()>& update_callback)
248 {
249 tree_->setUpdateCallback(update_callback);
250 }
251
257 void setTransformCacheCallback(const TransformCacheProvider& transform_cache_callback);
258
264 void publishDebugInformation(bool flag);
265
271 bool isActive() const
272 {
273 return active_;
274 }
275
276private:
286 bool saveMapCallback(const std::shared_ptr<rmw_request_id_t>& request_header,
287 const std::shared_ptr<moveit_msgs::srv::SaveMap::Request>& request,
288 const std::shared_ptr<moveit_msgs::srv::SaveMap::Response>& response);
289
299 bool loadMapCallback(const std::shared_ptr<rmw_request_id_t>& request_header,
300 const std::shared_ptr<moveit_msgs::srv::LoadMap::Request>& request,
301 const std::shared_ptr<moveit_msgs::srv::LoadMap::Response>& response);
302
313 bool getShapeTransformCache(std::size_t index, const std::string& target_frame, const rclcpp::Time& target_time,
314 ShapeTransformCache& cache) const;
315
316 std::unique_ptr<MiddlewareHandle> middleware_handle_;
317 std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
318 Parameters parameters_;
319 std::mutex parameters_lock_;
324 std::vector<OccupancyMapUpdaterPtr> map_updaters_;
325 std::vector<std::map<ShapeHandle, ShapeHandle>> mesh_handles_;
326 TransformCacheProvider transform_cache_callback_;
327 bool debug_info_;
329 std::size_t mesh_handle_count_;
331 bool active_;
333 rclcpp::Logger logger_;
334};
335} // namespace occupancy_map_monitor
This class contains the rcl interfaces for easier testing.
virtual OccupancyMapUpdaterPtr loadOccupancyMapUpdater(const std::string &sensor_plugin)=0
Loads an occupancy map updater based on string.
virtual ~MiddlewareHandle()=default
Destroys the object. Needed because this is pure virtual interface.
virtual void createLoadMapService(LoadMapServiceCallback callback)=0
Creates a load map service.
std::function< bool(const std::shared_ptr< rmw_request_id_t > request_header, const std::shared_ptr< moveit_msgs::srv::LoadMap::Request > request, std::shared_ptr< moveit_msgs::srv::LoadMap::Response > response)> LoadMapServiceCallback
virtual Parameters getParameters() const =0
Gets the parameters struct.
std::function< bool(const std::shared_ptr< rmw_request_id_t > request_header, const std::shared_ptr< moveit_msgs::srv::SaveMap::Request > request, std::shared_ptr< moveit_msgs::srv::SaveMap::Response > response)> SaveMapServiceCallback
virtual void createSaveMapService(SaveMapServiceCallback callback)=0
Creates a save map service.
virtual void initializeOccupancyMapUpdater(OccupancyMapUpdaterPtr occupancy_map_updater)=0
Initializes the occupancy map updater. Needed because of interface to OccupancyMapUpdater.
const collision_detection::OccMapTreeConstPtr & getOcTreePtr() const
Get a const pointer to the underlying octree for this monitor. Lock the tree before reading this poin...
const collision_detection::OccMapTreePtr & getOcTreePtr()
Get a pointer to the underlying octree for this monitor. Lock the tree before reading or writing usin...
void startMonitor()
start the monitor (will begin updating the octomap
void setTransformCacheCallback(const TransformCacheProvider &transform_cache_callback)
Sets the transform cache callback.
const std::shared_ptr< tf2_ros::Buffer > & getTFClient() const
Gets the tf client.
const std::string & getMapFrame() const
Gets the map frame (this is set either by the constor or a parameter).
void publishDebugInformation(bool flag)
Set the debug flag on the updaters.
double getMapResolution() const
Gets the map resolution.
void stopMonitor()
Stops the monitor, this also stops the updaters.
ShapeHandle excludeShape(const shapes::ShapeConstPtr &shape)
Add this shape to the set of shapes to be filtered out from the octomap.
bool isActive() const
Determines if active.
void addUpdater(const OccupancyMapUpdaterPtr &updater)
Adds an OccupancyMapUpdater to be monitored.
void setMapFrame(const std::string &frame)
Sets the map frame.
void setUpdateCallback(const std::function< void()> &update_callback)
Set the callback to trigger when updates to the maintained octomap are received.
void forgetShape(ShapeHandle handle)
Forget about this shape handle and the shapes it corresponds to.
std::shared_ptr< const OccMapTree > OccMapTreeConstPtr
std::shared_ptr< OccMapTree > OccMapTreePtr
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
This class describes parameters that are normally provided through ROS Parameters.
std::vector< std::pair< std::string, std::string > > sensor_plugins