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. | |
OccupancyMapUpdater (const std::string &type) | |
void | publishDebugInformation (bool flag) |
void | setMonitor (OccupancyMapMonitor *monitor) |
This is the first function to be called after construction. | |
virtual bool | setParams (XmlRpc::XmlRpcValue ¶ms)=0 |
Set updater params using struct that comes from parsing a yaml string. This must be called after setMonitor() | |
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 ¶ms, const std::string ¶m_name, double *value) |
static void | readXmlParam (XmlRpc::XmlRpcValue ¶ms, const std::string ¶m_name, unsigned int *value) |
Protected Attributes | |
bool | debug_info_ |
OccupancyMapMonitor * | monitor_ |
ShapeTransformCache | transform_cache_ |
TransformCacheProvider | transform_provider_callback_ |
OccMapTreePtr | tree_ |
std::string | type_ |
Base class for classes which update the occupancy map.
Definition at line 58 of file occupancy_map_updater.h.
occupancy_map_monitor::OccupancyMapUpdater::OccupancyMapUpdater | ( | const std::string & | type | ) |
Definition at line 43 of file occupancy_map_updater.cpp.
Definition at line 47 of file occupancy_map_updater.cpp.
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 82 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 92 of file occupancy_map_updater.h.
void occupancy_map_monitor::OccupancyMapUpdater::readXmlParam | ( | XmlRpc::XmlRpcValue & | params, |
const std::string & | param_name, | ||
double * | value | ||
) | [static, protected] |
Definition at line 57 of file occupancy_map_updater.cpp.
void occupancy_map_monitor::OccupancyMapUpdater::readXmlParam | ( | XmlRpc::XmlRpcValue & | params, |
const std::string & | param_name, | ||
unsigned int * | value | ||
) | [static, protected] |
Definition at line 68 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 51 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 87 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 74 of file occupancy_map_updater.cpp.
bool occupancy_map_monitor::OccupancyMapUpdater::debug_info_ [protected] |
Definition at line 104 of file occupancy_map_updater.h.
Definition at line 99 of file occupancy_map_updater.h.
Definition at line 103 of file occupancy_map_updater.h.
TransformCacheProvider occupancy_map_monitor::OccupancyMapUpdater::transform_provider_callback_ [protected] |
Definition at line 102 of file occupancy_map_updater.h.
Definition at line 101 of file occupancy_map_updater.h.
std::string occupancy_map_monitor::OccupancyMapUpdater::type_ [protected] |
Definition at line 100 of file occupancy_map_updater.h.