Class OccupancyMapMonitor

Nested Relationships

Nested Types

Class Documentation

class OccupancyMapMonitor

Public Functions

OccupancyMapMonitor(std::unique_ptr<MiddlewareHandle> middleware_handle, const std::shared_ptr<tf2_ros::Buffer> &tf_buffer)

Occupancy map monitor constructor with the MiddlewareHandle.

Parameters:
  • middleware_handle[in] The rcl interface

  • tf_buffer[in] The tf buffer

OccupancyMapMonitor(const rclcpp::Node::SharedPtr &node, const std::shared_ptr<tf2_ros::Buffer> &tf_buffer, const std::string &map_frame = "", double map_resolution = 0.0)

Occupancy map monitor constructor with Node.

Parameters:
  • node[in] The node

  • tf_buffer[in] The tf buffer

  • map_frame[in] The map frame

  • map_resolution[in] The map resolution

OccupancyMapMonitor(const rclcpp::Node::SharedPtr &node, double map_resolution = 0.0)

Occupancy map monitor constructor with Node.

Parameters:
  • node[in] The node

  • map_resolution[in] The map resolution

~OccupancyMapMonitor()

Destroys the object.

void startMonitor()

start the monitor (will begin updating the octomap

void stopMonitor()

Stops the monitor, this also stops the updaters.

inline const collision_detection::OccMapTreePtr &getOcTreePtr()

Get a pointer to the underlying octree for this monitor. Lock the tree before reading or writing using this pointer. The value of this pointer stays the same throughout the existence of the monitor instance.

inline const collision_detection::OccMapTreeConstPtr &getOcTreePtr() const

Get a const pointer to the underlying octree for this monitor. Lock the tree before reading this pointer.

inline const std::string &getMapFrame() const

Gets the map frame (this is set either by the constor or a parameter).

Returns:

The map frame.

void setMapFrame(const std::string &frame)

Sets the map frame.

Parameters:

frame[in] The frame

inline double getMapResolution() const

Gets the map resolution.

Returns:

The map resolution.

inline const std::shared_ptr<tf2_ros::Buffer> &getTFClient() const

Gets the tf client.

Returns:

The tf client.

void addUpdater(const OccupancyMapUpdaterPtr &updater)

Adds an OccupancyMapUpdater to be monitored.

Parameters:

updater[in] The OccupancyMapUpdater

ShapeHandle excludeShape(const shapes::ShapeConstPtr &shape)

Add this shape to the set of shapes to be filtered out from the octomap.

Parameters:

shape[in] The shape to be exclueded from the updaters.

Returns:

The shape handle. Can be used to forget the shape later.

void forgetShape(ShapeHandle handle)

Forget about this shape handle and the shapes it corresponds to.

Parameters:

handle[in] The handle to forget.

inline void setUpdateCallback(const std::function<void()> &update_callback)

Set the callback to trigger when updates to the maintained octomap are received.

Parameters:

update_callback[in] The update callback function

void setTransformCacheCallback(const TransformCacheProvider &transform_cache_callback)

Sets the transform cache callback.

Parameters:

transform_cache_callback[in] The transform cache callback

void publishDebugInformation(bool flag)

Set the debug flag on the updaters.

Parameters:

flag[in] The flag

inline bool isActive() const

Determines if active.

Returns:

True if active, False otherwise.

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

struct Parameters

This class describes parameters that are normally provided through ROS Parameters.

Public Members

double map_resolution
std::string map_frame
std::vector<std::pair<std::string, std::string>> sensor_plugins