#include <costmap_converter_interface.h>
Public Member Functions | |
void | convertStaticObstacles () |
Apply the underlying plugin for static costmap conversion. | |
PolygonContainerConstPtr | getStaticPolygons () |
Get the converted polygons from the underlying plugin. | |
void | loadStaticCostmapConverterPlugin (const std::string &plugin_name, ros::NodeHandle nh_parent) |
Load underlying static costmap conversion plugin via plugin-loader. | |
void | setStaticCostmap (boost::shared_ptr< costmap_2d::Costmap2D > static_costmap) |
Set the costmap for the underlying plugin. | |
void | setStaticCostmapConverterPlugin (boost::shared_ptr< BaseCostmapToPolygons > static_costmap_converter) |
Set the underlying plugin for subsequent costmap conversion of the static background of the costmap. | |
bool | stackedCostmapConversion () |
Determines whether an additional plugin for subsequent costmap conversion is specified. | |
Protected Member Functions | |
BaseCostmapToDynamicObstacles () | |
Protected constructor that should be called by subclasses. | |
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.
costmap_converter::BaseCostmapToDynamicObstacles::BaseCostmapToDynamicObstacles | ( | ) | [inline, protected] |
Protected constructor that should be called by subclasses.
Definition at line 356 of file costmap_converter_interface.h.
void costmap_converter::BaseCostmapToDynamicObstacles::convertStaticObstacles | ( | ) | [inline] |
Apply the underlying plugin for static costmap conversion.
Definition at line 325 of file costmap_converter_interface.h.
PolygonContainerConstPtr costmap_converter::BaseCostmapToDynamicObstacles::getStaticPolygons | ( | ) | [inline] |
Get the converted polygons from the underlying plugin.
Definition at line 334 of file costmap_converter_interface.h.
void costmap_converter::BaseCostmapToDynamicObstacles::loadStaticCostmapConverterPlugin | ( | const std::string & | plugin_name, |
ros::NodeHandle | nh_parent | ||
) | [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.
void costmap_converter::BaseCostmapToDynamicObstacles::setStaticCostmap | ( | boost::shared_ptr< costmap_2d::Costmap2D > | static_costmap | ) | [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.
void costmap_converter::BaseCostmapToDynamicObstacles::setStaticCostmapConverterPlugin | ( | boost::shared_ptr< BaseCostmapToPolygons > | static_costmap_converter | ) | [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.
bool costmap_converter::BaseCostmapToDynamicObstacles::stackedCostmapConversion | ( | ) | [inline, virtual] |
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.
pluginlib::ClassLoader<BaseCostmapToPolygons> costmap_converter::BaseCostmapToDynamicObstacles::static_converter_loader_ [private] |
Definition at line 359 of file costmap_converter_interface.h.
boost::shared_ptr<BaseCostmapToPolygons> costmap_converter::BaseCostmapToDynamicObstacles::static_costmap_converter_ [private] |
Definition at line 360 of file costmap_converter_interface.h.