moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
occupancy_map_monitor::OccupancyMapUpdater Class Referenceabstract

Base class for classes which update the occupancy map. More...

#include <occupancy_map_updater.h>

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

Public Member Functions

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

Protected Member Functions

bool updateTransformCache (const std::string &target_frame, const rclcpp::Time &target_time)
 

Protected Attributes

OccupancyMapMonitormonitor_
 
std::string type_
 
collision_detection::OccMapTreePtr tree_
 
TransformCacheProvider transform_provider_callback_
 
ShapeTransformCache transform_cache_
 
bool debug_info_
 

Detailed Description

Base class for classes which update the occupancy map.

Definition at line 65 of file occupancy_map_updater.h.

Constructor & Destructor Documentation

◆ OccupancyMapUpdater()

occupancy_map_monitor::OccupancyMapUpdater::OccupancyMapUpdater ( const std::string &  type)

Definition at line 55 of file occupancy_map_updater.cpp.

◆ ~OccupancyMapUpdater()

occupancy_map_monitor::OccupancyMapUpdater::~OccupancyMapUpdater ( )
virtualdefault

Member Function Documentation

◆ excludeShape()

virtual ShapeHandle occupancy_map_monitor::OccupancyMapUpdater::excludeShape ( const shapes::ShapeConstPtr &  shape)
pure virtual

◆ forgetShape()

virtual void occupancy_map_monitor::OccupancyMapUpdater::forgetShape ( ShapeHandle  handle)
pure virtual

◆ getType()

const std::string & occupancy_map_monitor::OccupancyMapUpdater::getType ( ) const
inline

Definition at line 90 of file occupancy_map_updater.h.

◆ initialize()

virtual bool occupancy_map_monitor::OccupancyMapUpdater::initialize ( const rclcpp::Node::SharedPtr &  node)
pure virtual

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

Implemented in occupancy_map_monitor::DepthImageOctomapUpdater, and occupancy_map_monitor::PointCloudOctomapUpdater.

◆ publishDebugInformation()

void occupancy_map_monitor::OccupancyMapUpdater::publishDebugInformation ( bool  flag)
inline

Definition at line 100 of file occupancy_map_updater.h.

◆ setMonitor()

void occupancy_map_monitor::OccupancyMapUpdater::setMonitor ( OccupancyMapMonitor monitor)

This is the first function to be called after construction.

Definition at line 61 of file occupancy_map_updater.cpp.

Here is the call graph for this function:

◆ setParams()

virtual bool occupancy_map_monitor::OccupancyMapUpdater::setParams ( const std::string &  name_space)
pure virtual

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

Implemented in occupancy_map_monitor::DepthImageOctomapUpdater, and occupancy_map_monitor::PointCloudOctomapUpdater.

◆ setTransformCacheCallback()

void occupancy_map_monitor::OccupancyMapUpdater::setTransformCacheCallback ( const TransformCacheProvider transform_callback)
inline

Definition at line 95 of file occupancy_map_updater.h.

◆ start()

virtual void occupancy_map_monitor::OccupancyMapUpdater::start ( )
pure virtual

◆ stop()

virtual void occupancy_map_monitor::OccupancyMapUpdater::stop ( )
pure virtual

◆ updateTransformCache()

bool occupancy_map_monitor::OccupancyMapUpdater::updateTransformCache ( const std::string &  target_frame,
const rclcpp::Time &  target_time 
)
protected

Definition at line 87 of file occupancy_map_updater.cpp.

Member Data Documentation

◆ debug_info_

bool occupancy_map_monitor::OccupancyMapUpdater::debug_info_
protected

Definition at line 111 of file occupancy_map_updater.h.

◆ monitor_

OccupancyMapMonitor* occupancy_map_monitor::OccupancyMapUpdater::monitor_
protected

Definition at line 106 of file occupancy_map_updater.h.

◆ transform_cache_

ShapeTransformCache occupancy_map_monitor::OccupancyMapUpdater::transform_cache_
protected

Definition at line 110 of file occupancy_map_updater.h.

◆ transform_provider_callback_

TransformCacheProvider occupancy_map_monitor::OccupancyMapUpdater::transform_provider_callback_
protected

Definition at line 109 of file occupancy_map_updater.h.

◆ tree_

collision_detection::OccMapTreePtr occupancy_map_monitor::OccupancyMapUpdater::tree_
protected

Definition at line 108 of file occupancy_map_updater.h.

◆ type_

std::string occupancy_map_monitor::OccupancyMapUpdater::type_
protected

Definition at line 107 of file occupancy_map_updater.h.


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