moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
occupancy_map_monitor.hpp
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 <rclcpp/version.h>
46// For Rolling, Kilted, and newer
47#if RCLCPP_VERSION_GTE(29, 6, 0)
48#include <tf2_ros/buffer.hpp>
49// For Jazzy and older
50#else
51#include <tf2_ros/buffer.h>
52#endif
53
54#include <functional>
55#include <memory>
56#include <mutex>
57#include <string>
58#include <utility>
59#include <vector>
60
62{
64{
65public:
70 {
72 std::string map_frame;
73 std::vector<std::pair<std::string, std::string>> sensor_plugins;
74 };
75
80 {
81 public:
82 using SaveMapServiceCallback = std::function<bool(const std::shared_ptr<rmw_request_id_t> request_header,
83 const std::shared_ptr<moveit_msgs::srv::SaveMap::Request> request,
84 std::shared_ptr<moveit_msgs::srv::SaveMap::Response> response)>;
85 using LoadMapServiceCallback = std::function<bool(const std::shared_ptr<rmw_request_id_t> request_header,
86 const std::shared_ptr<moveit_msgs::srv::LoadMap::Request> request,
87 std::shared_ptr<moveit_msgs::srv::LoadMap::Response> response)>;
88
92 virtual ~MiddlewareHandle() = default;
93
99 virtual Parameters getParameters() const = 0;
100
108 virtual OccupancyMapUpdaterPtr loadOccupancyMapUpdater(const std::string& sensor_plugin) = 0;
109
115 virtual void initializeOccupancyMapUpdater(OccupancyMapUpdaterPtr occupancy_map_updater) = 0;
116
123
130 };
131
138 OccupancyMapMonitor(std::unique_ptr<MiddlewareHandle> middleware_handle,
139 const std::shared_ptr<tf2_ros::Buffer>& tf_buffer);
140
149 OccupancyMapMonitor(const rclcpp::Node::SharedPtr& node, const std::shared_ptr<tf2_ros::Buffer>& tf_buffer,
150 const std::string& map_frame = "", double map_resolution = 0.0);
151
158 OccupancyMapMonitor(const rclcpp::Node::SharedPtr& node, double map_resolution = 0.0);
159
164
168 void startMonitor();
169
173 void stopMonitor();
174
178 {
179 return tree_;
180 }
181
185 {
186 return tree_const_;
187 }
188
194 const std::string& getMapFrame() const
195 {
196 return parameters_.map_frame;
197 }
198
204 void setMapFrame(const std::string& frame);
205
211 double getMapResolution() const
212 {
213 return parameters_.map_resolution;
214 }
215
221 const std::shared_ptr<tf2_ros::Buffer>& getTFClient() const
222 {
223 return tf_buffer_;
224 }
225
231 void addUpdater(const OccupancyMapUpdaterPtr& updater);
232
240 ShapeHandle excludeShape(const shapes::ShapeConstPtr& shape);
241
247 void forgetShape(ShapeHandle handle);
248
254 void setUpdateCallback(const std::function<void()>& update_callback)
255 {
256 tree_->setUpdateCallback(update_callback);
257 }
258
264 void setTransformCacheCallback(const TransformCacheProvider& transform_cache_callback);
265
271 void publishDebugInformation(bool flag);
272
278 bool isActive() const
279 {
280 return active_;
281 }
282
283private:
293 bool saveMapCallback(const std::shared_ptr<rmw_request_id_t>& request_header,
294 const std::shared_ptr<moveit_msgs::srv::SaveMap::Request>& request,
295 const std::shared_ptr<moveit_msgs::srv::SaveMap::Response>& response);
296
306 bool loadMapCallback(const std::shared_ptr<rmw_request_id_t>& request_header,
307 const std::shared_ptr<moveit_msgs::srv::LoadMap::Request>& request,
308 const std::shared_ptr<moveit_msgs::srv::LoadMap::Response>& response);
309
320 bool getShapeTransformCache(std::size_t index, const std::string& target_frame, const rclcpp::Time& target_time,
321 ShapeTransformCache& cache) const;
322
323 std::unique_ptr<MiddlewareHandle> middleware_handle_;
324 std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
325 Parameters parameters_;
326 std::mutex parameters_lock_;
331 std::vector<OccupancyMapUpdaterPtr> map_updaters_;
332 std::vector<std::map<ShapeHandle, ShapeHandle>> mesh_handles_;
333 TransformCacheProvider transform_cache_callback_;
334 bool debug_info_;
336 std::size_t mesh_handle_count_;
338 bool active_;
340 rclcpp::Logger logger_;
341};
342} // 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.
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