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>    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)
   105     const std::string &plugin_name,
   108   return boost::make_shared<mbf_costmap_nav::CostmapPlannerExecution>(
   116     const std::string &plugin_name,
   119   return boost::make_shared<mbf_costmap_nav::CostmapControllerExecution>(
   130     const std::string &plugin_name,
   133   return boost::make_shared<mbf_costmap_nav::CostmapRecoveryExecution>(
   150     ROS_DEBUG_STREAM(
"mbf_costmap_core-based planner plugin " << planner_name << 
" loaded.");
   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());
   160       planner_ptr = boost::make_shared<mbf_nav_core_wrapper::WrapperGlobalPlanner>(nav_core_planner_ptr);
   162       ROS_DEBUG_STREAM(
"nav_core-based planner plugin " << planner_name << 
" loaded");
   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());
   175     const std::string &name,
   190   ROS_DEBUG(
"Planner plugin initialized.");
   202     ROS_DEBUG_STREAM(
"mbf_costmap_core-based controller plugin " << controller_name << 
" loaded.");
   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());
   213       controller_ptr = boost::make_shared<mbf_nav_core_wrapper::WrapperLocalPlanner>(nav_core_controller_ptr);
   215       ROS_DEBUG_STREAM(
"nav_core-based controller plugin " << controller_name << 
" loaded.");
   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());
   223   return controller_ptr;
   227     const std::string &name,
   252     const std::string &recovery_type)
   261     ROS_DEBUG_STREAM(
"mbf_costmap_core-based recovery behavior plugin " << recovery_name << 
" loaded.");
   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());
   273       recovery_ptr = boost::make_shared<mbf_nav_core_wrapper::WrapperRecoveryBehavior>(nav_core_recovery_ptr);
   275       ROS_DEBUG_STREAM(
"nav_core-based recovery behavior plugin " << recovery_name << 
" loaded.");
   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());
   289     const std::string &name,
   315   ROS_DEBUG_STREAM(
"Recovery behavior plugin \"" << name << 
"\" initialized.");
   322   AbstractNavigationServer::stop();
   337   if (config.restore_defaults)
   341     config.restore_defaults = 
false;
   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;
   360   local_costmap_ptr_->reconfigure(config.shutdown_costmaps, config.shutdown_costmaps_delay);
   361   global_costmap_ptr_->reconfigure(config.shutdown_costmaps, config.shutdown_costmaps_delay);
   367                                                         mbf_msgs::CheckPoint::Response &response)
   371   std::string costmap_name;
   372   switch (request.costmap)
   374     case mbf_msgs::CheckPoint::Request::LOCAL_COSTMAP:
   376       costmap_name = 
"local costmap";
   378     case mbf_msgs::CheckPoint::Request::GLOBAL_COSTMAP:
   380       costmap_name = 
"global costmap";
   384                            << mbf_msgs::CheckPoint::Request::LOCAL_COSTMAP << 
": local costmap, "   385                            << mbf_msgs::CheckPoint::Request::GLOBAL_COSTMAP << 
": global costmap");
   390   std::string costmap_frame = costmap->getGlobalFrameID();
   392   geometry_msgs::PointStamped point;
   395     ROS_ERROR_STREAM(
"Transform target point to " << costmap_name << 
" frame '" << costmap_frame << 
"' failed");
   399   double x = point.point.x;
   400   double y = point.point.y;
   403   costmap->checkActivate();
   405   if (!costmap->getCostmap()->worldToMap(x, y, mx, my))
   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 << 
")");
   414     boost::unique_lock<costmap_2d::Costmap2D::mutex_t> lock(*(costmap->getCostmap()->getMutex()));
   417     response.cost = costmap->getCostmap()->getCost(mx, my);
   418     switch (response.cost)
   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 << 
")");
   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 << 
")");
   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 << 
")");
   433         response.state = 
static_cast<uint8_t
>(mbf_msgs::CheckPoint::Response::FREE);
   434         ROS_DEBUG_STREAM(
"Point [" << x << 
", " << y << 
"] is free (cost = " << response.cost << 
")");
   439   costmap->checkDeactivate();
   444                                                        mbf_msgs::CheckPose::Response &response)
   448   std::string costmap_name;
   449   switch (request.costmap)
   451     case mbf_msgs::CheckPose::Request::LOCAL_COSTMAP:
   453       costmap_name = 
"local costmap";
   455     case mbf_msgs::CheckPose::Request::GLOBAL_COSTMAP:
   457       costmap_name = 
"global costmap";
   461                        << mbf_msgs::CheckPose::Request::LOCAL_COSTMAP << 
