costmap_converter_interface.h
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2016
6  * TU Dortmund - Institute of Control Theory and Systems Engineering.
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of the institute nor the names of its
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  *
36  * Author: Christoph Rösmann, Otniel Rinaldo
37  *********************************************************************/
38 
39 #ifndef COSTMAP_CONVERTER_INTERFACE_H_
40 #define COSTMAP_CONVERTER_INTERFACE_H_
41 
42 //#include <costmap_2d/costmap_2d_ros.h>
43 #include <ros/ros.h>
44 #include <ros/callback_queue.h>
45 #include <boost/thread.hpp>
46 #include <costmap_2d/costmap_2d.h>
48 #include <geometry_msgs/Polygon.h>
49 #include <costmap_converter/ObstacleArrayMsg.h>
50 
51 
53 {
58 
63 
64 
78 {
79 public:
80 
85  virtual void initialize(ros::NodeHandle nh) = 0;
86 
90  virtual ~BaseCostmapToPolygons()
91  {
92  stopWorker();
93  }
94 
95 
102  virtual void setCostmap2D(costmap_2d::Costmap2D* costmap) = 0;
103 
109  virtual void updateCostmap2D() = 0;
110 
114  virtual void compute() = 0;
115 
126 
136  {
137  ObstacleArrayPtr obstacles = boost::make_shared<ObstacleArrayMsg>();
139  if (polygons)
140  {
141  for (const geometry_msgs::Polygon& polygon : *polygons)
142  {
143  obstacles->obstacles.emplace_back();
144  obstacles->obstacles.back().polygon = polygon;
145  }
146  }
147  return obstacles;
148  }
149 
157  virtual void setOdomTopic(const std::string& odom_topic) {}
158 
164  virtual bool stackedCostmapConversion() {return false;}
165 
177  void startWorker(ros::Rate rate, costmap_2d::Costmap2D* costmap, bool spin_thread = false)
178  {
179  setCostmap2D(costmap);
180 
181  if (spin_thread_)
182  {
183  {
184  boost::mutex::scoped_lock terminate_lock(terminate_mutex_);
185  need_to_terminate_ = true;
186  }
187  spin_thread_->join();
188  delete spin_thread_;
189  }
190 
191  if (spin_thread)
192  {
193  ROS_DEBUG_NAMED("costmap_converter", "Spinning up a thread for the CostmapToPolygons plugin");
194  need_to_terminate_ = false;
195  spin_thread_ = new boost::thread(boost::bind(&BaseCostmapToPolygons::spinThread, this));
197  }
198  else
199  {
200  spin_thread_ = NULL;
202  }
203 
205  }
206 
210  void stopWorker()
211  {
214  {
215  {
216  boost::mutex::scoped_lock terminate_lock(terminate_mutex_);
217  need_to_terminate_ = true;
218  }
219  spin_thread_->join();
220  delete spin_thread_;
221  }
222  }
223 
224 protected:
225 
229  BaseCostmapToPolygons() : nh_("~costmap_to_polygons"), spin_thread_(NULL), need_to_terminate_(false) {}
230 
234  void spinThread()
235  {
236  while (nh_.ok())
237  {
238  {
239  boost::mutex::scoped_lock terminate_lock(terminate_mutex_);
240  if (need_to_terminate_)
241  break;
242  }
244  }
245  }
246 
250  void workerCallback(const ros::TimerEvent&)
251  {
252  updateCostmap2D();
253  compute();
254  }
255 
256 private:
259  boost::thread* spin_thread_;
261  boost::mutex terminate_mutex_;
262  bool need_to_terminate_;
263 };
264 
265 
273 {
274 public:
275 
282  void loadStaticCostmapConverterPlugin(const std::string& plugin_name, ros::NodeHandle nh_parent)
283  {
284  try
285  {
287 
288  if(boost::dynamic_pointer_cast<BaseCostmapToDynamicObstacles>(static_costmap_converter_))
289  {
290  throw pluginlib::PluginlibException("The specified plugin for static costmap conversion is a dynamic plugin. Specify a static plugin.");
291  }
292  std::string raw_plugin_name = static_converter_loader_.getName(plugin_name);
293  static_costmap_converter_->initialize(ros::NodeHandle(nh_parent, raw_plugin_name));
295  ROS_INFO_STREAM("CostmapToDynamicObstacles: underlying costmap conversion plugin for static obstacles " << plugin_name << " loaded.");
296  }
298  {
299  ROS_WARN("CostmapToDynamicObstacles: The specified costmap converter plugin cannot be loaded. Continuing without subsequent conversion of static obstacles. Error message: %s", ex.what());
301  }
302  }
303 
309  {
310  static_costmap_converter_ = static_costmap_converter;
311  }
312 
318  {
319  static_costmap_converter_->setCostmap2D(static_costmap.get());
320  }
321 
326  {
327  static_costmap_converter_->compute();
328  }
329 
335  {
336  return static_costmap_converter_->getPolygons();
337  }
338 
345  {
347  return true;
348  else
349  return false;
350  }
351 
352 protected:
356  BaseCostmapToDynamicObstacles() : static_converter_loader_("costmap_converter", "costmap_converter::BaseCostmapToPolygons"), static_costmap_converter_() {}
357 
358 private:
361 };
362 
363 
364 }
365 
366 
367 
368 #endif // end COSTMAP_CONVERTER_INTERFACE_H_
costmap_converter::BaseCostmapToPolygons::worker_timer_
ros::Timer worker_timer_
Definition: costmap_converter_interface.h:293
costmap_converter::BaseCostmapToPolygons::setOdomTopic
virtual void setOdomTopic(const std::string &odom_topic)
Set name of robot's odometry topic.
Definition: costmap_converter_interface.h:193
costmap_converter::BaseCostmapToPolygons::getObstacles
virtual ObstacleArrayConstPtr getObstacles()
Get a shared instance of the current obstacle container If this method is not overwritten by the unde...
Definition: costmap_converter_interface.h:171
costmap_converter::BaseCostmapToPolygons::~BaseCostmapToPolygons
virtual ~BaseCostmapToPolygons()
Destructor.
Definition: costmap_converter_interface.h:126
costmap_converter::BaseCostmapToDynamicObstacles::convertStaticObstacles
void convertStaticObstacles()
Apply the underlying plugin for static costmap conversion.
Definition: costmap_converter_interface.h:361
costmap_converter::BaseCostmapToPolygons::compute
virtual void compute()=0
This method performs the actual work (conversion of the costmap to polygons)
boost::shared_ptr< ObstacleArrayMsg >
costmap_converter::BaseCostmapToPolygons
This abstract class defines the interface for plugins that convert the costmap into polygon types.
Definition: costmap_converter_interface.h:113
costmap_converter::BaseCostmapToPolygons::spin_thread_
boost::thread * spin_thread_
Definition: costmap_converter_interface.h:295
ros.h
costmap_2d.h
ros::Timer::stop
void stop()
costmap_converter::ObstacleArrayPtr
boost::shared_ptr< ObstacleArrayMsg > ObstacleArrayPtr
Typedef for a shared dynamic obstacle container.
Definition: costmap_converter_interface.h:91
costmap_2d::Costmap2D
costmap_converter::BaseCostmapToDynamicObstacles::static_costmap_converter_
boost::shared_ptr< BaseCostmapToPolygons > static_costmap_converter_
Definition: costmap_converter_interface.h:396
costmap_2d_ros.h
costmap_converter::BaseCostmapToDynamicObstacles::setStaticCostmapConverterPlugin
void setStaticCostmapConverterPlugin(boost::shared_ptr< BaseCostmapToPolygons > static_costmap_converter)
Set the underlying plugin for subsequent costmap conversion of the static background of the costmap.
Definition: costmap_converter_interface.h:344
costmap_converter::BaseCostmapToPolygons::stopWorker
void stopWorker()
Stop the worker that repeatedly converts the costmap to polygons.
Definition: costmap_converter_interface.h:246
costmap_converter::BaseCostmapToDynamicObstacles::loadStaticCostmapConverterPlugin
void loadStaticCostmapConverterPlugin(const std::string &plugin_name, ros::NodeHandle nh_parent)
Load underlying static costmap conversion plugin via plugin-loader.
Definition: costmap_converter_interface.h:318
pluginlib::PluginlibException
costmap_converter::BaseCostmapToDynamicObstacles
Definition: costmap_converter_interface.h:308
ros::CallbackQueue
ROS_DEBUG_NAMED
#define ROS_DEBUG_NAMED(name,...)
costmap_converter::BaseCostmapToDynamicObstacles::BaseCostmapToDynamicObstacles
BaseCostmapToDynamicObstacles()
Protected constructor that should be called by subclasses.
Definition: costmap_converter_interface.h:392
costmap_converter::BaseCostmapToPolygons::initialize
virtual void initialize(ros::NodeHandle nh)=0
Initialize the plugin.
ROS_WARN
#define ROS_WARN(...)
costmap_converter::BaseCostmapToDynamicObstacles::getStaticPolygons
PolygonContainerConstPtr getStaticPolygons()
Get the converted polygons from the underlying plugin.
Definition: costmap_converter_interface.h:370
costmap_converter::BaseCostmapToPolygons::getPolygons
virtual PolygonContainerConstPtr getPolygons()
Get a shared instance of the current polygon container.
Definition: costmap_converter_interface.h:161
pluginlib::ClassLoader
costmap_converter::BaseCostmapToPolygons::startWorker
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...
Definition: costmap_converter_interface.h:213
ros::TimerEvent
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
costmap_converter::BaseCostmapToPolygons::setCostmap2D
virtual void setCostmap2D(costmap_2d::Costmap2D *costmap)=0
Pass a pointer to the costap to the plugin.
costmap_converter::BaseCostmapToDynamicObstacles::stackedCostmapConversion
bool stackedCostmapConversion()
Determines whether an additional plugin for subsequent costmap conversion is specified.
Definition: costmap_converter_interface.h:380
costmap_converter::BaseCostmapToPolygons::workerCallback
void workerCallback(const ros::TimerEvent &)
The callback of the worker that performs the actual work (updating the costmap and converting it to p...
Definition: costmap_converter_interface.h:286
ros::NodeHandle::setCallbackQueue
void setCallbackQueue(CallbackQueueInterface *queue)
callback_queue.h
costmap_converter::BaseCostmapToPolygons::BaseCostmapToPolygons
BaseCostmapToPolygons()
Protected constructor that should be called by subclasses.
Definition: costmap_converter_interface.h:265
costmap_converter::PolygonContainerPtr
boost::shared_ptr< std::vector< geometry_msgs::Polygon > > PolygonContainerPtr
Typedef for a shared polygon container.
Definition: costmap_converter_interface.h:96
costmap_converter::BaseCostmapToDynamicObstacles::static_converter_loader_
pluginlib::ClassLoader< BaseCostmapToPolygons > static_converter_loader_
Definition: costmap_converter_interface.h:395
costmap_converter
Definition: costmap_converter_interface.h:52
ros::NodeHandle::ok
bool ok() const
costmap_converter::ObstacleArrayConstPtr
boost::shared_ptr< const ObstacleArrayMsg > ObstacleArrayConstPtr
Typedef for a shared dynamic obstacle container (read-only access)
Definition: costmap_converter_interface.h:93
costmap_converter::BaseCostmapToPolygons::nh_
ros::NodeHandle nh_
Definition: costmap_converter_interface.h:294
costmap_converter::PolygonContainerConstPtr
boost::shared_ptr< const std::vector< geometry_msgs::Polygon > > PolygonContainerConstPtr
Typedef for a shared polygon container (read-only access)
Definition: costmap_converter_interface.h:98
costmap_converter::BaseCostmapToPolygons::need_to_terminate_
bool need_to_terminate_
Definition: costmap_converter_interface.h:298
costmap_converter::BaseCostmapToPolygons::spinThread
void spinThread()
Blocking method that checks for new timer events (active if startWorker() is called with spin_thread ...
Definition: costmap_converter_interface.h:270
costmap_converter::BaseCostmapToPolygons::callback_queue_
ros::CallbackQueue callback_queue_
Definition: costmap_converter_interface.h:296
costmap_converter::BaseCostmapToPolygons::updateCostmap2D
virtual void updateCostmap2D()=0
Get updated data from the previously set Costmap2D.
ros::Rate
costmap_converter::BaseCostmapToDynamicObstacles::setStaticCostmap
void setStaticCostmap(boost::shared_ptr< costmap_2d::Costmap2D > static_costmap)
Set the costmap for the underlying plugin.
Definition: costmap_converter_interface.h:353
ros::WallDuration
ros::NodeHandle::createTimer
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
ros::Timer
ros::CallbackQueue::callAvailable
void callAvailable()
costmap_converter::BaseCostmapToPolygons::terminate_mutex_
boost::mutex terminate_mutex_
Definition: costmap_converter_interface.h:297
ros::NodeHandle
ros::getGlobalCallbackQueue
ROSCPP_DECL CallbackQueue * getGlobalCallbackQueue()
costmap_converter::BaseCostmapToPolygons::stackedCostmapConversion
virtual bool stackedCostmapConversion()
Determines whether an additional plugin for subsequent costmap conversion is specified.
Definition: costmap_converter_interface.h:200


costmap_converter
Author(s): Christoph Rösmann , Franz Albers , Otniel Rinaldo
autogenerated on Fri Sep 20 2024 02:19:25