costmap_navigation_server.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2018, Magazino GmbH, Sebastian Pütz, Jorge Santos Simón
3  *
4  * Redistribution and use in source and binary forms, with or without
5  * modification, are permitted provided that the following conditions
6  * are met:
7  *
8  * 1. Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  *
11  * 2. Redistributions in binary form must reproduce the above
12  * copyright notice, this list of conditions and the following
13  * disclaimer in the documentation and/or other materials provided
14  * with the distribution.
15  *
16  * 3. Neither the name of the copyright holder nor the names of its
17  * contributors may be used to endorse or promote products derived
18  * from this software without specific prior written permission.
19  *
20  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31  * POSSIBILITY OF SUCH DAMAGE.
32  *
33  * costmap_navigation_server.cpp
34  *
35  * authors:
36  * Sebastian Pütz <spuetz@uni-osnabrueck.de>
37  * Jorge Santos Simón <santos@magazino.eu>
38  *
39  */
40 
41 #include <nav_msgs/Path.h>
42 #include <geometry_msgs/PoseArray.h>
45 #include <mbf_msgs/MoveBaseAction.h>
46 #include <mbf_abstract_nav/MoveBaseFlexConfig.h>
51 
53 
54 namespace mbf_costmap_nav
55 {
56 
57 
59  AbstractNavigationServer(tf_listener_ptr),
60  recovery_plugin_loader_("mbf_costmap_core", "mbf_costmap_core::CostmapRecovery"),
61  nav_core_recovery_plugin_loader_("nav_core", "nav_core::RecoveryBehavior"),
62  controller_plugin_loader_("mbf_costmap_core", "mbf_costmap_core::CostmapController"),
63  nav_core_controller_plugin_loader_("nav_core", "nav_core::BaseLocalPlanner"),
64  planner_plugin_loader_("mbf_costmap_core", "mbf_costmap_core::CostmapPlanner"),
65  nav_core_planner_plugin_loader_("nav_core", "nav_core::BaseGlobalPlanner"),
66  global_costmap_ptr_(new costmap_2d::Costmap2DROS("global_costmap", *tf_listener_ptr_)),
67  local_costmap_ptr_(new costmap_2d::Costmap2DROS("local_costmap", *tf_listener_ptr_)),
68  setup_reconfigure_(false), shutdown_costmaps_(false), costmaps_users_(0)
69 {
70  // even if shutdown_costmaps is a dynamically reconfigurable parameter, we
71  // need it here to decide whether to start or not the costmaps on starting up
72  private_nh_.param("shutdown_costmaps", shutdown_costmaps_, false);
73 
74  // initialize costmaps stopped if shutdown_costmaps is true
76  {
77  local_costmap_ptr_->stop();
78  global_costmap_ptr_->stop();
79  }
80 
81  // advertise services and current goal topic
90 
91  // dynamic reconfigure server for mbf_costmap_nav configuration; also include abstract server parameters
92  dsrv_costmap_ = boost::make_shared<dynamic_reconfigure::Server<mbf_costmap_nav::MoveBaseFlexConfig> >(private_nh_);
93  dsrv_costmap_->setCallback(boost::bind(&CostmapNavigationServer::reconfigure, this, _1, _2));
94 
95  // initialize all plugins
97 
98  // start all action servers
100 }
101 
103  const std::string name,
105 {
106  return boost::make_shared<mbf_costmap_nav::CostmapPlannerExecution>(
107  name,
108  boost::static_pointer_cast<mbf_costmap_core::CostmapPlanner>(plugin_ptr),
109  boost::ref(global_costmap_ptr_),
110  last_config_,
113 }
114 
116  const std::string name,
118 {
119  return boost::make_shared<mbf_costmap_nav::CostmapControllerExecution>(
120  name,
121  boost::static_pointer_cast<mbf_costmap_core::CostmapController>(plugin_ptr),
122  vel_pub_,
123  goal_pub_,
125  boost::ref(local_costmap_ptr_),
126  last_config_,
129 }
130 
132  const std::string name,
134 {
135  return boost::make_shared<mbf_costmap_nav::CostmapRecoveryExecution>(
136  name,
137  boost::static_pointer_cast<mbf_costmap_core::CostmapRecovery>(plugin_ptr),
139  boost::ref(global_costmap_ptr_),
140  boost::ref(local_costmap_ptr_),
141  last_config_,
144 }
145 
147 {
149  try
150  {
151  planner_ptr = boost::static_pointer_cast<mbf_abstract_core::AbstractPlanner>(
152  planner_plugin_loader_.createInstance(planner_type));
153  std::string planner_name = planner_plugin_loader_.getName(planner_type);
154  ROS_DEBUG_STREAM("mbf_costmap_core-based planner plugin " << planner_name << " loaded.");
155  }
156  catch (const pluginlib::PluginlibException &ex_mbf_core)
157  {
158  ROS_DEBUG_STREAM("Failed to load the " << planner_type << " planner as a mbf_costmap_core-based plugin."
159  << " Try to load as a nav_core-based plugin. " << ex_mbf_core.what());
160  try
161  {
162  // For plugins still based on old nav_core API, we load them and pass to a new MBF API that will act as wrapper
163  boost::shared_ptr<nav_core::BaseGlobalPlanner> nav_core_planner_ptr = nav_core_planner_plugin_loader_.createInstance(planner_type);
164  planner_ptr = boost::make_shared<mbf_nav_core_wrapper::WrapperGlobalPlanner>(nav_core_planner_ptr);
165  std::string planner_name = nav_core_planner_plugin_loader_.getName(planner_type);
166  ROS_DEBUG_STREAM("nav_core-based planner plugin " << planner_name << " loaded");
167  }
168  catch (const pluginlib::PluginlibException &ex_nav_core)
169  {
170  ROS_FATAL_STREAM("Failed to load the " << planner_type << " planner, are you sure it's properly registered"
171  << " and that the containing library is built? " << ex_mbf_core.what() << " " << ex_nav_core.what());
172  }
173  }
174 
175  return planner_ptr;
176 }
177 
179  const std::string& name,
180  const mbf_abstract_core::AbstractPlanner::Ptr& planner_ptr
181 )
182 {
183  mbf_costmap_core::CostmapPlanner::Ptr costmap_planner_ptr
184  = boost::static_pointer_cast<mbf_costmap_core::CostmapPlanner>(planner_ptr);
185  ROS_DEBUG_STREAM("Initialize planner \"" << name << "\".");
186 
187  if (!global_costmap_ptr_)
188  {
189  ROS_FATAL_STREAM("The costmap pointer has not been initialized!");
190  return false;
191  }
192 
193  costmap_planner_ptr->initialize(name, global_costmap_ptr_.get());
194  ROS_DEBUG("Planner plugin initialized.");
195  return true;
196 }
197 
198 
200 {
202  try
203  {
204  controller_ptr = controller_plugin_loader_.createInstance(controller_type);
205  std::string controller_name = controller_plugin_loader_.getName(controller_type);
206  ROS_DEBUG_STREAM("mbf_costmap_core-based controller plugin " << controller_name << " loaded.");
207  }
208  catch (const pluginlib::PluginlibException &ex_mbf_core)
209  {
210  ROS_DEBUG_STREAM("Failed to load the " << controller_type << " controller as a mbf_costmap_core-based plugin;"
211  << " we will retry to load as a nav_core-based plugin. " << ex_mbf_core.what());
212  try
213  {
214  // For plugins still based on old nav_core API, we load them and pass to a new MBF API that will act as wrapper
215  boost::shared_ptr<nav_core::BaseLocalPlanner> nav_core_controller_ptr
216  = nav_core_controller_plugin_loader_.createInstance(controller_type);
217  controller_ptr = boost::make_shared<mbf_nav_core_wrapper::WrapperLocalPlanner>(nav_core_controller_ptr);
218  std::string controller_name = nav_core_controller_plugin_loader_.getName(controller_type);
219  ROS_DEBUG_STREAM("nav_core-based controller plugin " << controller_name << " loaded.");
220  }
221  catch (const pluginlib::PluginlibException &ex_nav_core)
222  {
223  ROS_FATAL_STREAM("Failed to load the " << controller_type << " controller, are you sure it's properly registered"
224  << " and that the containing library is built? " << ex_mbf_core.what() << " " << ex_nav_core.what());
225  }
226  }
227  return controller_ptr;
228 }
229 
231  const std::string& name,
232  const mbf_abstract_core::AbstractController::Ptr& controller_ptr)
233 {
234  ROS_DEBUG_STREAM("Initialize controller \"" << name << "\".");
235 
236  if (!tf_listener_ptr_)
237  {
238  ROS_FATAL_STREAM("The tf listener pointer has not been initialized!");
239  return false;
240  }
241 
242  if (!local_costmap_ptr_)
243  {
244  ROS_FATAL_STREAM("The costmap pointer has not been initialized!");
245  return false;
246  }
247 
248  mbf_costmap_core::CostmapController::Ptr costmap_controller_ptr
249  = boost::static_pointer_cast<mbf_costmap_core::CostmapController>(controller_ptr);
250  costmap_controller_ptr->initialize(name, tf_listener_ptr_.get(), local_costmap_ptr_.get());
251  ROS_DEBUG_STREAM("Controller plugin \"" << name << "\" initialized.");
252  return true;
253 }
254 
256  const std::string& recovery_type)
257 {
259 
260  try
261  {
262  recovery_ptr = boost::static_pointer_cast<mbf_abstract_core::AbstractRecovery>(
263  recovery_plugin_loader_.createInstance(recovery_type));
264  std::string recovery_name = recovery_plugin_loader_.getName(recovery_type);
265  ROS_DEBUG_STREAM("mbf_costmap_core-based recovery behavior plugin " << recovery_name << " loaded.");
266  }
267  catch (pluginlib::PluginlibException &ex_mbf_core)
268  {
269  ROS_DEBUG_STREAM("Failed to load the " << recovery_type << " recovery behavior as a mbf_costmap_core-based plugin;"
270  << " Retry to load as a nav_core-based plugin. " << ex_mbf_core.what());
271  try
272  {
273  // For plugins still based on old nav_core API, we load them and pass to a new MBF API that will act as wrapper
274  boost::shared_ptr<nav_core::RecoveryBehavior> nav_core_recovery_ptr =
275  nav_core_recovery_plugin_loader_.createInstance(recovery_type);
276 
277  recovery_ptr = boost::make_shared<mbf_nav_core_wrapper::WrapperRecoveryBehavior>(nav_core_recovery_ptr);
278  std::string recovery_name = recovery_plugin_loader_.getName(recovery_type);
279  ROS_DEBUG_STREAM("nav_core-based recovery behavior plugin " << recovery_name << " loaded.");
280 
281  }
282  catch (const pluginlib::PluginlibException &ex_nav_core)
283  {
284  ROS_FATAL_STREAM("Failed to load the " << recovery_type << " recovery behavior, are you sure it's properly registered"
285  << " and that the containing library is built? " << ex_mbf_core.what() << " " << ex_nav_core.what());
286  }
287  }
288 
289  return recovery_ptr;
290 }
291 
293  const std::string& name,
294  const mbf_abstract_core::AbstractRecovery::Ptr& behavior_ptr)
295 {
296  ROS_DEBUG_STREAM("Initialize recovery behavior \"" << name << "\".");
297 
298  if (!tf_listener_ptr_)
299  {
300  ROS_FATAL_STREAM("The tf listener pointer has not been initialized!");
301  return false;
302  }
303 
304  if (!local_costmap_ptr_)
305  {
306  ROS_FATAL_STREAM("The local costmap pointer has not been initialized!");
307  return false;
308  }
309 
310  if (!global_costmap_ptr_)
311  {
312  ROS_FATAL_STREAM("The global costmap pointer has not been initialized!");
313  return false;
314  }
315 
317  boost::static_pointer_cast<mbf_costmap_core::CostmapRecovery>(behavior_ptr);
318  behavior->initialize(name, tf_listener_ptr_.get(), global_costmap_ptr_.get(), local_costmap_ptr_.get());
319  ROS_DEBUG_STREAM("Recovery behavior plugin \"" << name << "\" initialized.");
320  return true;
321 }
322 
323 
325 {
326  AbstractNavigationServer::stop();
327  ROS_INFO_STREAM_NAMED("mbf_costmap_nav", "Stopping local and global costmap for shutdown");
328  local_costmap_ptr_->stop();
329  global_costmap_ptr_->stop();
330 }
331 
332 
334 {
335 }
336 
337 void CostmapNavigationServer::reconfigure(mbf_costmap_nav::MoveBaseFlexConfig &config, uint32_t level)
338 {
339  // Make sure we have the original configuration the first time we're called, so we can restore it if needed
340  if (!setup_reconfigure_)
341  {
342  default_config_ = config;
343  setup_reconfigure_ = true;
344  }
345 
346  if (config.restore_defaults)
347  {
348  config = default_config_;
349  // if someone sets restore defaults on the parameter server, prevent looping
350  config.restore_defaults = false;
351  }
352 
353  // fill the abstract configuration common to all MBF-based navigation
354  mbf_abstract_nav::MoveBaseFlexConfig abstract_config;
355  abstract_config.planner_frequency = config.planner_frequency;
356  abstract_config.planner_patience = config.planner_patience;
357  abstract_config.planner_max_retries = config.planner_max_retries;
358  abstract_config.controller_frequency = config.controller_frequency;
359  abstract_config.controller_patience = config.controller_patience;
360  abstract_config.controller_max_retries = config.controller_max_retries;
361  abstract_config.recovery_enabled = config.recovery_enabled;
362  abstract_config.recovery_patience = config.recovery_patience;
363  abstract_config.oscillation_timeout = config.oscillation_timeout;
364  abstract_config.oscillation_distance = config.oscillation_distance;
365  abstract_config.restore_defaults = config.restore_defaults;
367 
368  // handle costmap activation reconfiguration here.
369  shutdown_costmaps_delay_ = ros::Duration(config.shutdown_costmaps_delay);
371  ROS_WARN("Zero shutdown costmaps delay is not recommended, as it forces us to enable costmaps on each action");
372 
373  if (shutdown_costmaps_ && !config.shutdown_costmaps)
374  {
376  shutdown_costmaps_ = config.shutdown_costmaps;
377  }
378  if (!shutdown_costmaps_ && config.shutdown_costmaps)
379  {
380  shutdown_costmaps_ = config.shutdown_costmaps;
382  }
383 
384  last_config_ = config;
385 }
386 
387 bool CostmapNavigationServer::callServiceCheckPointCost(mbf_msgs::CheckPoint::Request &request,
388  mbf_msgs::CheckPoint::Response &response)
389 {
390  // selecting the requested costmap
391  CostmapPtr costmap;
392  std::string costmap_name;
393  switch (request.costmap)
394  {
395  case mbf_msgs::CheckPoint::Request::LOCAL_COSTMAP:
396  costmap = local_costmap_ptr_;
397  costmap_name = "local costmap";
398  break;
399  case mbf_msgs::CheckPoint::Request::GLOBAL_COSTMAP:
400  costmap = global_costmap_ptr_;
401  costmap_name = "global costmap";
402  break;
403  default:
404  ROS_ERROR_STREAM("No valid costmap provided; options are "
405  << mbf_msgs::CheckPoint::Request::LOCAL_COSTMAP << ": local costmap, "
406  << mbf_msgs::CheckPoint::Request::GLOBAL_COSTMAP << ": global costmap");
407  return false;
408  }
409 
410  // get target point as x, y coordinates
411  std::string costmap_frame = costmap->getGlobalFrameID();
412 
413  geometry_msgs::PointStamped point;
414  if (! mbf_utility::transformPoint(*tf_listener_ptr_, costmap_frame, request.point.header.stamp,
415  ros::Duration(0.5), request.point, global_frame_, point))
416  {
417  ROS_ERROR_STREAM("Transform target point to " << costmap_name << " frame '" << costmap_frame << "' failed");
418  return false;
419  }
420 
421  double x = point.point.x;
422  double y = point.point.y;
423 
424  // ensure costmaps are active so cost reflects latest sensor readings
426  unsigned int mx, my;
427  if (!costmap->getCostmap()->worldToMap(x, y, mx, my))
428  {
429  // point is outside of the map
430  response.state = static_cast<uint8_t>(mbf_msgs::CheckPoint::Response::OUTSIDE);
431  ROS_DEBUG_STREAM("Point [" << x << ", " << y << "] is outside the map (cost = " << response.cost << ")");
432  }
433  else
434  {
435  // lock costmap so content doesn't change while checking cell costs
436  boost::unique_lock<costmap_2d::Costmap2D::mutex_t> lock(*(costmap->getCostmap()->getMutex()));
437 
438  // get cost of cell under point and classify as one of the states: UNKNOWN, LETHAL, INSCRIBED, FREE
439  response.cost = costmap->getCostmap()->getCost(mx, my);
440  switch (response.cost)
441  {
443  response.state = static_cast<uint8_t>(mbf_msgs::CheckPoint::Response::UNKNOWN);
444  ROS_DEBUG_STREAM("Point [" << x << ", " << y << "] is in unknown space! (cost = " << response.cost << ")");
445  break;
447  response.state = static_cast<uint8_t>(mbf_msgs::CheckPoint::Response::LETHAL);
448  ROS_DEBUG_STREAM("Point [" << x << ", " << y << "] is in collision! (cost = " << response.cost << ")");
449  break;
451  response.state = static_cast<uint8_t>(mbf_msgs::CheckPoint::Response::INSCRIBED);
452  ROS_DEBUG_STREAM("Point [" << x << ", " << y << "] is near an obstacle (cost = " << response.cost << ")");
453  break;
454  default:
455  response.state = static_cast<uint8_t>(mbf_msgs::CheckPoint::Response::FREE);
456  ROS_DEBUG_STREAM("Point [" << x << ", " << y << "] is free (cost = " << response.cost << ")");
457  break;
458  }
459  }
460 
462  return true;
463 }
464 
465 bool CostmapNavigationServer::callServiceCheckPoseCost(mbf_msgs::CheckPose::Request &request,
466  mbf_msgs::CheckPose::Response &response)
467 {
468  // selecting the requested costmap
469  CostmapPtr costmap;
470  std::string costmap_name;
471  switch (request.costmap)
472  {
473  case mbf_msgs::CheckPose::Request::LOCAL_COSTMAP:
474  costmap = local_costmap_ptr_;
475  costmap_name = "local costmap";
476  break;
477  case mbf_msgs::CheckPose::Request::GLOBAL_COSTMAP:
478  costmap = global_costmap_ptr_;
479  costmap_name = "global costmap";
480  break;
481  default:
482  ROS_ERROR_STREAM("No valid costmap provided; options are "
483  << mbf_msgs::CheckPose::Request::LOCAL_COSTMAP << ": local costmap, "
484  << mbf_msgs::CheckPose::Request::GLOBAL_COSTMAP << ": global costmap");
485  return false;
486  }
487 
488  // get target pose or current robot pose as x, y, yaw coordinates
489  std::string costmap_frame = costmap->getGlobalFrameID();
490 
491  geometry_msgs::PoseStamped pose;
492  if (request.current_pose)
493  {
494  if (! mbf_utility::getRobotPose(*tf_listener_ptr_, robot_frame_, costmap_frame, ros::Duration(0.5), pose))
495  {
496  ROS_ERROR_STREAM("Get robot pose on " << costmap_name << " frame '" << costmap_frame << "' failed");
497  return false;
498  }
499  }
500  else
501  {
502  if (! mbf_utility::transformPose(*tf_listener_ptr_, costmap_frame, request.pose.header.stamp,
503  ros::Duration(0.5), request.pose, global_frame_, pose))
504  {
505  ROS_ERROR_STREAM("Transform target pose to " << costmap_name << " frame '" << costmap_frame << "' failed");
506  return false;
507  }
508  }
509 
510  double x = pose.pose.position.x;
511  double y = pose.pose.position.y;
512  double yaw = tf::getYaw(pose.pose.orientation);
513 
514  // ensure costmaps are active so cost reflects latest sensor readings
516 
517  // pad raw footprint to the requested safety distance; note that we discard footprint_padding parameter effect
518  std::vector<geometry_msgs::Point> footprint = costmap->getUnpaddedRobotFootprint();
519  costmap_2d::padFootprint(footprint, request.safety_dist);
520 
521  // use a footprint helper instance to get all the cells totally or partially within footprint polygon
523  std::vector<base_local_planner::Position2DInt> footprint_cells =
524  fph.getFootprintCells(Eigen::Vector3f(x, y, yaw), footprint, *costmap->getCostmap(), true);
525  response.state = mbf_msgs::CheckPose::Response::FREE;
526  if (footprint_cells.empty())
527  {
528  // no cells within footprint polygon must mean that robot is completely outside of the map
529  response.state = std::max(response.state, static_cast<uint8_t>(mbf_msgs::CheckPose::Response::OUTSIDE));
530  }
531  else
532  {
533  // lock costmap so content doesn't change while adding cell costs
534  boost::unique_lock<costmap_2d::Costmap2D::mutex_t> lock(*(costmap->getCostmap()->getMutex()));
535 
536  // integrate the cost of all cells; state value precedence is UNKNOWN > LETHAL > INSCRIBED > FREE
537  for (int i = 0; i < footprint_cells.size(); ++i)
538  {
539  unsigned char cost = costmap->getCostmap()->getCost(footprint_cells[i].x, footprint_cells[i].y);
540  switch (cost)
541  {
543  response.state = std::max(response.state, static_cast<uint8_t>(mbf_msgs::CheckPose::Response::UNKNOWN));
544  response.cost += cost * (request.unknown_cost_mult ? request.unknown_cost_mult : 1.0);
545  break;
547  response.state = std::max(response.state, static_cast<uint8_t>(mbf_msgs::CheckPose::Response::LETHAL));
548  response.cost += cost * (request.lethal_cost_mult ? request.lethal_cost_mult : 1.0);
549  break;
551  response.state = std::max(response.state, static_cast<uint8_t>(mbf_msgs::CheckPose::Response::INSCRIBED));
552  response.cost += cost * (request.inscrib_cost_mult ? request.inscrib_cost_mult : 1.0);
553  break;
554  default:response.cost += cost;
555  break;
556  }
557  }
558  }
559 
560  // Provide some details of the outcome
561  switch (response.state)
562  {
563  case mbf_msgs::CheckPose::Response::OUTSIDE:
564  ROS_DEBUG_STREAM("Pose [" << x << ", " << y << ", " << yaw << "] is outside the map (cost = " << response.cost
565  << "; safety distance = " << request.safety_dist << ")");
566  break;
567  case mbf_msgs::CheckPose::Response::UNKNOWN:
568  ROS_DEBUG_STREAM("Pose [" << x << ", " << y << ", " << yaw << "] is in unknown space! (cost = " << response.cost
569  << "; safety distance = " << request.safety_dist << ")");
570  break;
571  case mbf_msgs::CheckPose::Response::LETHAL:
572  ROS_DEBUG_STREAM("Pose [" << x << ", " << y << ", " << yaw << "] is in collision! (cost = " << response.cost
573  << "; safety distance = " << request.safety_dist << ")");
574  break;
575  case mbf_msgs::CheckPose::Response::INSCRIBED:
576  ROS_DEBUG_STREAM("Pose [" << x << ", " << y << ", " << yaw << "] is near an obstacle (cost = " << response.cost
577  << "; safety distance = " << request.safety_dist << ")");
578  break;
579  case mbf_msgs::CheckPose::Response::FREE:
580  ROS_DEBUG_STREAM("Pose [" << x << ", " << y << ", " << yaw << "] is free (cost = " << response.cost
581  << "; safety distance = " << request.safety_dist << ")");
582  break;
583  }
584 
586  return true;
587 }
588 
589 bool CostmapNavigationServer::callServiceCheckPathCost(mbf_msgs::CheckPath::Request &request,
590  mbf_msgs::CheckPath::Response &response)
591 {
592  // selecting the requested costmap
593  CostmapPtr costmap;
594  std::string costmap_name;
595  switch (request.costmap)
596  {
597  case mbf_msgs::CheckPath::Request::LOCAL_COSTMAP:
598  costmap = local_costmap_ptr_;
599  costmap_name = "local costmap";
600  break;
601  case mbf_msgs::CheckPath::Request::GLOBAL_COSTMAP:
602  costmap = global_costmap_ptr_;
603  costmap_name = "global costmap";
604  break;
605  default:ROS_ERROR_STREAM("No valid costmap provided; options are "
606  << mbf_msgs::CheckPath::Request::LOCAL_COSTMAP << ": local costmap, "
607  << mbf_msgs::CheckPath::Request::GLOBAL_COSTMAP << ": global costmap");
608  return false;
609  }
610 
611  // ensure costmaps are active so cost reflects latest sensor readings
613 
614  // get target pose or current robot pose as x, y, yaw coordinates
615  std::string costmap_frame = costmap->getGlobalFrameID();
616 
617  // use a footprint helper instance to get all the cells totally or partially within footprint polygon
619 
620  std::vector<geometry_msgs::Point> footprint;
621  if (!request.path_cells_only)
622  {
623  // unless we want to check just the cells directly traversed by the path, pad raw footprint
624  // to the requested safety distance; note that we discard footprint_padding parameter effect
625  footprint = costmap->getUnpaddedRobotFootprint();
626  costmap_2d::padFootprint(footprint, request.safety_dist);
627  }
628 
629  // lock costmap so content doesn't change while adding cell costs
630  boost::unique_lock<costmap_2d::Costmap2D::mutex_t> lock(*(costmap->getCostmap()->getMutex()));
631 
632  geometry_msgs::PoseStamped pose;
633 
634  response.state = mbf_msgs::CheckPath::Response::FREE;
635 
636  for (int i = 0; i < request.path.poses.size(); ++i)
637  {
638  response.last_checked = i;
639 
640  if (! mbf_utility::transformPose(*tf_listener_ptr_, costmap_frame, request.path.header.stamp,
641  ros::Duration(0.5), request.path.poses[i], global_frame_, pose))
642  {
643  ROS_ERROR_STREAM("Transform target pose to " << costmap_name << " frame '" << costmap_frame << "' failed");
644  return false;
645  }
646 
647  double x = pose.pose.position.x;
648  double y = pose.pose.position.y;
649  double yaw = tf::getYaw(pose.pose.orientation);
650  std::vector<base_local_planner::Position2DInt> cells_to_check;
651  if (request.path_cells_only)
652  {
653  base_local_planner::Position2DInt cell;
654  if (costmap->getCostmap()->worldToMap(x, y, (unsigned int&)cell.x, (unsigned int&)cell.y))
655  cells_to_check.push_back(cell); // out of map if false; cells_to_check will be empty
656  }
657  else
658  {
659  cells_to_check = fph.getFootprintCells(Eigen::Vector3f(x, y, yaw), footprint, *costmap->getCostmap(), true);
660  }
661 
662  if (cells_to_check.empty())
663  {
664  // if path_cells_only is true, this means that current path's pose is outside the map
665  // if not, no cells within footprint polygon means that robot is completely outside of the map
666  response.state = std::max(response.state, static_cast<uint8_t>(mbf_msgs::CheckPath::Response::OUTSIDE));
667  }
668  else
669  {
670  // integrate the cost of all cells; state value precedence is UNKNOWN > LETHAL > INSCRIBED > FREE
671  // we apply the requested cost multipliers if different from zero (default value)
672  for (int j = 0; j < cells_to_check.size(); ++j)
673  {
674  unsigned char cost = costmap->getCostmap()->getCost(cells_to_check[j].x, cells_to_check[j].y);
675  switch (cost)
676  {
678  response.state = std::max(response.state, static_cast<uint8_t>(mbf_msgs::CheckPose::Response::UNKNOWN));
679  response.cost += cost * (request.unknown_cost_mult ? request.unknown_cost_mult : 1.0);
680  break;
682  response.state = std::max(response.state, static_cast<uint8_t>(mbf_msgs::CheckPath::Response::LETHAL));
683  response.cost += cost * (request.lethal_cost_mult ? request.lethal_cost_mult : 1.0);
684  break;
686  response.state = std::max(response.state, static_cast<uint8_t>(mbf_msgs::CheckPath::Response::INSCRIBED));
687  response.cost += cost * (request.inscrib_cost_mult ? request.inscrib_cost_mult : 1.0);
688  break;
689  default:response.cost += cost;
690  break;
691  }
692  }
693  }
694 
695  if (request.return_on && response.state >= request.return_on)
696  {
697  // i-th pose state is bad enough for the client, so provide some details of the outcome and abort checking
698  switch (response.state)
699  {
700  case mbf_msgs::CheckPath::Response::OUTSIDE:
701  ROS_DEBUG_STREAM("At pose " << i << " [" << x << ", " << y << ", " << yaw << "] path goes outside the map "
702  << "(cost = " << response.cost << "; safety distance = " << request.safety_dist << ")");
703  break;
704  case mbf_msgs::CheckPath::Response::UNKNOWN:
705  ROS_DEBUG_STREAM("At pose " << i << " [" << x << ", " << y << ", " << yaw << "] path goes in unknown space! "
706  << "(cost = " << response.cost << "; safety distance = " << request.safety_dist << ")");
707  break;
708  case mbf_msgs::CheckPath::Response::LETHAL:
709  ROS_DEBUG_STREAM("At pose " << i << " [" << x << ", " << y << ", " << yaw << "] path goes in collision! "
710  << "(cost = " << response.cost << "; safety distance = " << request.safety_dist << ")");
711  break;
712  case mbf_msgs::CheckPath::Response::INSCRIBED:
713  ROS_DEBUG_STREAM("At pose " << i << " [" << x << ", " << y << ", " << yaw << "] path goes near an obstacle "
714  << "(cost = " << response.cost << "; safety distance = " << request.safety_dist << ")");
715  break;
716  case mbf_msgs::CheckPath::Response::FREE:
717  ROS_DEBUG_STREAM("Path is entirely free (maximum cost = "
718  << response.cost << "; safety distance = " << request.safety_dist << ")");
719  break;
720  }
721 
722  break;
723  }
724 
725  i += request.skip_poses; // skip some poses to speedup processing (disabled by default)
726  }
727 
729  return true;
730 }
731 
732 bool CostmapNavigationServer::callServiceClearCostmaps(std_srvs::Empty::Request &request,
733  std_srvs::Empty::Response &response)
734 {
735  //clear both costmaps
736  local_costmap_ptr_->getCostmap()->getMutex()->lock();
737  local_costmap_ptr_->resetLayers();
738  local_costmap_ptr_->getCostmap()->getMutex()->unlock();
739 
740  global_costmap_ptr_->getCostmap()->getMutex()->lock();
741  global_costmap_ptr_->resetLayers();
742  global_costmap_ptr_->getCostmap()->getMutex()->unlock();
743  return true;
744 }
745 
747 {
748  boost::mutex::scoped_lock sl(check_costmaps_mutex_);
749 
751 
752  // Activate costmaps if we shutdown them when not moving and they are not already active. This method must be
753  // synchronized because start costmap can take up to 1/update freq., and concurrent calls to it can lead to segfaults
755  {
756  local_costmap_ptr_->start();
757  global_costmap_ptr_->start();
758  ROS_DEBUG_STREAM("Costmaps activated.");
759  }
760  ++costmaps_users_;
761 }
762 
764 {
765  --costmaps_users_;
767  {
768  // Delay costmaps shutdown by shutdown_costmaps_delay so we don't need to enable at each step of a normal
769  // navigation sequence, what is terribly inefficient; the timer is stopped on costmaps re-activation and
770  // reset after every new call to deactivate
773  }
774 }
775 
777 {
778  boost::mutex::scoped_lock sl(check_costmaps_mutex_);
779 
780  ROS_ASSERT_MSG(!costmaps_users_, "Deactivating costmaps with %u active users!", costmaps_users_);
781  local_costmap_ptr_->stop();
782  global_costmap_ptr_->stop();
783  ROS_DEBUG_STREAM("Costmaps deactivated.");
784 }
785 
786 } /* namespace mbf_costmap_nav */
virtual bool initializeControllerPlugin(const std::string &name, const mbf_abstract_core::AbstractController::Ptr &controller_ptr)
Initializes the controller plugin with its name, a pointer to the TransformListener and pointer to th...
bool callServiceCheckPathCost(mbf_msgs::CheckPath::Request &request, mbf_msgs::CheckPath::Response &response)
Callback method for the check_path_cost service.
CostmapPtr global_costmap_ptr_
Shared pointer to the common global costmap.
bool callServiceCheckPointCost(mbf_msgs::CheckPoint::Request &request, mbf_msgs::CheckPoint::Response &response)
Callback method for the check_point_cost service.
boost::mutex check_costmaps_mutex_
Start/stop costmaps mutex; concurrent calls to start can lead to segfault.
bool shutdown_costmaps_
Stop updating costmaps when not planning or controlling, if true.
CostmapNavigationServer(const TFPtr &tf_listener_ptr)
Constructor.
void reconfigure(mbf_costmap_nav::MoveBaseFlexConfig &config, uint32_t level)
Reconfiguration method called by dynamic reconfigure.
mbf_costmap_nav::MoveBaseFlexConfig default_config_
the default parameter configuration save
virtual mbf_abstract_nav::AbstractControllerExecution::Ptr newControllerExecution(const std::string name, const mbf_abstract_core::AbstractController::Ptr plugin_ptr)
shared pointer to a new ControllerExecution
virtual mbf_abstract_core::AbstractPlanner::Ptr loadPlannerPlugin(const std::string &planner_type)
Loads the plugin associated with the given planner_type parameter.
std::vector< base_local_planner::Position2DInt > getFootprintCells(Eigen::Vector3f pos, std::vector< geometry_msgs::Point > footprint_spec, const costmap_2d::Costmap2D &, bool fill)
virtual bool initializeRecoveryPlugin(const std::string &name, const mbf_abstract_core::AbstractRecovery::Ptr &behavior_ptr)
Initializes a recovery behavior plugin with its name and pointers to the global and local costmaps...
static double getYaw(const Quaternion &bt_q)
void stop()
virtual mbf_abstract_nav::AbstractPlannerExecution::Ptr newPlannerExecution(const std::string name, const mbf_abstract_core::AbstractPlanner::Ptr plugin_ptr)
shared pointer to a new PlannerExecution
bool getRobotPose(const TF &tf, const std::string &robot_frame, const std::string &global_frame, const ros::Duration &timeout, geometry_msgs::PoseStamped &robot_pose)
#define ROS_INFO_STREAM_NAMED(name, args)
virtual void reconfigure(mbf_abstract_nav::MoveBaseFlexConfig &config, uint32_t level)
void checkActivateCostmaps()
Check whether the costmaps should be activated.
pluginlib::ClassLoader< mbf_costmap_core::CostmapController > controller_plugin_loader_
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
ros::ServiceServer check_point_cost_srv_
Service Server for the check_point_cost service.
TFSIMD_FORCE_INLINE const tfScalar & y() const
#define ROS_WARN(...)
ros::ServiceServer clear_costmaps_srv_
Service Server for the clear_costmap service.
mbf_costmap_nav::MoveBaseFlexConfig last_config_
last configuration save
virtual mbf_abstract_core::AbstractRecovery::Ptr loadRecoveryPlugin(const std::string &recovery_type)
Loads a Recovery plugin associated with given recovery type parameter.
static const unsigned char INSCRIBED_INFLATED_OBSTACLE
ros::Duration shutdown_costmaps_delay_
costmpas delayed shutdown delay
pluginlib::ClassLoader< mbf_costmap_core::CostmapRecovery > recovery_plugin_loader_
#define ROS_FATAL_STREAM(args)
DynamicReconfigureServerCostmapNav dsrv_costmap_
Dynamic reconfigure server for the mbf_costmap2d_specific part.
bool param(const std::string &param_name, T &param_val, const T &default_val) const
#define ROS_ASSERT_MSG(cond,...)
void padFootprint(std::vector< geometry_msgs::Point > &footprint, double padding)
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
TFSIMD_FORCE_INLINE const tfScalar & x() const
uint16_t costmaps_users_
keep track of plugins using costmaps
#define ROS_DEBUG_STREAM(args)
virtual std::string getName(const std::string &lookup_name)
CostmapPtr local_costmap_ptr_
Shared pointer to the common local costmap.
bool callServiceClearCostmaps(std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
Callback method for the make_plan service.
void checkDeactivateCostmaps()
Check whether the costmaps should and could be deactivated.
ros::Timer shutdown_costmaps_timer_
costmpas delayed shutdown timer
pluginlib::ClassLoader< nav_core::BaseGlobalPlanner > nav_core_planner_plugin_loader_
static const unsigned char LETHAL_OBSTACLE
static const unsigned char NO_INFORMATION
ros::ServiceServer check_pose_cost_srv_
Service Server for the check_pose_cost service.
bool setup_reconfigure_
true, if the dynamic reconfigure has been setup
pluginlib::ClassLoader< nav_core::RecoveryBehavior > nav_core_recovery_plugin_loader_
ros::ServiceServer check_path_cost_srv_
Service Server for the check_path_cost service.
#define ROS_ERROR_STREAM(args)
pluginlib::ClassLoader< nav_core::BaseLocalPlanner > nav_core_controller_plugin_loader_
virtual mbf_abstract_core::AbstractController::Ptr loadControllerPlugin(const std::string &controller_type)
Loads the plugin associated with the given controller type parameter.
void deactivateCostmaps(const ros::TimerEvent &event)
Timer-triggered deactivation of both costmaps.
bool transformPoint(const TF &tf, const std::string &target_frame, const ros::Time &target_time, const ros::Duration &timeout, const geometry_msgs::PointStamped &in, const std::string &fixed_frame, geometry_msgs::PointStamped &out)
bool transformPose(const TF &tf, const std::string &target_frame, const ros::Time &target_time, const ros::Duration &timeout, const geometry_msgs::PoseStamped &in, const std::string &fixed_frame, geometry_msgs::PoseStamped &out)
bool callServiceCheckPoseCost(mbf_msgs::CheckPose::Request &request, mbf_msgs::CheckPose::Response &response)
Callback method for the check_pose_cost service.
virtual mbf_abstract_nav::AbstractRecoveryExecution::Ptr newRecoveryExecution(const std::string name, const mbf_abstract_core::AbstractRecovery::Ptr plugin_ptr)
shared pointer to a new RecoveryExecution
virtual bool initializePlannerPlugin(const std::string &name, const mbf_abstract_core::AbstractPlanner::Ptr &planner_ptr)
Initializes the controller plugin with its name and pointer to the costmap.
pluginlib::ClassLoader< mbf_costmap_core::CostmapPlanner > planner_plugin_loader_
#define ROS_DEBUG(...)


mbf_costmap_nav
Author(s): Sebastian Pütz
autogenerated on Tue Jun 18 2019 19:34:40