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