moveit2
The MoveIt Motion Planning Framework for ROS 2.
occupancy_map_monitor_middleware_handle.cpp
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 
39 
40 #include <pluginlib/class_loader.hpp>
41 #include <rclcpp/logger.hpp>
42 #include <rclcpp/logging.hpp>
43 #include <rclcpp/parameter_value.hpp>
44 #include <memory>
45 #include <string>
46 #include <utility>
47 #include <vector>
48 
49 namespace occupancy_map_monitor
50 {
51 namespace
52 {
53 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ros.occupancy_map_monitor.middleware_handle");
54 }
55 
57  double map_resolution,
58  const std::string& map_frame)
59  : node_{ node }, parameters_{ map_resolution, map_frame, {} }
60 {
61  try
62  {
63  updater_plugin_loader_ = std::make_unique<pluginlib::ClassLoader<OccupancyMapUpdater>>(
64  "moveit_ros_occupancy_map_monitor", "occupancy_map_monitor::OccupancyMapUpdater");
65  }
66  catch (pluginlib::PluginlibException& ex)
67  {
68  RCLCPP_FATAL_STREAM(LOGGER, "Exception while creating octomap updater plugin loader " << ex.what());
69  throw ex;
70  }
71 
72  if (parameters_.map_resolution <= std::numeric_limits<double>::epsilon())
73  {
74  if (!node_->get_parameter("octomap_resolution", parameters_.map_resolution))
75  {
76  parameters_.map_resolution = 0.1;
77  RCLCPP_WARN(LOGGER, "Resolution not specified for Octomap. Assuming resolution = %g instead",
78  parameters_.map_resolution);
79  }
80  }
81 
82  if (parameters_.map_frame.empty())
83  {
84  node_->get_parameter("octomap_frame", parameters_.map_frame);
85  if (parameters_.map_frame.empty())
86  {
87  RCLCPP_ERROR(LOGGER, "No 'octomap_frame' parameter defined for octomap updates");
88  }
89  }
90 
91  std::vector<std::string> sensor_names;
92  if (!node_->get_parameter("sensors", sensor_names))
93  {
94  RCLCPP_ERROR(LOGGER, "No 3D sensor plugin(s) defined for octomap updates");
95  }
96  else if (sensor_names.empty())
97  {
98  RCLCPP_ERROR(LOGGER, "List of sensors is empty!");
99  }
100 
101  for (const auto& sensor_name : sensor_names)
102  {
103  std::string sensor_plugin = "";
104  if (!node_->get_parameter(sensor_name + ".sensor_plugin", sensor_plugin))
105  {
106  RCLCPP_ERROR(LOGGER, "No sensor plugin specified for octomap updater %s; ignoring.", sensor_name.c_str());
107  }
108 
109  if (sensor_plugin.empty() || sensor_plugin[0] == '~')
110  {
111  RCLCPP_INFO_STREAM(LOGGER, "Skipping octomap updater plugin '" << sensor_plugin << "'");
112  continue;
113  }
114  else
115  {
116  parameters_.sensor_plugins.emplace_back(sensor_name, sensor_plugin);
117  }
118  }
119 }
120 
121 OccupancyMapMonitor::Parameters OccupancyMapMonitorMiddlewareHandle::getParameters() const
122 {
123  return parameters_;
124 }
125 
126 OccupancyMapUpdaterPtr OccupancyMapMonitorMiddlewareHandle::loadOccupancyMapUpdater(const std::string& sensor_plugin)
127 {
128  try
129  {
130  return updater_plugin_loader_->createUniqueInstance(sensor_plugin);
131  }
132  catch (pluginlib::PluginlibException& exception)
133  {
134  RCLCPP_ERROR_STREAM(LOGGER, "Exception while loading octomap updater '" << sensor_plugin
135  << "': " << exception.what() << '\n');
136  }
137  return nullptr;
138 }
139 
140 void OccupancyMapMonitorMiddlewareHandle::initializeOccupancyMapUpdater(OccupancyMapUpdaterPtr occupancy_map_updater)
141 {
142  if (!occupancy_map_updater->initialize(node_))
143  {
144  RCLCPP_ERROR(LOGGER, "Unable to initialize map updater of type %s", occupancy_map_updater->getType().c_str());
145  }
146 }
147 
148 void OccupancyMapMonitorMiddlewareHandle::createSaveMapService(
150 {
151  save_map_srv_ = node_->create_service<moveit_msgs::srv::SaveMap>("save_map", callback);
152 }
153 
154 void OccupancyMapMonitorMiddlewareHandle::createLoadMapService(
156 {
157  load_map_srv_ = node_->create_service<moveit_msgs::srv::LoadMap>("load_map", callback);
158 }
159 
160 } // namespace occupancy_map_monitor
OccupancyMapMonitorMiddlewareHandle(const rclcpp::Node::SharedPtr &node, double map_resolution, const std::string &map_frame)
Constructor, reads the parameters.
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
const rclcpp::Logger LOGGER
Definition: async_test.h:31
This class describes parameters that are normally provided through ROS Parameters.