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 <tf/tf.h>
42 #include <nav_msgs/Path.h>
43 #include <geometry_msgs/PoseArray.h>
44 #include <mbf_msgs/MoveBaseAction.h>
45 #include <mbf_abstract_nav/MoveBaseFlexConfig.h>
50 
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 CostmapWrapper("global_costmap", tf_listener_ptr_)),
67  local_costmap_ptr_(new CostmapWrapper("local_costmap", tf_listener_ptr_)),
68  setup_reconfigure_(false)
69 {
70  // advertise services and current goal topic
79 
80  // dynamic reconfigure server for mbf_costmap_nav configuration; also include abstract server parameters
81  dsrv_costmap_ = boost::make_shared<dynamic_reconfigure::Server<mbf_costmap_nav::MoveBaseFlexConfig> >(private_nh_);
82  dsrv_costmap_->setCallback(boost::bind(&CostmapNavigationServer::reconfigure, this, _1, _2));
83 
84  // initialize all plugins
86 
87  // start all action servers
89 }
90 
92 {
93  // remove every plugin before its classLoader goes out of scope.
97 
102 }
103 
105  const std::string &plugin_name,
107 {
108  return boost::make_shared<mbf_costmap_nav::CostmapPlannerExecution>(
109  plugin_name,
110  boost::static_pointer_cast<mbf_costmap_core::CostmapPlanner>(plugin_ptr),
112  last_config_);
113 }
114 
116  const std::string &plugin_name,
118 {
119  return boost::make_shared<mbf_costmap_nav::CostmapControllerExecution>(
120  plugin_name,
121  boost::static_pointer_cast<mbf_costmap_core::CostmapController>(plugin_ptr),
122  vel_pub_,
123  goal_pub_,
126  last_config_);
127 }
128 
130  const std::string &plugin_name,
132 {
133  return boost::make_shared<mbf_costmap_nav::CostmapRecoveryExecution>(
134  plugin_name,
135  boost::static_pointer_cast<mbf_costmap_core::CostmapRecovery>(plugin_ptr),
139  last_config_);
140 }
141 
143 {
145  try
146  {
147  planner_ptr = boost::static_pointer_cast<mbf_abstract_core::AbstractPlanner>(
148  planner_plugin_loader_.createInstance(planner_type));
149  std::string planner_name = planner_plugin_loader_.getName(planner_type);
150  ROS_DEBUG_STREAM("mbf_costmap_core-based planner plugin " << planner_name << " loaded.");
151  }
152  catch (const pluginlib::PluginlibException &ex_mbf_core)
153  {
154  ROS_DEBUG_STREAM("Failed to load the " << planner_type << " planner as a mbf_costmap_core-based plugin."
155  << " Try to load as a nav_core-based plugin. " << ex_mbf_core.what());
156  try
157  {
158  // For plugins still based on old nav_core API, we load them and pass to a new MBF API that will act as wrapper
159  boost::shared_ptr<nav_core::BaseGlobalPlanner> nav_core_planner_ptr = nav_core_planner_plugin_loader_.createInstance(planner_type);
160  planner_ptr = boost::make_shared<mbf_nav_core_wrapper::WrapperGlobalPlanner>(nav_core_planner_ptr);
161  std::string planner_name = nav_core_planner_plugin_loader_.getName(planner_type);
162  ROS_DEBUG_STREAM("nav_core-based planner plugin " << planner_name << " loaded");
163  }
164  catch (const pluginlib::PluginlibException &ex_nav_core)
165  {
166  ROS_FATAL_STREAM("Failed to load the " << planner_type << " planner, are you sure it's properly registered"
167  << " and that the containing library is built? " << ex_mbf_core.what() << " " << ex_nav_core.what());
168  }
169  }
170 
171  return planner_ptr;
172 }
173 
175  const std::string &name,
176  const mbf_abstract_core::AbstractPlanner::Ptr &planner_ptr
177 )
178 {
179  mbf_costmap_core::CostmapPlanner::Ptr costmap_planner_ptr
180  = boost::static_pointer_cast<mbf_costmap_core::CostmapPlanner>(planner_ptr);
181  ROS_DEBUG_STREAM("Initialize planner \"" << name << "\".");
182 
183  if (!global_costmap_ptr_)
184  {
185  ROS_FATAL_STREAM("The costmap pointer has not been initialized!");
186  return false;
187  }
188 
189  costmap_planner_ptr->initialize(name, global_costmap_ptr_.get());
190  ROS_DEBUG("Planner plugin initialized.");
191  return true;
192 }
193 
194 
196 {
198  try
199  {
200  controller_ptr = controller_plugin_loader_.createInstance(controller_type);
201  std::string controller_name = controller_plugin_loader_.getName(controller_type);
202  ROS_DEBUG_STREAM("mbf_costmap_core-based controller plugin " << controller_name << " loaded.");
203  }
204  catch (const pluginlib::PluginlibException &ex_mbf_core)
205  {
206  ROS_DEBUG_STREAM("Failed to load the " << controller_type << " controller as a mbf_costmap_core-based plugin;"
207  << " we will retry to load as a nav_core-based plugin. " << ex_mbf_core.what());
208  try
209  {
210  // For plugins still based on old nav_core API, we load them and pass to a new MBF API that will act as wrapper
211  boost::shared_ptr<nav_core::BaseLocalPlanner> nav_core_controller_ptr
212  = nav_core_controller_plugin_loader_.createInstance(controller_type);
213  controller_ptr = boost::make_shared<mbf_nav_core_wrapper::WrapperLocalPlanner>(nav_core_controller_ptr);
214  std::string controller_name = nav_core_controller_plugin_loader_.getName(controller_type);
215  ROS_DEBUG_STREAM("nav_core-based controller plugin " << controller_name << " loaded.");
216  }
217  catch (const pluginlib::PluginlibException &ex_nav_core)
218  {
219  ROS_FATAL_STREAM("Failed to load the " << controller_type << " controller, are you sure it's properly registered"
220  << " and that the containing library is built? " << ex_mbf_core.what() << " " << ex_nav_core.what());
221  }
222  }
223  return controller_ptr;
224 }
225 
227  const std::string &name,
228  const mbf_abstract_core::AbstractController::Ptr &controller_ptr)
229 {
230  ROS_DEBUG_STREAM("Initialize controller \"" << name << "\".");
231 
232  if (!tf_listener_ptr_)
233  {
234  ROS_FATAL_STREAM("The tf listener pointer has not been initialized!");
235  return false;
236  }
237 
238  if (!local_costmap_ptr_)
239  {
240  ROS_FATAL_STREAM("The costmap pointer has not been initialized!");
241  return false;
242  }
243 
244  mbf_costmap_core::CostmapController::Ptr costmap_controller_ptr
245  = boost::static_pointer_cast<mbf_costmap_core::CostmapController>(controller_ptr);
246  costmap_controller_ptr->initialize(name, tf_listener_ptr_.get(), local_costmap_ptr_.get());
247  ROS_DEBUG_STREAM("Controller plugin \"" << name << "\" initialized.");
248  return true;
249 }
250 
252  const std::string &recovery_type)
253 {
255 
256  try
257  {
258  recovery_ptr = boost::static_pointer_cast<mbf_abstract_core::AbstractRecovery>(
259  recovery_plugin_loader_.createInstance(recovery_type));
260  std::string recovery_name = recovery_plugin_loader_.getName(recovery_type);
261  ROS_DEBUG_STREAM("mbf_costmap_core-based recovery behavior plugin " << recovery_name << " loaded.");
262  }
263  catch (pluginlib::PluginlibException &ex_mbf_core)
264  {
265  ROS_DEBUG_STREAM("Failed to load the " << recovery_type << " recovery behavior as a mbf_costmap_core-based plugin;"
266  << " Retry to load as a nav_core-based plugin. " << ex_mbf_core.what());
267  try
268  {
269  // For plugins still based on old nav_core API, we load them and pass to a new MBF API that will act as wrapper
270  boost::shared_ptr<nav_core::RecoveryBehavior> nav_core_recovery_ptr =
271  nav_core_recovery_plugin_loader_.createInstance(recovery_type);
272 
273  recovery_ptr = boost::make_shared<mbf_nav_core_wrapper::WrapperRecoveryBehavior>(nav_core_recovery_ptr);
274  std::string recovery_name = recovery_plugin_loader_.getName(recovery_type);
275  ROS_DEBUG_STREAM("nav_core-based recovery behavior plugin " << recovery_name << " loaded.");
276 
277  }
278  catch (const pluginlib::PluginlibException &ex_nav_core)
279  {
280  ROS_FATAL_STREAM("Failed to load the " << recovery_type << " recovery behavior, are you sure it's properly registered"
281  << " and that the containing library is built? " << ex_mbf_core.what() << " " << ex_nav_core.what());
282  }
283  }
284 
285  return recovery_ptr;
286 }
287 
289  const std::string &name,
290  const mbf_abstract_core::AbstractRecovery::Ptr &behavior_ptr)
291 {
292  ROS_DEBUG_STREAM("Initialize recovery behavior \"" << name << "\".");
293 
294  if (!tf_listener_ptr_)
295  {
296  ROS_FATAL_STREAM("The tf listener pointer has not been initialized!");
297  return false;
298  }
299 
300  if (!local_costmap_ptr_)
301  {
302  ROS_FATAL_STREAM("The local costmap pointer has not been initialized!");
303  return false;
304  }
305 
306  if (!global_costmap_ptr_)
307  {
308  ROS_FATAL_STREAM("The global costmap pointer has not been initialized!");
309  return false;
310  }
311 
313  boost::static_pointer_cast<mbf_costmap_core::CostmapRecovery>(behavior_ptr);
314  behavior->initialize(name, tf_listener_ptr_.get(), global_costmap_ptr_.get(), local_costmap_ptr_.get());
315  ROS_DEBUG_STREAM("Recovery behavior plugin \"" << name << "\" initialized.");
316  return true;
317 }
318 
319 
321 {
322  AbstractNavigationServer::stop();
323  ROS_INFO_STREAM_NAMED("mbf_costmap_nav", "Stopping local and global costmap for shutdown");
324  local_costmap_ptr_->stop();
325  global_costmap_ptr_->stop();
326 }
327 
328 void CostmapNavigationServer::reconfigure(mbf_costmap_nav::MoveBaseFlexConfig &config, uint32_t level)
329 {
330  // Make sure we have the original configuration the first time we're called, so we can restore it if needed
331  if (!setup_reconfigure_)
332  {
333  default_config_ = config;
334  setup_reconfigure_ = true;
335  }
336 
337  if (config.restore_defaults)
338  {
339  config = default_config_;
340  // if someone sets restore defaults on the parameter server, prevent looping
341  config.restore_defaults = false;
342  }
343 
344  // fill the abstract configuration common to all MBF-based navigation
345  mbf_abstract_nav::MoveBaseFlexConfig abstract_config;
346  abstract_config.planner_frequency = config.planner_frequency;
347  abstract_config.planner_patience = config.planner_patience;
348  abstract_config.planner_max_retries = config.planner_max_retries;
349  abstract_config.controller_frequency = config.controller_frequency;
350  abstract_config.controller_patience = config.controller_patience;
351  abstract_config.controller_max_retries = config.controller_max_retries;
352  abstract_config.recovery_enabled = config.recovery_enabled;
353  abstract_config.recovery_patience = config.recovery_patience;
354  abstract_config.oscillation_timeout = config.oscillation_timeout;
355  abstract_config.oscillation_distance = config.oscillation_distance;
356  abstract_config.restore_defaults = config.restore_defaults;
358 
359  // also reconfigure costmaps
360  local_costmap_ptr_->reconfigure(config.shutdown_costmaps, config.shutdown_costmaps_delay);
361  global_costmap_ptr_->reconfigure(config.shutdown_costmaps, config.shutdown_costmaps_delay);
362 
363  last_config_ = config;
364 }
365 
366 bool CostmapNavigationServer::callServiceCheckPointCost(mbf_msgs::CheckPoint::Request &request,
367  mbf_msgs::CheckPoint::Response &response)
368 {
369  // selecting the requested costmap
370  CostmapWrapper::Ptr costmap;
371  std::string costmap_name;
372  switch (request.costmap)
373  {
374  case mbf_msgs::CheckPoint::Request::LOCAL_COSTMAP:
375  costmap = local_costmap_ptr_;
376  costmap_name = "local costmap";
377  break;
378  case mbf_msgs::CheckPoint::Request::GLOBAL_COSTMAP:
379  costmap = global_costmap_ptr_;
380  costmap_name = "global costmap";
381  break;
382  default:
383  ROS_ERROR_STREAM("No valid costmap provided; options are "
384  << mbf_msgs::CheckPoint::Request::LOCAL_COSTMAP << ": local costmap, "
385  << mbf_msgs::CheckPoint::Request::GLOBAL_COSTMAP << ": global costmap");
386  return false;
387  }
388 
389  // get target point as x, y coordinates
390  std::string costmap_frame = costmap->getGlobalFrameID();
391 
392  geometry_msgs::PointStamped point;
393  if (!mbf_utility::transformPoint(*tf_listener_ptr_, costmap_frame, ros::Duration(0.5), request.point, point))
394  {
395  ROS_ERROR_STREAM("Transform target point to " << costmap_name << " frame '" << costmap_frame << "' failed");
396  return false;
397  }
398 
399  double x = point.point.x;
400  double y = point.point.y;
401 
402  // ensure costmap is active so cost reflects latest sensor readings
403  costmap->checkActivate();
404  unsigned int mx, my;
405  if (!costmap->getCostmap()->worldToMap(x, y, mx, my))
406  {
407  // point is outside of the map
408  response.state = static_cast<uint8_t>(mbf_msgs::CheckPoint::Response::OUTSIDE);
409  ROS_DEBUG_STREAM("Point [" << x << ", " << y << "] is outside the map (cost = " << response.cost << ")");
410  }
411  else
412  {
413  // lock costmap so content doesn't change while checking cell costs
414  boost::unique_lock<costmap_2d::Costmap2D::mutex_t> lock(*(costmap->getCostmap()->getMutex()));
415 
416  // get cost of cell under point and classify as one of the states: UNKNOWN, LETHAL, INSCRIBED, FREE
417  response.cost = costmap->getCostmap()->getCost(mx, my);
418  switch (response.cost)
419  {
421  response.state = static_cast<uint8_t>(mbf_msgs::CheckPoint::Response::UNKNOWN);
422  ROS_DEBUG_STREAM("Point [" << x << ", " << y << "] is in unknown space! (cost = " << response.cost << ")");
423  break;
425  response.state = static_cast<uint8_t>(mbf_msgs::CheckPoint::Response::LETHAL);
426  ROS_DEBUG_STREAM("Point [" << x << ", " << y << "] is in collision! (cost = " << response.cost << ")");
427  break;
429  response.state = static_cast<uint8_t>(mbf_msgs::CheckPoint::Response::INSCRIBED);
430  ROS_DEBUG_STREAM("Point [" << x << ", " << y << "] is near an obstacle (cost = " << response.cost << ")");
431  break;
432  default:
433  response.state = static_cast<uint8_t>(mbf_msgs::CheckPoint::Response::FREE);
434  ROS_DEBUG_STREAM("Point [" << x << ", " << y << "] is free (cost = " << response.cost << ")");
435  break;
436  }
437  }
438 
439  costmap->checkDeactivate();
440  return true;
441 }
442 
443 bool CostmapNavigationServer::callServiceCheckPoseCost(mbf_msgs::CheckPose::Request &request,
444  mbf_msgs::CheckPose::Response &response)
445 {
446  // selecting the requested costmap
447  CostmapWrapper::Ptr costmap;
448  std::string costmap_name;
449  switch (request.costmap)
450  {
451  case mbf_msgs::CheckPose::Request::LOCAL_COSTMAP:
452  costmap = local_costmap_ptr_;
453  costmap_name = "local costmap";
454  break;
455  case mbf_msgs::CheckPose::Request::GLOBAL_COSTMAP:
456  costmap = global_costmap_ptr_;
457  costmap_name = "global costmap";
458  break;
459  default:
460  ROS_ERROR_STREAM("No valid costmap provided; options are "
461  << mbf_msgs::CheckPose::Request::LOCAL_COSTMAP << ": local costmap, "
462  << mbf_msgs::CheckPose::Request::GLOBAL_COSTMAP << ": global costmap");
463  return false;
464  }
465 
466  // get target pose or current robot pose as x, y, yaw coordinates
467  std::string costmap_frame = costmap->getGlobalFrameID();
468 
469  geometry_msgs::PoseStamped pose;
470  if (request.current_pose)
471  {
472  if (!mbf_utility::getRobotPose(*tf_listener_ptr_, robot_frame_, costmap_frame, ros::Duration(0.5), pose))
473  {
474  ROS_ERROR_STREAM("Get robot pose on " << costmap_name << " frame '" << costmap_frame << "' failed");
475  return false;
476  }
477  }
478  else
479  {
480  if (!mbf_utility::transformPose(*tf_listener_ptr_, costmap_frame, ros::Duration(0.5), request.pose, pose))
481  {
482  ROS_ERROR_STREAM("Transform target pose to " << costmap_name << " frame '" << costmap_frame << "' failed");
483  return false;
484  }
485  }
486 
487  double x = pose.pose.position.x;
488  double y = pose.pose.position.y;
489  double yaw = tf::getYaw(pose.pose.orientation);
490 
491  // ensure costmap is active so cost reflects latest sensor readings
492  costmap->checkActivate();
493 
494  // pad raw footprint to the requested safety distance; note that we discard footprint_padding parameter effect
495  std::vector<geometry_msgs::Point> footprint = costmap->getUnpaddedRobotFootprint();
496  costmap_2d::padFootprint(footprint, request.safety_dist);
497 
498  // use footprint helper to get all the cells totally or partially within footprint polygon
499  std::vector<Cell> footprint_cells =
500  FootprintHelper::getFootprintCells(x, y, yaw, footprint, *costmap->getCostmap(), true);
501  response.state = mbf_msgs::CheckPose::Response::FREE;
502  if (footprint_cells.empty())
503  {
504  // no cells within footprint polygon must mean that robot is completely outside of the map
505  response.state = std::max(response.state, static_cast<uint8_t>(mbf_msgs::CheckPose::Response::OUTSIDE));
506  }
507  else
508  {
509  // lock costmap so content doesn't change while adding cell costs
510  boost::unique_lock<costmap_2d::Costmap2D::mutex_t> lock(*(costmap->getCostmap()->getMutex()));
511 
512  // integrate the cost of all cells; state value precedence is UNKNOWN > LETHAL > INSCRIBED > FREE
513  for (int i = 0; i < footprint_cells.size(); ++i)
514  {
515  unsigned char cost = costmap->getCostmap()->getCost(footprint_cells[i].x, footprint_cells[i].y);
516  switch (cost)
517  {
519  response.state = std::max(response.state, static_cast<uint8_t>(mbf_msgs::CheckPose::Response::UNKNOWN));
520  response.cost += cost * (request.unknown_cost_mult ? request.unknown_cost_mult : 1.0);
521  break;
523  response.state = std::max(response.state, static_cast<uint8_t>(mbf_msgs::CheckPose::Response::LETHAL));
524  response.cost += cost * (request.lethal_cost_mult ? request.lethal_cost_mult : 1.0);
525  break;
527  response.state = std::max(response.state, static_cast<uint8_t>(mbf_msgs::CheckPose::Response::INSCRIBED));
528  response.cost += cost * (request.inscrib_cost_mult ? request.inscrib_cost_mult : 1.0);
529  break;
530  default:
531  response.cost += cost;
532  break;
533  }
534  }
535  }
536 
537  // Provide some details of the outcome
538  switch (response.state)
539  {
540  case mbf_msgs::CheckPose::Response::OUTSIDE:
541  ROS_DEBUG_STREAM("Pose [" << x << ", " << y << ", " << yaw << "] is outside the map (cost = " << response.cost
542  << "; safety distance = " << request.safety_dist << ")");
543  break;
544  case mbf_msgs::CheckPose::Response::UNKNOWN:
545  ROS_DEBUG_STREAM("Pose [" << x << ", " << y << ", " << yaw << "] is in unknown space! (cost = " << response.cost
546  << "; safety distance = " << request.safety_dist << ")");
547  break;
548  case mbf_msgs::CheckPose::Response::LETHAL:
549  ROS_DEBUG_STREAM("Pose [" << x << ", " << y << ", " << yaw << "] is in collision! (cost = " << response.cost
550  << "; safety distance = " << request.safety_dist << ")");
551  break;
552  case mbf_msgs::CheckPose::Response::INSCRIBED:
553  ROS_DEBUG_STREAM("Pose [" << x << ", " << y << ", " << yaw << "] is near an obstacle (cost = " << response.cost
554  << "; safety distance = " << request.safety_dist << ")");
555  break;
556  case mbf_msgs::CheckPose::Response::FREE:
557  ROS_DEBUG_STREAM("Pose [" << x << ", " << y << ", " << yaw << "] is free (cost = " << response.cost
558  << "; safety distance = " << request.safety_dist << ")");
559  break;
560  }
561 
562  costmap->checkDeactivate();
563  return true;
564 }
565 
566 bool CostmapNavigationServer::callServiceCheckPathCost(mbf_msgs::CheckPath::Request &request,
567  mbf_msgs::CheckPath::Response &response)
568 {
569  // selecting the requested costmap
570  CostmapWrapper::Ptr costmap;
571  std::string costmap_name;
572  switch (request.costmap)
573  {
574  case mbf_msgs::CheckPath::Request::LOCAL_COSTMAP:
575  costmap = local_costmap_ptr_;
576  costmap_name = "local costmap";
577  break;
578  case mbf_msgs::CheckPath::Request::GLOBAL_COSTMAP:
579  costmap = global_costmap_ptr_;
580  costmap_name = "global costmap";
581  break;
582  default:
583  ROS_ERROR_STREAM("No valid costmap provided; options are "
584  << mbf_msgs::CheckPath::Request::LOCAL_COSTMAP << ": local costmap, "
585  << mbf_msgs::CheckPath::Request::GLOBAL_COSTMAP << ": global costmap");
586  return false;
587  }
588 
589  // ensure costmap is active so cost reflects latest sensor readings
590  costmap->checkActivate();
591 
592  // get target pose or current robot pose as x, y, yaw coordinates
593  std::string costmap_frame = costmap->getGlobalFrameID();
594 
595  std::vector<geometry_msgs::Point> footprint;
596  if (!request.path_cells_only)
597  {
598  // unless we want to check just the cells directly traversed by the path, pad raw footprint
599  // to the requested safety distance; note that we discard footprint_padding parameter effect
600  footprint = costmap->getUnpaddedRobotFootprint();
601  costmap_2d::padFootprint(footprint, request.safety_dist);
602  }
603 
604  // lock costmap so content doesn't change while adding cell costs
605  boost::unique_lock<costmap_2d::Costmap2D::mutex_t> lock(*(costmap->getCostmap()->getMutex()));
606 
607  geometry_msgs::PoseStamped pose;
608 
609  response.state = mbf_msgs::CheckPath::Response::FREE;
610 
611  for (int i = 0; i < request.path.poses.size(); ++i)
612  {
613  response.last_checked = i;
614 
615  if (!mbf_utility::transformPose(*tf_listener_ptr_, costmap_frame, ros::Duration(0.5), request.path.poses[i], pose))
616  {
617  ROS_ERROR_STREAM("Transform target pose to " << costmap_name << " frame '" << costmap_frame << "' failed");
618  return false;
619  }
620 
621  double x = pose.pose.position.x;
622  double y = pose.pose.position.y;
623  double yaw = tf::getYaw(pose.pose.orientation);
624  std::vector<Cell> cells_to_check;
625  if (request.path_cells_only)
626  {
627  Cell cell;
628  if (costmap->getCostmap()->worldToMap(x, y, cell.x, cell.y))
629  {
630  cells_to_check.push_back(cell); // out of map if false; cells_to_check will be empty
631  }
632  }
633  else
634  {
635  // use footprint helper to get all the cells totally or partially within footprint polygon
636  cells_to_check = FootprintHelper::getFootprintCells(x, y, yaw, footprint, *costmap->getCostmap(), true);
637  }
638 
639  if (cells_to_check.empty())
640  {
641  // if path_cells_only is true, this means that current path's pose is outside the map
642  // if not, no cells within footprint polygon means that robot is completely outside of the map
643  response.state = std::max(response.state, static_cast<uint8_t>(mbf_msgs::CheckPath::Response::OUTSIDE));
644  }
645  else
646  {
647  // integrate the cost of all cells; state value precedence is UNKNOWN > LETHAL > INSCRIBED > FREE
648  // we apply the requested cost multipliers if different from zero (default value)
649  for (int j = 0; j < cells_to_check.size(); ++j)
650  {
651  unsigned char cost = costmap->getCostmap()->getCost(cells_to_check[j].x, cells_to_check[j].y);
652  switch (cost)
653  {
655  response.state = std::max(response.state, static_cast<uint8_t>(mbf_msgs::CheckPose::Response::UNKNOWN));
656  response.cost += cost * (request.unknown_cost_mult ? request.unknown_cost_mult : 1.0);
657  break;
659  response.state = std::max(response.state, static_cast<uint8_t>(mbf_msgs::CheckPath::Response::LETHAL));
660  response.cost += cost * (request.lethal_cost_mult ? request.lethal_cost_mult : 1.0);
661  break;
663  response.state = std::max(response.state, static_cast<uint8_t>(mbf_msgs::CheckPath::Response::INSCRIBED));
664  response.cost += cost * (request.inscrib_cost_mult ? request.inscrib_cost_mult : 1.0);
665  break;
666  default:response.cost += cost;
667  break;
668  }
669  }
670  }
671 
672  if (request.return_on && response.state >= request.return_on)
673  {
674  // i-th pose state is bad enough for the client, so provide some details of the outcome and abort checking
675  switch (response.state)
676  {
677  case mbf_msgs::CheckPath::Response::OUTSIDE:
678  ROS_DEBUG_STREAM("At pose " << i << " [" << x << ", " << y << ", " << yaw << "] path goes outside the map "
679  << "(cost = " << response.cost << "; safety distance = " << request.safety_dist << ")");
680  break;
681  case mbf_msgs::CheckPath::Response::UNKNOWN:
682  ROS_DEBUG_STREAM("At pose " << i << " [" << x << ", " << y << ", " << yaw << "] path goes in unknown space! "
683  << "(cost = " << response.cost << "; safety distance = " << request.safety_dist << ")");
684  break;
685  case mbf_msgs::CheckPath::Response::LETHAL:
686  ROS_DEBUG_STREAM("At pose " << i << " [" << x << ", " << y << ", " << yaw << "] path goes in collision! "
687  << "(cost = " << response.cost << "; safety distance = " << request.safety_dist << ")");
688  break;
689  case mbf_msgs::CheckPath::Response::INSCRIBED:
690  ROS_DEBUG_STREAM("At pose " << i << " [" << x << ", " << y << ", " << yaw << "] path goes near an obstacle "
691  << "(cost = " << response.cost << "; safety distance = " << request.safety_dist << ")");
692  break;
693  case mbf_msgs::CheckPath::Response::FREE:
694  ROS_DEBUG_STREAM("Path is entirely free (maximum cost = "
695  << response.cost << "; safety distance = " << request.safety_dist << ")");
696  break;
697  }
698 
699  break;
700  }
701 
702  i += request.skip_poses; // skip some poses to speedup processing (disabled by default)
703  }
704 
705  costmap->checkDeactivate();
706  return true;
707 }
708 
709 bool CostmapNavigationServer::callServiceClearCostmaps(std_srvs::Empty::Request &request,
710  std_srvs::Empty::Response &response)
711 {
712  // clear both costmaps
713  local_costmap_ptr_->clear();
714  global_costmap_ptr_->clear();
715  return true;
716 }
717 
718 } /* 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...
ActionServerRecoveryPtr action_server_recovery_ptr_
bool callServiceCheckPathCost(mbf_msgs::CheckPath::Request &request, mbf_msgs::CheckPath::Response &response)
Callback method for the check_path_cost service.
virtual mbf_abstract_nav::AbstractRecoveryExecution::Ptr newRecoveryExecution(const std::string &plugin_name, const mbf_abstract_core::AbstractRecovery::Ptr plugin_ptr)
Create a new recovery behavior execution.
bool callServiceCheckPointCost(mbf_msgs::CheckPoint::Request &request, mbf_msgs::CheckPoint::Response &response)
Callback method for the check_point_cost service.
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_core::AbstractPlanner::Ptr loadPlannerPlugin(const std::string &planner_type)
Loads the plugin associated with the given planner_type parameter.
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...
bool transformPoint(const TF &tf, const std::string &target_frame, const ros::Duration &timeout, const geometry_msgs::PointStamped &in, geometry_msgs::PointStamped &out)
AbstractPluginManager< mbf_abstract_core::AbstractController > controller_plugin_manager_
const CostmapWrapper::Ptr global_costmap_ptr_
Shared pointer to the common global costmap.
static double getYaw(const Quaternion &bt_q)
virtual mbf_abstract_nav::AbstractPlannerExecution::Ptr newPlannerExecution(const std::string &plugin_name, const mbf_abstract_core::AbstractPlanner::Ptr plugin_ptr)
Create a new planner execution.
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)
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
ros::ServiceServer clear_costmaps_srv_
Service Server for the clear_costmap service.
ActionServerGetPathPtr action_server_get_path_ptr_
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.
AbstractPluginManager< mbf_abstract_core::AbstractPlanner > planner_plugin_manager_
static const unsigned char INSCRIBED_INFLATED_OBSTACLE
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.
void padFootprint(std::vector< geometry_msgs::Point > &footprint, double padding)
static std::vector< Cell > getFootprintCells(double x, double y, double theta, std::vector< geometry_msgs::Point > footprint_spec, const costmap_2d::Costmap2D &, bool fill)
Used to get the cells that make up the footprint of the robot.
virtual mbf_abstract_nav::AbstractControllerExecution::Ptr newControllerExecution(const std::string &plugin_name, const mbf_abstract_core::AbstractController::Ptr plugin_ptr)
Create a new controller execution.
TFSIMD_FORCE_INLINE const tfScalar & x() const
The CostmapWrapper class manages access to a costmap by locking/unlocking its mutex and handles (de)a...
#define ROS_DEBUG_STREAM(args)
virtual std::string getName(const std::string &lookup_name)
bool callServiceClearCostmaps(std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
Callback method for the make_plan service.
ActionServerMoveBasePtr action_server_move_base_ptr_
pluginlib::ClassLoader< nav_core::BaseGlobalPlanner > nav_core_planner_plugin_loader_
static const unsigned char LETHAL_OBSTACLE
ActionServerExePathPtr action_server_exe_path_ptr_
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_
AbstractPluginManager< mbf_abstract_core::AbstractRecovery > recovery_plugin_manager_
ros::ServiceServer check_path_cost_srv_
Service Server for the check_path_cost service.
const CostmapWrapper::Ptr local_costmap_ptr_
Shared pointer to the common local costmap.
#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.
bool callServiceCheckPoseCost(mbf_msgs::CheckPose::Request &request, mbf_msgs::CheckPose::Response &response)
Callback method for the check_pose_cost service.
bool transformPose(const TF &tf, const std::string &target_frame, const ros::Duration &timeout, const geometry_msgs::PoseStamped &in, geometry_msgs::PoseStamped &out)
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 Fri Nov 6 2020 03:56:29