": local costmap, "   462                        << mbf_msgs::CheckPose::Request::GLOBAL_COSTMAP << 
": global costmap");
   467   std::string costmap_frame = costmap->getGlobalFrameID();
   469   geometry_msgs::PoseStamped pose;
   470   if (request.current_pose)
   474       ROS_ERROR_STREAM(
"Get robot pose on " << costmap_name << 
" frame '" << costmap_frame << 
"' failed");
   482       ROS_ERROR_STREAM(
"Transform target pose to " << costmap_name << 
" frame '" << costmap_frame << 
"' failed");
   487   double x = pose.pose.position.x;
   488   double y = pose.pose.position.y;
   489   double yaw = 
tf::getYaw(pose.pose.orientation);
   492   costmap->checkActivate();
   495   std::vector<geometry_msgs::Point> footprint = costmap->getUnpaddedRobotFootprint();
   499   std::vector<Cell> footprint_cells =
   501   response.state = mbf_msgs::CheckPose::Response::FREE;
   502   if (footprint_cells.empty())
   505     response.state = std::max(response.state, static_cast<uint8_t>(mbf_msgs::CheckPose::Response::OUTSIDE));
   510     boost::unique_lock<costmap_2d::Costmap2D::mutex_t> lock(*(costmap->getCostmap()->getMutex()));
   513     for (
int i = 0; i < footprint_cells.size(); ++i)
   515       unsigned char cost = costmap->getCostmap()->getCost(footprint_cells[i].x, footprint_cells[i].y);
   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);
   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);
   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);
   531           response.cost += cost;
   538   switch (response.state)
   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 << 
")");
   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 << 
")");
   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 << 
")");
   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 << 
")");
   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 << 
")");
   562   costmap->checkDeactivate();
   567                                                        mbf_msgs::CheckPath::Response &response)
   571   std::string costmap_name;
   572   switch (request.costmap)
   574     case mbf_msgs::CheckPath::Request::LOCAL_COSTMAP:
   576       costmap_name = 
"local costmap";
   578     case mbf_msgs::CheckPath::Request::GLOBAL_COSTMAP:
   580       costmap_name = 
"global costmap";
   584                        << mbf_msgs::CheckPath::Request::LOCAL_COSTMAP << 
": local costmap, "   585                        << mbf_msgs::CheckPath::Request::GLOBAL_COSTMAP << 
": global costmap");
   590   costmap->checkActivate();
   593   std::string costmap_frame = costmap->getGlobalFrameID();
   595   std::vector<geometry_msgs::Point> footprint;
   596   if (!request.path_cells_only)
   600     footprint = costmap->getUnpaddedRobotFootprint();
   605   boost::unique_lock<costmap_2d::Costmap2D::mutex_t> lock(*(costmap->getCostmap()->getMutex()));
   607   geometry_msgs::PoseStamped pose;
   609   response.state = mbf_msgs::CheckPath::Response::FREE;
   611   for (
int i = 0; i < request.path.poses.size(); ++i)
   613     response.last_checked = i;
   617       ROS_ERROR_STREAM(
"Transform target pose to " << costmap_name << 
" frame '" << costmap_frame << 
"' failed");
   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)
   628       if (costmap->getCostmap()->worldToMap(x, y, cell.
x, cell.
y))
   630         cells_to_check.push_back(cell);  
   639     if (cells_to_check.empty())
   643       response.state = std::max(response.state, static_cast<uint8_t>(mbf_msgs::CheckPath::Response::OUTSIDE));
   649       for (
int j = 0; j < cells_to_check.size(); ++j)
   651         unsigned char cost = costmap->getCostmap()->getCost(cells_to_check[j].x, cells_to_check[j].y);
   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);
   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);
   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);
   666           default:response.cost += cost;
   672     if (request.return_on && response.state >= request.return_on)
   675       switch (response.state)
   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 << 
")");
   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 << 
")");
   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 << 
")");
   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 << 
")");
   693         case mbf_msgs::CheckPath::Response::FREE:
   695                            << response.cost << 
"; safety distance = " << request.safety_dist << 
")");
   702     i += request.skip_poses;  
   705   costmap->checkDeactivate();
   710                                                        std_srvs::Empty::Response &response)
 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. 
const TFPtr tf_listener_ptr_
mbf_costmap_nav::MoveBaseFlexConfig default_config_
the default parameter configuration save 
virtual ~CostmapNavigationServer()
Destructor. 
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)
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. 
virtual void startActionServers()
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. 
virtual void initializeServerComponents()
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. 
ros::NodeHandle private_nh_
pluginlib::ClassLoader< mbf_costmap_core::CostmapPlanner > planner_plugin_loader_