Public Member Functions | Protected Member Functions | Static 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>

Public Member Functions

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

Protected Member Functions

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

Static Protected Member Functions

static void readXmlParam (XmlRpc::XmlRpcValue &params, const std::string &param_name, double *value)
 
static void readXmlParam (XmlRpc::XmlRpcValue &params, const std::string &param_name, unsigned int *value)
 

Protected Attributes

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

Detailed Description

Base class for classes which update the occupancy map.

Definition at line 90 of file occupancy_map_updater.h.

Constructor & Destructor Documentation

◆ OccupancyMapUpdater()

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

Definition at line 76 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 115 of file occupancy_map_updater.h.

◆ initialize()

virtual bool occupancy_map_monitor::OccupancyMapUpdater::initialize ( )
pure virtual

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

◆ publishDebugInformation()

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

Definition at line 125 of file occupancy_map_updater.h.

◆ readXmlParam() [1/2]

void occupancy_map_monitor::OccupancyMapUpdater::readXmlParam ( XmlRpc::XmlRpcValue params,
const std::string &  param_name,
double *  value 
)
staticprotected

Definition at line 88 of file occupancy_map_updater.cpp.

◆ readXmlParam() [2/2]

void occupancy_map_monitor::OccupancyMapUpdater::readXmlParam ( XmlRpc::XmlRpcValue params,
const std::string &  param_name,
unsigned int *  value 
)
staticprotected

Definition at line 99 of file occupancy_map_updater.cpp.

◆ setMonitor()

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

This is the first function to be called after construction.

Definition at line 82 of file occupancy_map_updater.cpp.

◆ setParams()

virtual bool occupancy_map_monitor::OccupancyMapUpdater::setParams ( XmlRpc::XmlRpcValue params)
pure virtual

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

◆ setTransformCacheCallback()

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

Definition at line 120 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 ros::Time target_time 
)
protected

Definition at line 105 of file occupancy_map_updater.cpp.

Member Data Documentation

◆ debug_info_

bool occupancy_map_monitor::OccupancyMapUpdater::debug_info_
protected

Definition at line 136 of file occupancy_map_updater.h.

◆ monitor_

OccupancyMapMonitor* occupancy_map_monitor::OccupancyMapUpdater::monitor_
protected

Definition at line 131 of file occupancy_map_updater.h.

◆ transform_cache_

ShapeTransformCache occupancy_map_monitor::OccupancyMapUpdater::transform_cache_
protected

Definition at line 135 of file occupancy_map_updater.h.

◆ transform_provider_callback_

TransformCacheProvider occupancy_map_monitor::OccupancyMapUpdater::transform_provider_callback_
protected

Definition at line 134 of file occupancy_map_updater.h.

◆ tree_

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

Definition at line 133 of file occupancy_map_updater.h.

◆ type_

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

Definition at line 132 of file occupancy_map_updater.h.


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


occupancy_map_monitor
Author(s): Ioan Sucan , Jon Binney , Suat Gedikli
autogenerated on Sat Apr 27 2024 02:25:59