moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Types | Public Member Functions | List of all members
occupancy_map_monitor::OccupancyMapMonitor::MiddlewareHandle Class Referenceabstract

This class contains the rcl interfaces for easier testing. More...

#include <occupancy_map_monitor.h>

Inheritance diagram for occupancy_map_monitor::OccupancyMapMonitor::MiddlewareHandle:
Inheritance graph
[legend]

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 Member Functions

virtual ~MiddlewareHandle ()=default
 Destroys the object. Needed because this is pure virtual interface. More...
 
virtual Parameters getParameters () const =0
 Gets the parameters struct. More...
 
virtual OccupancyMapUpdaterPtr loadOccupancyMapUpdater (const std::string &sensor_plugin)=0
 Loads an occupancy map updater based on string. More...
 
virtual void initializeOccupancyMapUpdater (OccupancyMapUpdaterPtr occupancy_map_updater)=0
 Initializes the occupancy map updater. Needed because of interface to OccupancyMapUpdater. More...
 
virtual void createSaveMapService (SaveMapServiceCallback callback)=0
 Creates a save map service. More...
 
virtual void createLoadMapService (LoadMapServiceCallback callback)=0
 Creates a load map service. More...
 

Detailed Description

This class contains the rcl interfaces for easier testing.

Definition at line 72 of file occupancy_map_monitor.h.

Member Typedef Documentation

◆ LoadMapServiceCallback

using occupancy_map_monitor::OccupancyMapMonitor::MiddlewareHandle::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)>

Definition at line 78 of file occupancy_map_monitor.h.

◆ SaveMapServiceCallback

using occupancy_map_monitor::OccupancyMapMonitor::MiddlewareHandle::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)>

Definition at line 75 of file occupancy_map_monitor.h.

Constructor & Destructor Documentation

◆ ~MiddlewareHandle()

virtual occupancy_map_monitor::OccupancyMapMonitor::MiddlewareHandle::~MiddlewareHandle ( )
virtualdefault

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

Member Function Documentation

◆ createLoadMapService()

virtual void occupancy_map_monitor::OccupancyMapMonitor::MiddlewareHandle::createLoadMapService ( LoadMapServiceCallback  callback)
pure virtual

Creates a load map service.

Parameters
[in]callbackThe callback

Implemented in occupancy_map_monitor::OccupancyMapMonitorMiddlewareHandle.

◆ createSaveMapService()

virtual void occupancy_map_monitor::OccupancyMapMonitor::MiddlewareHandle::createSaveMapService ( SaveMapServiceCallback  callback)
pure virtual

Creates a save map service.

Parameters
[in]callbackThe callback

Implemented in occupancy_map_monitor::OccupancyMapMonitorMiddlewareHandle.

◆ getParameters()

virtual Parameters occupancy_map_monitor::OccupancyMapMonitor::MiddlewareHandle::getParameters ( ) const
pure virtual

Gets the parameters struct.

Returns
The parameters.

Implemented in occupancy_map_monitor::OccupancyMapMonitorMiddlewareHandle.

◆ initializeOccupancyMapUpdater()

virtual void occupancy_map_monitor::OccupancyMapMonitor::MiddlewareHandle::initializeOccupancyMapUpdater ( OccupancyMapUpdaterPtr  occupancy_map_updater)
pure virtual

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

Parameters
[in]occupancy_map_updaterThe occupancy map updater

Implemented in occupancy_map_monitor::OccupancyMapMonitorMiddlewareHandle.

◆ loadOccupancyMapUpdater()

virtual OccupancyMapUpdaterPtr occupancy_map_monitor::OccupancyMapMonitor::MiddlewareHandle::loadOccupancyMapUpdater ( const std::string &  sensor_plugin)
pure virtual

Loads an occupancy map updater based on string.

Parameters
[in]sensor_pluginThe sensor plugin string.
Returns
The occupancy map updater pointer.

Implemented in occupancy_map_monitor::OccupancyMapMonitorMiddlewareHandle.


The documentation for this class was generated from the following file: