Class OccupancyMapMonitorMiddlewareHandle
Inheritance Relationships
Base Type
public occupancy_map_monitor::OccupancyMapMonitor::MiddlewareHandle
(Class OccupancyMapMonitor::MiddlewareHandle)
Class Documentation
-
class OccupancyMapMonitorMiddlewareHandle : public occupancy_map_monitor::OccupancyMapMonitor::MiddlewareHandle
This class contains the ros interfaces for OccupancyMapMontior.
Public Functions
Constructor, reads the parameters.
- Parameters:
node – [in] The ros node
map_resolution – [in] The map resolution, if not > 0 read from a parameter
map_frame – [in] The map frame, if not empty read from a parameter
-
virtual OccupancyMapMonitor::Parameters getParameters() const override
Gets the parameters struct.
- Returns:
The parameters.
-
virtual OccupancyMapUpdaterPtr loadOccupancyMapUpdater(const std::string &sensor_plugin) override
Loads an occupancy map updater using pluginlib.
- Parameters:
sensor_plugin – [in] The sensor plugin type string
- Returns:
The occupancy map updater pointer.
-
virtual void initializeOccupancyMapUpdater(OccupancyMapUpdaterPtr occupancy_map_updater) override
Initializes the occupancy map updater. This must be called because of the interface of OccupancyMapUpdater.
- Parameters:
occupancy_map_updater – [in] The occupancy map updater
-
virtual void createSaveMapService(OccupancyMapMonitor::MiddlewareHandle::SaveMapServiceCallback callback) override
Creates a save map service.
- Parameters:
callback – [in] The callback closure
-
virtual void createLoadMapService(OccupancyMapMonitor::MiddlewareHandle::LoadMapServiceCallback callback) override
Creates a load map service.
- Parameters:
callback – [in] The callback closure