39 #ifndef COSTMAP_CONVERTER_INTERFACE_H_    40 #define COSTMAP_CONVERTER_INTERFACE_H_    45 #include <boost/thread.hpp>    48 #include <geometry_msgs/Polygon.h>    49 #include <costmap_converter/ObstacleArrayMsg.h>   137       ObstacleArrayPtr obstacles = boost::make_shared<ObstacleArrayMsg>();
   141         for (
const geometry_msgs::Polygon& polygon : *polygons)
   143           obstacles->obstacles.emplace_back();
   144           obstacles->obstacles.back().polygon = polygon;
   193         ROS_DEBUG_NAMED(
"costmap_converter", 
"Spinning up a thread for the CostmapToPolygons plugin");
   286       static_costmap_converter_ = static_converter_loader_.createInstance(plugin_name);
   288       if(boost::dynamic_pointer_cast<BaseCostmapToDynamicObstacles>(static_costmap_converter_))
   292       std::string raw_plugin_name = static_converter_loader_.getName(plugin_name);
   293       static_costmap_converter_->initialize(
ros::NodeHandle(nh_parent, raw_plugin_name));
   294       setStaticCostmapConverterPlugin(static_costmap_converter_);
   295       ROS_INFO_STREAM(
"CostmapToDynamicObstacles: underlying costmap conversion plugin for static obstacles " << plugin_name << 
" loaded.");
   299       ROS_WARN(
"CostmapToDynamicObstacles: The specified costmap converter plugin cannot be loaded. Continuing without subsequent conversion of static obstacles. Error message: %s", ex.what());
   300       static_costmap_converter_.reset();
   310     static_costmap_converter_ = static_costmap_converter;
   319     static_costmap_converter_->setCostmap2D(static_costmap.get());
   327     static_costmap_converter_->compute();
   336     return static_costmap_converter_->getPolygons();
   346     if(static_costmap_converter_)
   368 #endif // end COSTMAP_CONVERTER_INTERFACE_H_ 
void convertStaticObstacles()
Apply the underlying plugin for static costmap conversion. 
virtual ObstacleArrayConstPtr getObstacles()
Get a shared instance of the current obstacle container If this method is not overwritten by the unde...
boost::shared_ptr< BaseCostmapToPolygons > static_costmap_converter_
boost::mutex terminate_mutex_
void setStaticCostmapConverterPlugin(boost::shared_ptr< BaseCostmapToPolygons > static_costmap_converter)
Set the underlying plugin for subsequent costmap conversion of the static background of the costmap...
virtual void initialize(ros::NodeHandle nh)=0
Initialize the plugin. 
void workerCallback(const ros::TimerEvent &)
The callback of the worker that performs the actual work (updating the costmap and converting it to p...
virtual bool stackedCostmapConversion()
Determines whether an additional plugin for subsequent costmap conversion is specified. 
pluginlib::ClassLoader< BaseCostmapToPolygons > static_converter_loader_
virtual void setOdomTopic(const std::string &odom_topic)
Set name of robot's odometry topic. 
BaseCostmapToDynamicObstacles()
Protected constructor that should be called by subclasses. 
virtual PolygonContainerConstPtr getPolygons()
Get a shared instance of the current polygon container. 
ROSCPP_DECL CallbackQueue * getGlobalCallbackQueue()
virtual void setCostmap2D(costmap_2d::Costmap2D *costmap)=0
Pass a pointer to the costap to the plugin. 
#define ROS_DEBUG_NAMED(name,...)
void stopWorker()
Stop the worker that repeatedly converts the costmap to polygons. 
virtual ~BaseCostmapToPolygons()
Destructor. 
boost::thread * spin_thread_
void loadStaticCostmapConverterPlugin(const std::string &plugin_name, ros::NodeHandle nh_parent)
Load underlying static costmap conversion plugin via plugin-loader. 
void spinThread()
Blocking method that checks for new timer events (active if startWorker() is called with spin_thread ...
ros::CallbackQueue callback_queue_
void setCallbackQueue(CallbackQueueInterface *queue)
This abstract class defines the interface for plugins that convert the costmap into polygon types...
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const 
void setStaticCostmap(boost::shared_ptr< costmap_2d::Costmap2D > static_costmap)
Set the costmap for the underlying plugin. 
BaseCostmapToPolygons()
Protected constructor that should be called by subclasses. 
boost::shared_ptr< ObstacleArrayMsg > ObstacleArrayPtr
Typedef for a shared dynamic obstacle container. 
virtual void compute()=0
This method performs the actual work (conversion of the costmap to polygons) 
#define ROS_INFO_STREAM(args)
boost::shared_ptr< const std::vector< geometry_msgs::Polygon > > PolygonContainerConstPtr
Typedef for a shared polygon container (read-only access) 
boost::shared_ptr< const ObstacleArrayMsg > ObstacleArrayConstPtr
Typedef for a shared dynamic obstacle container (read-only access) 
boost::shared_ptr< std::vector< geometry_msgs::Polygon > > PolygonContainerPtr
Typedef for a shared polygon container. 
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 imple...
virtual void updateCostmap2D()=0
Get updated data from the previously set Costmap2D. 
PolygonContainerConstPtr getStaticPolygons()
Get the converted polygons from the underlying plugin. 
bool stackedCostmapConversion()
Determines whether an additional plugin for subsequent costmap conversion is specified.