Public Member Functions | Protected Member Functions | Private Attributes | List of all members
costmap_converter::BaseCostmapToPolygons Class Referenceabstract

This abstract class defines the interface for plugins that convert the costmap into polygon types. More...

#include <costmap_converter_interface.h>

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

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_
 

Detailed Description

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:

  1. Manual call to conversion routines: setCostmap2D(), compute() and getPolygons() (in subsequent calls setCostmap2D() can be substituted by updateCostmap2D())
  2. Repeatedly process costmap with a specific rate (startWorker() and stopWorker()): Make sure that the costmap is valid while the worker is active (you can specify your own spinner or activate a threaded spinner). Costmaps can be obtained by invoking getPolygons().

Definition at line 77 of file costmap_converter_interface.h.

Constructor & Destructor Documentation

virtual costmap_converter::BaseCostmapToPolygons::~BaseCostmapToPolygons ( )
inlinevirtual

Destructor.

Definition at line 90 of file costmap_converter_interface.h.

costmap_converter::BaseCostmapToPolygons::BaseCostmapToPolygons ( )
inlineprotected

Protected constructor that should be called by subclasses.

Definition at line 229 of file costmap_converter_interface.h.

Member Function Documentation

virtual void costmap_converter::BaseCostmapToPolygons::compute ( )
pure virtual
virtual ObstacleArrayConstPtr costmap_converter::BaseCostmapToPolygons::getObstacles ( )
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().

Remarks
If compute() or startWorker() has not been called before, this method returns an empty instance!
Warning
The underlying plugin must ensure that this method is thread safe.
Returns
Shared instance of the current obstacle container
See also
getPolygons

Reimplemented in costmap_converter::CostmapToDynamicObstacles.

Definition at line 135 of file costmap_converter_interface.h.

virtual PolygonContainerConstPtr costmap_converter::BaseCostmapToPolygons::getPolygons ( )
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.

Remarks
If compute() or startWorker() has not been called before, this method returns an empty instance!
Warning
The underlying plugin must ensure that this method is thread safe.
Returns
Shared instance of the current polygon container

Reimplemented in costmap_converter::CostmapToPolygonsDBSMCCH.

Definition at line 125 of file costmap_converter_interface.h.

virtual void costmap_converter::BaseCostmapToPolygons::initialize ( ros::NodeHandle  nh)
pure virtual
virtual void costmap_converter::BaseCostmapToPolygons::setCostmap2D ( costmap_2d::Costmap2D costmap)
pure virtual

Pass a pointer to the costap to the plugin.

Warning
The plugin should handle the costmap's mutex locking.
See also
updateCostmap2D
Parameters
costmapPointer to the costmap2d source

Implemented in costmap_converter::CostmapToPolygonsDBSMCCH, and costmap_converter::CostmapToDynamicObstacles.

virtual void costmap_converter::BaseCostmapToPolygons::setOdomTopic ( const std::string &  odom_topic)
inlinevirtual

Set name of robot's odometry topic.

Some plugins might require odometry information to compensate the robot's ego motion

Parameters
odom_topictopic name

Reimplemented in costmap_converter::CostmapToDynamicObstacles.

Definition at line 157 of file costmap_converter_interface.h.

void costmap_converter::BaseCostmapToPolygons::spinThread ( )
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.

virtual bool costmap_converter::BaseCostmapToPolygons::stackedCostmapConversion ( )
inlinevirtual

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

Returns
false, since all plugins for static costmap conversion are independent

Reimplemented in costmap_converter::BaseCostmapToDynamicObstacles.

Definition at line 164 of file costmap_converter_interface.h.

void costmap_converter::BaseCostmapToPolygons::startWorker ( ros::Rate  rate,
costmap_2d::Costmap2D costmap,
bool  spin_thread = false 
)
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).

Parameters
rateThe rate that specifies how often the costmap should be updated
costmapPointer to the underlying costmap (must be valid and lockable as long as the worker is active
spin_threadif 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.

void costmap_converter::BaseCostmapToPolygons::stopWorker ( )
inline

Stop the worker that repeatedly converts the costmap to polygons.

Definition at line 210 of file costmap_converter_interface.h.

virtual void costmap_converter::BaseCostmapToPolygons::updateCostmap2D ( )
pure virtual

Get updated data from the previously set Costmap2D.

Warning
The plugin should handle the costmap's mutex locking.
See also
setCostmap2D

Implemented in costmap_converter::CostmapToPolygonsDBSMCCH, and costmap_converter::CostmapToDynamicObstacles.

void costmap_converter::BaseCostmapToPolygons::workerCallback ( const ros::TimerEvent )
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.

Member Data Documentation

ros::CallbackQueue costmap_converter::BaseCostmapToPolygons::callback_queue_
private

Definition at line 260 of file costmap_converter_interface.h.

bool costmap_converter::BaseCostmapToPolygons::need_to_terminate_
private

Definition at line 262 of file costmap_converter_interface.h.

ros::NodeHandle costmap_converter::BaseCostmapToPolygons::nh_
private

Definition at line 258 of file costmap_converter_interface.h.

boost::thread* costmap_converter::BaseCostmapToPolygons::spin_thread_
private

Definition at line 259 of file costmap_converter_interface.h.

boost::mutex costmap_converter::BaseCostmapToPolygons::terminate_mutex_
private

Definition at line 261 of file costmap_converter_interface.h.

ros::Timer costmap_converter::BaseCostmapToPolygons::worker_timer_
private

Definition at line 257 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 May 16 2020 03:19:18