This abstract class defines the interface for plugins that convert the costmap into polygon types. More...
#include <costmap_converter_interface.h>
Public Member Functions | |
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... | |
virtual bool | stackedCostmapConversion () |
Determines whether an additional plugin for subsequent costmap conversion is specified. 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 | |
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 | |
ros::CallbackQueue | callback_queue_ |
bool | need_to_terminate_ |
ros::NodeHandle | nh_ |
boost::thread * | spin_thread_ |
boost::mutex | terminate_mutex_ |
ros::Timer | worker_timer_ |
This abstract class defines the interface for plugins that convert the costmap into polygon types.
Plugins must accept a costmap_2d::Costmap2D datatype as information source. The interface provides two different use cases:
Definition at line 77 of file costmap_converter_interface.h.
|
inlinevirtual |
Destructor.
Definition at line 90 of file costmap_converter_interface.h.
|
inlineprotected |
Protected constructor that should be called by subclasses.
Definition at line 229 of file costmap_converter_interface.h.
|
pure virtual |
This method performs the actual work (conversion of the costmap to polygons)
Implemented in costmap_converter::CostmapToPolygonsDBSMCCH, costmap_converter::CostmapToDynamicObstacles, costmap_converter::CostmapToLinesDBSRANSAC, costmap_converter::CostmapToLinesDBSMCCH, and costmap_converter::CostmapToPolygonsDBSConcaveHull.
|
inlinevirtual |
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().
Reimplemented in costmap_converter::CostmapToDynamicObstacles.
Definition at line 135 of file costmap_converter_interface.h.
|
inlinevirtual |
Get a shared instance of the current polygon container.
If this method is not implemented by any subclass (plugin) the returned shared pointer is empty.
Reimplemented in costmap_converter::CostmapToPolygonsDBSMCCH.
Definition at line 125 of file costmap_converter_interface.h.
|
pure virtual |
Initialize the plugin.
nh | Nodehandle that defines the namespace for parameters |
Implemented in costmap_converter::CostmapToPolygonsDBSMCCH, costmap_converter::CostmapToDynamicObstacles, costmap_converter::CostmapToLinesDBSRANSAC, costmap_converter::CostmapToLinesDBSMCCH, and costmap_converter::CostmapToPolygonsDBSConcaveHull.
|
pure virtual |
Pass a pointer to the costap to the plugin.
costmap | Pointer to the costmap2d source |
Implemented in costmap_converter::CostmapToPolygonsDBSMCCH, and costmap_converter::CostmapToDynamicObstacles.
|
inlinevirtual |
Set name of robot's odometry topic.
Some plugins might require odometry information to compensate the robot's ego motion
odom_topic | topic name |
Reimplemented in costmap_converter::CostmapToDynamicObstacles.
Definition at line 157 of file costmap_converter_interface.h.
|
inlineprotected |
Blocking method that checks for new timer events (active if startWorker() is called with spin_thread enabled)
Definition at line 234 of file costmap_converter_interface.h.
|
inlinevirtual |
Determines whether an additional plugin for subsequent costmap conversion is specified.
Reimplemented in costmap_converter::BaseCostmapToDynamicObstacles.
Definition at line 164 of file costmap_converter_interface.h.
|
inline |
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).
rate | The rate that specifies how often the costmap should be updated |
costmap | Pointer to the underlying costmap (must be valid and lockable as long as the worker is active |
spin_thread | if true ,the timer is invoked in a separate thread, otherwise in the default callback queue) |
Definition at line 177 of file costmap_converter_interface.h.
|
inline |
Stop the worker that repeatedly converts the costmap to polygons.
Definition at line 210 of file costmap_converter_interface.h.
|
pure virtual |
Get updated data from the previously set Costmap2D.
Implemented in costmap_converter::CostmapToPolygonsDBSMCCH, and costmap_converter::CostmapToDynamicObstacles.
|
inlineprotected |
The callback of the worker that performs the actual work (updating the costmap and converting it to polygons)
Definition at line 250 of file costmap_converter_interface.h.
|
private |
Definition at line 260 of file costmap_converter_interface.h.
|
private |
Definition at line 262 of file costmap_converter_interface.h.
|
private |
Definition at line 258 of file costmap_converter_interface.h.
|
private |
Definition at line 259 of file costmap_converter_interface.h.
|
private |
Definition at line 261 of file costmap_converter_interface.h.
|
private |
Definition at line 257 of file costmap_converter_interface.h.