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) | |
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(). | |
virtual PolygonContainerConstPtr | getPolygons () |
Get a shared instance of the current polygon container. | |
virtual void | initialize (ros::NodeHandle nh)=0 |
Initialize the plugin. | |
virtual void | setCostmap2D (costmap_2d::Costmap2D *costmap)=0 |
Pass a pointer to the costap to the plugin. | |
virtual void | setOdomTopic (const std::string &odom_topic) |
Set name of robot's odometry topic. | |
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). | |
void | stopWorker () |
Stop the worker that repeatedly converts the costmap to polygons. | |
virtual void | updateCostmap2D ()=0 |
Get updated data from the previously set Costmap2D. | |
virtual | ~BaseCostmapToPolygons () |
Destructor. | |
Protected Member Functions | |
BaseCostmapToPolygons () | |
Protected constructor that should be called by subclasses. | |
void | spinThread () |
Blocking method that checks for new timer events (active if startWorker() is called with spin_thread enabled) | |
void | workerCallback (const ros::TimerEvent &) |
The callback of the worker that performs the actual work (updating the costmap and converting it to polygons) | |
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: 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 79 of file costmap_converter_interface.h.
virtual costmap_converter::BaseCostmapToPolygons::~BaseCostmapToPolygons | ( | ) | [inline, virtual] |
Destructor.
Definition at line 92 of file costmap_converter_interface.h.
costmap_converter::BaseCostmapToPolygons::BaseCostmapToPolygons | ( | ) | [inline, protected] |
Protected constructor that should be called by subclasses.
Definition at line 224 of file costmap_converter_interface.h.
virtual void costmap_converter::BaseCostmapToPolygons::compute | ( | ) | [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.
virtual ObstacleArrayConstPtr costmap_converter::BaseCostmapToPolygons::getObstacles | ( | ) | [inline, virtual] |
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 137 of file costmap_converter_interface.h.
virtual PolygonContainerConstPtr costmap_converter::BaseCostmapToPolygons::getPolygons | ( | ) | [inline, virtual] |
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 127 of file costmap_converter_interface.h.
virtual void costmap_converter::BaseCostmapToPolygons::initialize | ( | ros::NodeHandle | nh | ) | [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.
virtual void costmap_converter::BaseCostmapToPolygons::setCostmap2D | ( | costmap_2d::Costmap2D * | costmap | ) | [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.
virtual void costmap_converter::BaseCostmapToPolygons::setOdomTopic | ( | const std::string & | odom_topic | ) | [inline, virtual] |
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 159 of file costmap_converter_interface.h.
void costmap_converter::BaseCostmapToPolygons::spinThread | ( | ) | [inline, protected] |
Blocking method that checks for new timer events (active if startWorker() is called with spin_thread enabled)
Definition at line 229 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).
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 172 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 205 of file costmap_converter_interface.h.
virtual void costmap_converter::BaseCostmapToPolygons::updateCostmap2D | ( | ) | [pure virtual] |
Get updated data from the previously set Costmap2D.
Implemented in costmap_converter::CostmapToPolygonsDBSMCCH, and costmap_converter::CostmapToDynamicObstacles.
void costmap_converter::BaseCostmapToPolygons::workerCallback | ( | const ros::TimerEvent & | ) | [inline, protected] |
The callback of the worker that performs the actual work (updating the costmap and converting it to polygons)
Definition at line 245 of file costmap_converter_interface.h.
ros::CallbackQueue costmap_converter::BaseCostmapToPolygons::callback_queue_ [private] |
Definition at line 255 of file costmap_converter_interface.h.
bool costmap_converter::BaseCostmapToPolygons::need_to_terminate_ [private] |
Definition at line 257 of file costmap_converter_interface.h.
ros::NodeHandle costmap_converter::BaseCostmapToPolygons::nh_ [private] |
Definition at line 253 of file costmap_converter_interface.h.
boost::thread* costmap_converter::BaseCostmapToPolygons::spin_thread_ [private] |
Definition at line 254 of file costmap_converter_interface.h.
boost::mutex costmap_converter::BaseCostmapToPolygons::terminate_mutex_ [private] |
Definition at line 256 of file costmap_converter_interface.h.
ros::Timer costmap_converter::BaseCostmapToPolygons::worker_timer_ [private] |
Definition at line 252 of file costmap_converter_interface.h.