#include <costmap_converter_interface.h>
Public Member Functions | |
void | convertStaticObstacles () |
Apply the underlying plugin for static costmap conversion. More... | |
PolygonContainerConstPtr | getStaticPolygons () |
Get the converted polygons from the underlying plugin. More... | |
void | loadStaticCostmapConverterPlugin (const std::string &plugin_name, ros::NodeHandle nh_parent) |
Load underlying static costmap conversion plugin via plugin-loader. More... | |
void | setStaticCostmap (boost::shared_ptr< costmap_2d::Costmap2D > static_costmap) |
Set the costmap for the underlying plugin. More... | |
void | setStaticCostmapConverterPlugin (boost::shared_ptr< BaseCostmapToPolygons > static_costmap_converter) |
Set the underlying plugin for subsequent costmap conversion of the static background of the costmap. More... | |
bool | stackedCostmapConversion () |
Determines whether an additional plugin for subsequent costmap conversion is specified. More... | |
Public Member Functions inherited from costmap_converter::BaseCostmapToPolygons | |
virtual void | compute ()=0 |
This method performs the actual work (conversion of the costmap to polygons) More... | |
virtual ObstacleArrayConstPtr | getObstacles () |
Get a shared instance of the current obstacle container If this method is not overwritten by the underlying plugin, the obstacle container just imports getPolygons(). More... | |
virtual PolygonContainerConstPtr | getPolygons () |
Get a shared instance of the current polygon container. More... | |
virtual void | initialize (ros::NodeHandle nh)=0 |
Initialize the plugin. More... | |
virtual void | setCostmap2D (costmap_2d::Costmap2D *costmap)=0 |
Pass a pointer to the costap to the plugin. More... | |
virtual void | setOdomTopic (const std::string &odom_topic) |
Set name of robot's odometry topic. More... | |
void | startWorker (ros::Rate rate, costmap_2d::Costmap2D *costmap, bool spin_thread=false) |
Instantiate a worker that repeatedly coverts the most recent costmap to polygons. The worker is implemented as a timer event that is invoked at a specific rate . The passed costmap pointer must be valid at the complete time and must be lockable. By specifying the argument spin_thread the timer event is invoked in a separate thread and callback queue or otherwise it is called from the global callback queue (of the node in which the plugin is used). More... | |
void | stopWorker () |
Stop the worker that repeatedly converts the costmap to polygons. More... | |
virtual void | updateCostmap2D ()=0 |
Get updated data from the previously set Costmap2D. More... | |
virtual | ~BaseCostmapToPolygons () |
Destructor. More... | |
Protected Member Functions | |
BaseCostmapToDynamicObstacles () | |
Protected constructor that should be called by subclasses. More... | |
Protected Member Functions inherited from costmap_converter::BaseCostmapToPolygons | |
BaseCostmapToPolygons () | |
Protected constructor that should be called by subclasses. More... | |
void | spinThread () |
Blocking method that checks for new timer events (active if startWorker() is called with spin_thread enabled) More... | |
void | workerCallback (const ros::TimerEvent &) |
The callback of the worker that performs the actual work (updating the costmap and converting it to polygons) More... | |
Private Attributes | |
pluginlib::ClassLoader< BaseCostmapToPolygons > | static_converter_loader_ |
boost::shared_ptr< BaseCostmapToPolygons > | static_costmap_converter_ |
Definition at line 272 of file costmap_converter_interface.h.
|
inlineprotected |
Protected constructor that should be called by subclasses.
Definition at line 356 of file costmap_converter_interface.h.
|
inline |
Apply the underlying plugin for static costmap conversion.
Definition at line 325 of file costmap_converter_interface.h.
|
inline |
Get the converted polygons from the underlying plugin.
Definition at line 334 of file costmap_converter_interface.h.
|
inline |
Load underlying static costmap conversion plugin via plugin-loader.
plugin_name | Exact class name of the plugin to be loaded, e.g. costmap_converter::CostmapToPolygonsDBSMCCH |
nh_parent | NodeHandle which is extended by the namespace of the static conversion plugin |
Definition at line 282 of file costmap_converter_interface.h.
|
inline |
Set the costmap for the underlying plugin.
static_costmap | Costmap2D, which contains the static part of the original costmap |
Definition at line 317 of file costmap_converter_interface.h.
|
inline |
Set the underlying plugin for subsequent costmap conversion of the static background of the costmap.
static_costmap_converter | shared pointer to the static costmap conversion plugin |
Definition at line 308 of file costmap_converter_interface.h.
|
inlinevirtual |
Determines whether an additional plugin for subsequent costmap conversion is specified.
Reimplemented from costmap_converter::BaseCostmapToPolygons.
Definition at line 344 of file costmap_converter_interface.h.
|
private |
Definition at line 359 of file costmap_converter_interface.h.
|
private |
Definition at line 360 of file costmap_converter_interface.h.