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>

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

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_
 
OccMapTreePtr tree_
 
std::string type_
 

Detailed Description

Base class for classes which update the occupancy map.

Definition at line 62 of file occupancy_map_updater.h.

Constructor & Destructor Documentation

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

Definition at line 42 of file occupancy_map_updater.cpp.

occupancy_map_monitor::OccupancyMapUpdater::~OccupancyMapUpdater ( )
virtual

Definition at line 46 of file occupancy_map_updater.cpp.

Member Function Documentation

virtual ShapeHandle occupancy_map_monitor::OccupancyMapUpdater::excludeShape ( const shapes::ShapeConstPtr shape)
pure virtual
virtual void occupancy_map_monitor::OccupancyMapUpdater::forgetShape ( ShapeHandle  handle)
pure virtual
const std::string& occupancy_map_monitor::OccupancyMapUpdater::getType ( ) const
inline

Definition at line 87 of file occupancy_map_updater.h.

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.

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

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

Definition at line 97 of file occupancy_map_updater.h.

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

Definition at line 56 of file occupancy_map_updater.cpp.

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

Definition at line 67 of file occupancy_map_updater.cpp.

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

This is the first function to be called after construction.

Definition at line 50 of file occupancy_map_updater.cpp.

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()

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

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

Definition at line 92 of file occupancy_map_updater.h.

virtual void occupancy_map_monitor::OccupancyMapUpdater::start ( )
pure virtual
virtual void occupancy_map_monitor::OccupancyMapUpdater::stop ( )
pure virtual
bool occupancy_map_monitor::OccupancyMapUpdater::updateTransformCache ( const std::string &  target_frame,
const ros::Time target_time 
)
protected

Definition at line 73 of file occupancy_map_updater.cpp.

Member Data Documentation

bool occupancy_map_monitor::OccupancyMapUpdater::debug_info_
protected

Definition at line 108 of file occupancy_map_updater.h.

OccupancyMapMonitor* occupancy_map_monitor::OccupancyMapUpdater::monitor_
protected

Definition at line 103 of file occupancy_map_updater.h.

ShapeTransformCache occupancy_map_monitor::OccupancyMapUpdater::transform_cache_
protected

Definition at line 107 of file occupancy_map_updater.h.

TransformCacheProvider occupancy_map_monitor::OccupancyMapUpdater::transform_provider_callback_
protected

Definition at line 106 of file occupancy_map_updater.h.

OccMapTreePtr occupancy_map_monitor::OccupancyMapUpdater::tree_
protected

Definition at line 105 of file occupancy_map_updater.h.

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

Definition at line 104 of file occupancy_map_updater.h.


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


perception
Author(s): Ioan Sucan , Jon Binney , Suat Gedikli
autogenerated on Sun Oct 18 2020 13:17:23