42 #include <pluginlib/class_loader.hpp>
43 #include <rclcpp/rclcpp.hpp>
66 const std::string& map_frame);
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_;
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.