Public Member Functions | Protected Member Functions | Private Attributes
costmap_converter::BaseCostmapToDynamicObstacles Class Reference

#include <costmap_converter_interface.h>

Inheritance diagram for costmap_converter::BaseCostmapToDynamicObstacles:
Inheritance graph
[legend]

List of all members.

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_

Detailed Description

Definition at line 272 of file costmap_converter_interface.h.


Constructor & Destructor Documentation

Protected constructor that should be called by subclasses.

Definition at line 356 of file costmap_converter_interface.h.


Member Function Documentation

Apply the underlying plugin for static costmap conversion.

Definition at line 325 of file costmap_converter_interface.h.

Get the converted polygons from the underlying plugin.

Returns:
Shared instance of the underlying plugins polygon container

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.

Parameters:
plugin_nameExact class name of the plugin to be loaded, e.g. costmap_converter::CostmapToPolygonsDBSMCCH
nh_parentNodeHandle 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.

Parameters:
static_costmapCostmap2D, 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.

Parameters:
static_costmap_convertershared pointer to the static costmap conversion plugin

Definition at line 308 of file costmap_converter_interface.h.

Determines whether an additional plugin for subsequent costmap conversion is specified.

Returns:
true, if a plugin for subsequent costmap conversion is specified

Reimplemented from costmap_converter::BaseCostmapToPolygons.

Definition at line 344 of file costmap_converter_interface.h.


Member Data Documentation

Definition at line 359 of file costmap_converter_interface.h.

Definition at line 360 of file costmap_converter_interface.h.


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


costmap_converter
Author(s): Christoph Rösmann , Franz Albers , Otniel Rinaldo
autogenerated on Sat Jun 8 2019 20:53:15