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

#include <occupancy_map_monitor.h>

Classes

class  MiddlewareHandle
 This class contains the rcl interfaces for easier testing. More...
 
struct  Parameters
 This class describes parameters that are normally provided through ROS Parameters. More...
 

Public Member Functions

 OccupancyMapMonitor (std::unique_ptr< MiddlewareHandle > middleware_handle, const std::shared_ptr< tf2_ros::Buffer > &tf_buffer)
 Occupancy map monitor constructor with the MiddlewareHandle. More...
 
 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. More...
 
 OccupancyMapMonitor (const rclcpp::Node::SharedPtr &node, double map_resolution=0.0)
 Occupancy map monitor constructor with Node. More...
 
 ~OccupancyMapMonitor ()
 Destroys the object. More...
 
void startMonitor ()
 start the monitor (will begin updating the octomap More...
 
void stopMonitor ()
 Stops the monitor, this also stops the updaters. More...
 
const collision_detection::OccMapTreePtrgetOcTreePtr ()
 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. More...
 
const collision_detection::OccMapTreeConstPtrgetOcTreePtr () const
 Get a const pointer to the underlying octree for this monitor. Lock the tree before reading this pointer. More...
 
const std::string & getMapFrame () const
 Gets the map frame (this is set either by the constor or a parameter). More...
 
void setMapFrame (const std::string &frame)
 Sets the map frame. More...
 
double getMapResolution () const
 Gets the map resolution. More...
 
const std::shared_ptr< tf2_ros::Buffer > & getTFClient () const
 Gets the tf client. More...
 
void addUpdater (const OccupancyMapUpdaterPtr &updater)
 Adds an OccupancyMapUpdater to be monitored. More...
 
ShapeHandle excludeShape (const shapes::ShapeConstPtr &shape)
 Add this shape to the set of shapes to be filtered out from the octomap. More...
 
void forgetShape (ShapeHandle handle)
 Forget about this shape handle and the shapes it corresponds to. More...
 
void setUpdateCallback (const std::function< void()> &update_callback)
 Set the callback to trigger when updates to the maintained octomap are received. More...
 
void setTransformCacheCallback (const TransformCacheProvider &transform_cache_callback)
 Sets the transform cache callback. More...
 
void publishDebugInformation (bool flag)
 Set the debug flag on the updaters. More...
 
bool isActive () const
 Determines if active. More...
 

Detailed Description

Definition at line 56 of file occupancy_map_monitor.h.

Constructor & Destructor Documentation

◆ OccupancyMapMonitor() [1/3]

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

Occupancy map monitor constructor with the MiddlewareHandle.

Parameters
[in]middleware_handleThe rcl interface
[in]tf_bufferThe tf buffer

Definition at line 71 of file occupancy_map_monitor.cpp.

◆ OccupancyMapMonitor() [2/3]

occupancy_map_monitor::OccupancyMapMonitor::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
[in]nodeThe node
[in]tf_bufferThe tf buffer
[in]map_frameThe map frame
[in]map_resolutionThe map resolution

Definition at line 63 of file occupancy_map_monitor.cpp.

◆ OccupancyMapMonitor() [3/3]

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

Occupancy map monitor constructor with Node.

Parameters
[in]nodeThe node
[in]map_resolutionThe map resolution

Definition at line 58 of file occupancy_map_monitor.cpp.

◆ ~OccupancyMapMonitor()

occupancy_map_monitor::OccupancyMapMonitor::~OccupancyMapMonitor ( )

Destroys the object.

Definition at line 330 of file occupancy_map_monitor.cpp.

Member Function Documentation

◆ addUpdater()

void occupancy_map_monitor::OccupancyMapMonitor::addUpdater ( const OccupancyMapUpdaterPtr &  updater)

Adds an OccupancyMapUpdater to be monitored.

Parameters
[in]updaterThe OccupancyMapUpdater

Definition at line 148 of file occupancy_map_monitor.cpp.

◆ excludeShape()

ShapeHandle occupancy_map_monitor::OccupancyMapMonitor::excludeShape ( const shapes::ShapeConstPtr &  shape)

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

Parameters
[in]shapeThe shape to be exclueded from the updaters.
Returns
The shape handle. Can be used to forget the shape later.

Definition at line 196 of file occupancy_map_monitor.cpp.

◆ forgetShape()

void occupancy_map_monitor::OccupancyMapMonitor::forgetShape ( ShapeHandle  handle)

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

Parameters
[in]handleThe handle to forget.

Definition at line 216 of file occupancy_map_monitor.cpp.

◆ getMapFrame()

const std::string& occupancy_map_monitor::OccupancyMapMonitor::getMapFrame ( ) const
inline

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

Returns
The map frame.

Definition at line 187 of file occupancy_map_monitor.h.

Here is the caller graph for this function:

◆ getMapResolution()

double occupancy_map_monitor::OccupancyMapMonitor::getMapResolution ( ) const
inline

Gets the map resolution.

Returns
The map resolution.

Definition at line 204 of file occupancy_map_monitor.h.

◆ getOcTreePtr() [1/2]

const collision_detection::OccMapTreePtr& occupancy_map_monitor::OccupancyMapMonitor::getOcTreePtr ( )
inline

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.

Definition at line 170 of file occupancy_map_monitor.h.

Here is the caller graph for this function:

◆ getOcTreePtr() [2/2]

const collision_detection::OccMapTreeConstPtr& occupancy_map_monitor::OccupancyMapMonitor::getOcTreePtr ( ) const
inline

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

Definition at line 177 of file occupancy_map_monitor.h.

◆ getTFClient()

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

Gets the tf client.

Returns
The tf client.

Definition at line 214 of file occupancy_map_monitor.h.

Here is the caller graph for this function:

◆ isActive()

bool occupancy_map_monitor::OccupancyMapMonitor::isActive ( ) const
inline

Determines if active.

Returns
True if active, False otherwise.

Definition at line 271 of file occupancy_map_monitor.h.

◆ publishDebugInformation()

void occupancy_map_monitor::OccupancyMapMonitor::publishDebugInformation ( bool  flag)

Set the debug flag on the updaters.

Parameters
[in]flagThe flag

Definition at line 183 of file occupancy_map_monitor.cpp.

◆ setMapFrame()

void occupancy_map_monitor::OccupancyMapMonitor::setMapFrame ( const std::string &  frame)

Sets the map frame.

Parameters
[in]frameThe frame

Definition at line 190 of file occupancy_map_monitor.cpp.

◆ setTransformCacheCallback()

void occupancy_map_monitor::OccupancyMapMonitor::setTransformCacheCallback ( const TransformCacheProvider transform_cache_callback)

Sets the transform cache callback.

Parameters
[in]transform_cache_callbackThe transform cache callback

Definition at line 234 of file occupancy_map_monitor.cpp.

◆ setUpdateCallback()

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

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

Parameters
[in]update_callbackThe update callback function

Definition at line 247 of file occupancy_map_monitor.h.

Here is the caller graph for this function:

◆ startMonitor()

void occupancy_map_monitor::OccupancyMapMonitor::startMonitor ( )

start the monitor (will begin updating the octomap

Definition at line 315 of file occupancy_map_monitor.cpp.

◆ stopMonitor()

void occupancy_map_monitor::OccupancyMapMonitor::stopMonitor ( )

Stops the monitor, this also stops the updaters.

Definition at line 323 of file occupancy_map_monitor.cpp.


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