This abstract class defines the interface for plugins that convert the costmap into polygon types.
More...
#include <costmap_converter_interface.h>
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:
- Manual call to conversion routines: setCostmap2D(), compute() and getPolygons() (in subsequent calls setCostmap2D() can be substituted by updateCostmap2D())
- 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 113 of file costmap_converter_interface.h.
◆ ~BaseCostmapToPolygons()
virtual costmap_converter::BaseCostmapToPolygons::~BaseCostmapToPolygons |
( |
| ) |
|
|
inlinevirtual |
◆ BaseCostmapToPolygons()
costmap_converter::BaseCostmapToPolygons::BaseCostmapToPolygons |
( |
| ) |
|
|
inlineprotected |
◆ compute()
virtual void costmap_converter::BaseCostmapToPolygons::compute |
( |
| ) |
|
|
pure virtual |
◆ getObstacles()
◆ getPolygons()
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.
- 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 161 of file costmap_converter_interface.h.
◆ initialize()
virtual void costmap_converter::BaseCostmapToPolygons::initialize |
( |
ros::NodeHandle |
nh | ) |
|
|
pure virtual |
◆ setCostmap2D()
◆ setOdomTopic()
virtual void costmap_converter::BaseCostmapToPolygons::setOdomTopic |
( |
const std::string & |
odom_topic | ) |
|
|
inlinevirtual |
◆ spinThread()
void costmap_converter::BaseCostmapToPolygons::spinThread |
( |
| ) |
|
|
inlineprotected |
◆ stackedCostmapConversion()
virtual bool costmap_converter::BaseCostmapToPolygons::stackedCostmapConversion |
( |
| ) |
|
|
inlinevirtual |
◆ startWorker()
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
-
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 213 of file costmap_converter_interface.h.
◆ stopWorker()
void costmap_converter::BaseCostmapToPolygons::stopWorker |
( |
| ) |
|
|
inline |
◆ updateCostmap2D()
virtual void costmap_converter::BaseCostmapToPolygons::updateCostmap2D |
( |
| ) |
|
|
pure virtual |
◆ workerCallback()
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 286 of file costmap_converter_interface.h.
◆ callback_queue_
◆ need_to_terminate_
bool costmap_converter::BaseCostmapToPolygons::need_to_terminate_ |
|
private |
◆ nh_
◆ spin_thread_
boost::thread* costmap_converter::BaseCostmapToPolygons::spin_thread_ |
|
private |
◆ terminate_mutex_
boost::mutex costmap_converter::BaseCostmapToPolygons::terminate_mutex_ |
|
private |
◆ worker_timer_
ros::Timer costmap_converter::BaseCostmapToPolygons::worker_timer_ |
|
private |
The documentation for this class was generated from the following file: