Class OccupancyMapMonitor::MiddlewareHandle

Nested Relationships

This class is a nested type of Class OccupancyMapMonitor.

Inheritance Relationships

Derived Type

Class Documentation

class MiddlewareHandle

This class contains the rcl interfaces for easier testing.

Subclassed by occupancy_map_monitor::OccupancyMapMonitorMiddlewareHandle

Public Types

using SaveMapServiceCallback = 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)>
using LoadMapServiceCallback = 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)>

Public Functions

virtual ~MiddlewareHandle() = default

Destroys the object. Needed because this is pure virtual interface.

virtual Parameters getParameters() const = 0

Gets the parameters struct.

Returns:

The parameters.

virtual OccupancyMapUpdaterPtr loadOccupancyMapUpdater(const std::string &sensor_plugin) = 0

Loads an occupancy map updater based on string.

Parameters:

sensor_plugin[in] The sensor plugin string.

Returns:

The occupancy map updater pointer.

virtual void initializeOccupancyMapUpdater(OccupancyMapUpdaterPtr occupancy_map_updater) = 0

Initializes the occupancy map updater. Needed because of interface to OccupancyMapUpdater.

Parameters:

occupancy_map_updater[in] The occupancy map updater

virtual void createSaveMapService(SaveMapServiceCallback callback) = 0

Creates a save map service.

Parameters:

callback[in] The callback

virtual void createLoadMapService(LoadMapServiceCallback callback) = 0

Creates a load map service.

Parameters:

callback[in] The callback