40 #include <pluginlib/class_loader.hpp>
41 #include <rclcpp/logger.hpp>
42 #include <rclcpp/logging.hpp>
43 #include <rclcpp/parameter_value.hpp>
53 static const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"moveit.ros.occupancy_map_monitor.middleware_handle");
57 double map_resolution,
58 const std::string& map_frame)
59 : node_{ node }, parameters_{ map_resolution, map_frame, {} }
63 updater_plugin_loader_ = std::make_unique<pluginlib::ClassLoader<OccupancyMapUpdater>>(
64 "moveit_ros_occupancy_map_monitor",
"occupancy_map_monitor::OccupancyMapUpdater");
66 catch (pluginlib::PluginlibException& ex)
68 RCLCPP_FATAL_STREAM(LOGGER,
"Exception while creating octomap updater plugin loader " << ex.what());
72 if (parameters_.map_resolution <= std::numeric_limits<double>::epsilon())
74 if (!node_->get_parameter(
"octomap_resolution", parameters_.map_resolution))
76 parameters_.map_resolution = 0.1;
77 RCLCPP_WARN(LOGGER,
"Resolution not specified for Octomap. Assuming resolution = %g instead",
78 parameters_.map_resolution);
82 if (parameters_.map_frame.empty())
84 node_->get_parameter(
"octomap_frame", parameters_.map_frame);
85 if (parameters_.map_frame.empty())
87 RCLCPP_ERROR(LOGGER,
"No 'octomap_frame' parameter defined for octomap updates");
91 std::vector<std::string> sensor_names;
92 if (!node_->get_parameter(
"sensors", sensor_names))
94 RCLCPP_ERROR(LOGGER,
"No 3D sensor plugin(s) defined for octomap updates");
96 else if (sensor_names.empty())
98 RCLCPP_ERROR(LOGGER,
"List of sensors is empty!");
101 for (
const auto& sensor_name : sensor_names)
103 std::string sensor_plugin =
"";
104 if (!node_->get_parameter(sensor_name +
".sensor_plugin", sensor_plugin))
106 RCLCPP_ERROR(LOGGER,
"No sensor plugin specified for octomap updater %s; ignoring.", sensor_name.c_str());
109 if (sensor_plugin.empty() || sensor_plugin[0] ==
'~')
111 RCLCPP_INFO_STREAM(LOGGER,
"Skipping octomap updater plugin '" << sensor_plugin <<
"'");
116 parameters_.sensor_plugins.emplace_back(sensor_name, sensor_plugin);
126 OccupancyMapUpdaterPtr OccupancyMapMonitorMiddlewareHandle::loadOccupancyMapUpdater(
const std::string& sensor_plugin)
130 return updater_plugin_loader_->createUniqueInstance(sensor_plugin);
132 catch (pluginlib::PluginlibException& exception)
134 RCLCPP_ERROR_STREAM(LOGGER,
"Exception while loading octomap updater '" << sensor_plugin
135 <<
"': " << exception.what() <<
'\n');
140 void OccupancyMapMonitorMiddlewareHandle::initializeOccupancyMapUpdater(OccupancyMapUpdaterPtr occupancy_map_updater)
142 if (!occupancy_map_updater->initialize(node_))
144 RCLCPP_ERROR(LOGGER,
"Unable to initialize map updater of type %s", occupancy_map_updater->getType().c_str());
148 void OccupancyMapMonitorMiddlewareHandle::createSaveMapService(
151 save_map_srv_ = node_->create_service<moveit_msgs::srv::SaveMap>(
"save_map", callback);
154 void OccupancyMapMonitorMiddlewareHandle::createLoadMapService(
157 load_map_srv_ = node_->create_service<moveit_msgs::srv::LoadMap>(
"load_map", callback);
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
This class describes parameters that are normally provided through ROS Parameters.