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

#include <depth_image_octomap_updater.h>

Inheritance diagram for occupancy_map_monitor::DepthImageOctomapUpdater:
Inheritance graph
[legend]
Collaboration diagram for occupancy_map_monitor::DepthImageOctomapUpdater:
Collaboration graph
[legend]

Public Member Functions

 DepthImageOctomapUpdater ()
 
 ~DepthImageOctomapUpdater () override
 
bool setParams (const std::string &name_space) override
 Set updater params using struct that comes from parsing a yaml string. This must be called after setMonitor() More...
 
bool initialize (const rclcpp::Node::SharedPtr &node) override
 Do any necessary setup (subscribe to ros topics, etc.). This call assumes setMonitor() and setParams() have been previously called. More...
 
void start () override
 
void stop () override
 
ShapeHandle excludeShape (const shapes::ShapeConstPtr &shape) override
 
void forgetShape (ShapeHandle handle) override
 
- Public Member Functions inherited from occupancy_map_monitor::OccupancyMapUpdater
 OccupancyMapUpdater (const std::string &type)
 
virtual ~OccupancyMapUpdater ()
 
void setMonitor (OccupancyMapMonitor *monitor)
 This is the first function to be called after construction. More...
 
const std::string & getType () const
 
void setTransformCacheCallback (const TransformCacheProvider &transform_callback)
 
void publishDebugInformation (bool flag)
 

Additional Inherited Members

- Protected Member Functions inherited from occupancy_map_monitor::OccupancyMapUpdater
bool updateTransformCache (const std::string &target_frame, const rclcpp::Time &target_time)
 
- Protected Attributes inherited from occupancy_map_monitor::OccupancyMapUpdater
OccupancyMapMonitormonitor_
 
std::string type_
 
collision_detection::OccMapTreePtr tree_
 
TransformCacheProvider transform_provider_callback_
 
ShapeTransformCache transform_cache_
 
bool debug_info_
 

Detailed Description

Definition at line 50 of file depth_image_octomap_updater.h.

Constructor & Destructor Documentation

◆ DepthImageOctomapUpdater()

occupancy_map_monitor::DepthImageOctomapUpdater::DepthImageOctomapUpdater ( )

Definition at line 53 of file depth_image_octomap_updater.cpp.

◆ ~DepthImageOctomapUpdater()

occupancy_map_monitor::DepthImageOctomapUpdater::~DepthImageOctomapUpdater ( )
override

Definition at line 78 of file depth_image_octomap_updater.cpp.

Member Function Documentation

◆ excludeShape()

mesh_filter::MeshHandle occupancy_map_monitor::DepthImageOctomapUpdater::excludeShape ( const shapes::ShapeConstPtr &  shape)
overridevirtual

◆ forgetShape()

void occupancy_map_monitor::DepthImageOctomapUpdater::forgetShape ( ShapeHandle  handle)
overridevirtual

◆ initialize()

bool occupancy_map_monitor::DepthImageOctomapUpdater::initialize ( const rclcpp::Node::SharedPtr &  node)
overridevirtual

Do any necessary setup (subscribe to ros topics, etc.). This call assumes setMonitor() and setParams() have been previously called.

Implements occupancy_map_monitor::OccupancyMapUpdater.

Definition at line 108 of file depth_image_octomap_updater.cpp.

Here is the call graph for this function:

◆ setParams()

bool occupancy_map_monitor::DepthImageOctomapUpdater::setParams ( const std::string &  name_space)
overridevirtual

Set updater params using struct that comes from parsing a yaml string. This must be called after setMonitor()

Implements occupancy_map_monitor::OccupancyMapUpdater.

Definition at line 83 of file depth_image_octomap_updater.cpp.

◆ start()

void occupancy_map_monitor::DepthImageOctomapUpdater::start ( )
overridevirtual

◆ stop()

void occupancy_map_monitor::DepthImageOctomapUpdater::stop ( )
overridevirtual

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