moveit2
The MoveIt Motion Planning Framework for ROS 2.
occupancy_map_monitor_middleware_handle.hpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2021, PickNik, 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 PickNik 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: Tyler Weaver */
36 
37 #pragma once
38 
41 
42 #include <pluginlib/class_loader.hpp>
43 #include <rclcpp/rclcpp.hpp>
44 
45 #include <memory>
46 #include <string>
47 #include <utility>
48 #include <vector>
49 
50 namespace occupancy_map_monitor
51 {
56 {
57 public:
65  OccupancyMapMonitorMiddlewareHandle(const rclcpp::Node::SharedPtr& node, double map_resolution,
66  const std::string& map_frame);
67 
74 
82  OccupancyMapUpdaterPtr loadOccupancyMapUpdater(const std::string& sensor_plugin) override;
83 
89  void initializeOccupancyMapUpdater(OccupancyMapUpdaterPtr occupancy_map_updater) override;
90 
97 
104 
105 private:
106  rclcpp::Node::SharedPtr node_;
107  rclcpp::Service<moveit_msgs::srv::SaveMap>::SharedPtr save_map_srv_;
108  rclcpp::Service<moveit_msgs::srv::LoadMap>::SharedPtr load_map_srv_;
109  std::unique_ptr<pluginlib::ClassLoader<OccupancyMapUpdater>>
110  updater_plugin_loader_;
112  OccupancyMapMonitor::Parameters parameters_;
113 };
114 
115 } // namespace occupancy_map_monitor
This class contains the ros interfaces for OccupancyMapMontior.
void initializeOccupancyMapUpdater(OccupancyMapUpdaterPtr occupancy_map_updater) override
Initializes the occupancy map updater. This must be called because of the interface of OccupancyMapUp...
void createSaveMapService(OccupancyMapMonitor::MiddlewareHandle::SaveMapServiceCallback callback) override
Creates a save map service.
OccupancyMapMonitorMiddlewareHandle(const rclcpp::Node::SharedPtr &node, double map_resolution, const std::string &map_frame)
Constructor, reads the parameters.
OccupancyMapMonitor::Parameters getParameters() const override
Gets the parameters struct.
void createLoadMapService(OccupancyMapMonitor::MiddlewareHandle::LoadMapServiceCallback callback) override
Creates a load map service.
OccupancyMapUpdaterPtr loadOccupancyMapUpdater(const std::string &sensor_plugin) override
Loads an occupancy map updater using pluginlib.
This class contains the rcl interfaces for easier testing.
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
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
This class describes parameters that are normally provided through ROS Parameters.