moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#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. | |
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. | |
OccupancyMapMonitor (const rclcpp::Node::SharedPtr &node, double map_resolution=0.0) | |
Occupancy map monitor constructor with Node. | |
~OccupancyMapMonitor () | |
Destroys the object. | |
void | startMonitor () |
start the monitor (will begin updating the octomap | |
void | stopMonitor () |
Stops the monitor, this also stops the updaters. | |
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. | |
const collision_detection::OccMapTreeConstPtr & | getOcTreePtr () const |
Get a const pointer to the underlying octree for this monitor. Lock the tree before reading this pointer. | |
const std::string & | getMapFrame () const |
Gets the map frame (this is set either by the constor or a parameter). | |
void | setMapFrame (const std::string &frame) |
Sets the map frame. | |
double | getMapResolution () const |
Gets the map resolution. | |
const std::shared_ptr< tf2_ros::Buffer > & | getTFClient () const |
Gets the tf client. | |
void | addUpdater (const OccupancyMapUpdaterPtr &updater) |
Adds an OccupancyMapUpdater to be monitored. | |
ShapeHandle | excludeShape (const shapes::ShapeConstPtr &shape) |
Add this shape to the set of shapes to be filtered out from the octomap. | |
void | forgetShape (ShapeHandle handle) |
Forget about this shape handle and the shapes it corresponds to. | |
void | setUpdateCallback (const std::function< void()> &update_callback) |
Set the callback to trigger when updates to the maintained octomap are received. | |
void | setTransformCacheCallback (const TransformCacheProvider &transform_cache_callback) |
Sets the transform cache callback. | |
void | publishDebugInformation (bool flag) |
Set the debug flag on the updaters. | |
bool | isActive () const |
Determines if active. | |
Definition at line 56 of file occupancy_map_monitor.h.
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.
[in] | middleware_handle | The rcl interface |
[in] | tf_buffer | The tf buffer |
Definition at line 68 of file occupancy_map_monitor.cpp.
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.
[in] | node | The node |
[in] | tf_buffer | The tf buffer |
[in] | map_frame | The map frame |
[in] | map_resolution | The map resolution |
Definition at line 60 of file occupancy_map_monitor.cpp.
occupancy_map_monitor::OccupancyMapMonitor::OccupancyMapMonitor | ( | const rclcpp::Node::SharedPtr & | node, |
double | map_resolution = 0.0 |
||
) |
Occupancy map monitor constructor with Node.
[in] | node | The node |
[in] | map_resolution | The map resolution |
Definition at line 55 of file occupancy_map_monitor.cpp.
occupancy_map_monitor::OccupancyMapMonitor::~OccupancyMapMonitor | ( | ) |
Destroys the object.
Definition at line 337 of file occupancy_map_monitor.cpp.
void occupancy_map_monitor::OccupancyMapMonitor::addUpdater | ( | const OccupancyMapUpdaterPtr & | updater | ) |
Adds an OccupancyMapUpdater to be monitored.
[in] | updater | The OccupancyMapUpdater |
Definition at line 146 of file occupancy_map_monitor.cpp.
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.
[in] | shape | The shape to be exclueded from the updaters. |
Definition at line 196 of file occupancy_map_monitor.cpp.
void occupancy_map_monitor::OccupancyMapMonitor::forgetShape | ( | ShapeHandle | handle | ) |
Forget about this shape handle and the shapes it corresponds to.
[in] | handle | The handle to forget. |
Definition at line 216 of file occupancy_map_monitor.cpp.
|
inline |
Gets the map frame (this is set either by the constor or a parameter).
Definition at line 187 of file occupancy_map_monitor.h.
|
inline |
Gets the map resolution.
Definition at line 204 of file occupancy_map_monitor.h.
|
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.
|
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.
|
inline |
Gets the tf client.
Definition at line 214 of file occupancy_map_monitor.h.
|
inline |
Determines if active.
Definition at line 271 of file occupancy_map_monitor.h.
void occupancy_map_monitor::OccupancyMapMonitor::publishDebugInformation | ( | bool | flag | ) |
Set the debug flag on the updaters.
[in] | flag | The flag |
Definition at line 183 of file occupancy_map_monitor.cpp.
void occupancy_map_monitor::OccupancyMapMonitor::setMapFrame | ( | const std::string & | frame | ) |
Sets the map frame.
[in] | frame | The frame |
Definition at line 190 of file occupancy_map_monitor.cpp.
void occupancy_map_monitor::OccupancyMapMonitor::setTransformCacheCallback | ( | const TransformCacheProvider & | transform_cache_callback | ) |
Sets the transform cache callback.
[in] | transform_cache_callback | The transform cache callback |
Definition at line 234 of file occupancy_map_monitor.cpp.
|
inline |
Set the callback to trigger when updates to the maintained octomap are received.
[in] | update_callback | The update callback function |
Definition at line 247 of file occupancy_map_monitor.h.
void occupancy_map_monitor::OccupancyMapMonitor::startMonitor | ( | ) |
start the monitor (will begin updating the octomap
Definition at line 322 of file occupancy_map_monitor.cpp.
void occupancy_map_monitor::OccupancyMapMonitor::stopMonitor | ( | ) |
Stops the monitor, this also stops the updaters.
Definition at line 330 of file occupancy_map_monitor.cpp.