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> 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)
103 const std::string name,
106 return boost::make_shared<mbf_costmap_nav::CostmapPlannerExecution>(
116 const std::string name,
119 return boost::make_shared<mbf_costmap_nav::CostmapControllerExecution>(
132 const std::string name,
135 return boost::make_shared<mbf_costmap_nav::CostmapRecoveryExecution>(
154 ROS_DEBUG_STREAM(
"mbf_costmap_core-based planner plugin " << planner_name <<
" loaded.");
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());
164 planner_ptr = boost::make_shared<mbf_nav_core_wrapper::WrapperGlobalPlanner>(nav_core_planner_ptr);
166 ROS_DEBUG_STREAM(
"nav_core-based planner plugin " << planner_name <<
" loaded");
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());
179 const std::string& name,
194 ROS_DEBUG(
"Planner plugin initialized.");
206 ROS_DEBUG_STREAM(
"mbf_costmap_core-based controller plugin " << controller_name <<
" loaded.");
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());
217 controller_ptr = boost::make_shared<mbf_nav_core_wrapper::WrapperLocalPlanner>(nav_core_controller_ptr);
219 ROS_DEBUG_STREAM(
"nav_core-based controller plugin " << controller_name <<
" loaded.");
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());
227 return controller_ptr;
231 const std::string& name,
256 const std::string& recovery_type)
265 ROS_DEBUG_STREAM(
"mbf_costmap_core-based recovery behavior plugin " << recovery_name <<
" loaded.");
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());
277 recovery_ptr = boost::make_shared<mbf_nav_core_wrapper::WrapperRecoveryBehavior>(nav_core_recovery_ptr);
279 ROS_DEBUG_STREAM(
"nav_core-based recovery behavior plugin " << recovery_name <<
" loaded.");
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());
293 const std::string& name,
319 ROS_DEBUG_STREAM(
"Recovery behavior plugin \"" << name <<
"\" initialized.");
326 AbstractNavigationServer::stop();
346 if (config.restore_defaults)
350 config.restore_defaults =
false;
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;
371 ROS_WARN(
"Zero shutdown costmaps delay is not recommended, as it forces us to enable costmaps on each action");
388 mbf_msgs::CheckPoint::Response &response)
392 std::string costmap_name;
393 switch (request.costmap)
395 case mbf_msgs::CheckPoint::Request::LOCAL_COSTMAP:
397 costmap_name =
"local costmap";
399 case mbf_msgs::CheckPoint::Request::GLOBAL_COSTMAP:
401 costmap_name =
"global costmap";
405 << mbf_msgs::CheckPoint::Request::LOCAL_COSTMAP <<
": local costmap, " 406 << mbf_msgs::CheckPoint::Request::GLOBAL_COSTMAP <<
": global costmap");
411 std::string costmap_frame = costmap->getGlobalFrameID();
413 geometry_msgs::PointStamped point;
417 ROS_ERROR_STREAM(
"Transform target point to " << costmap_name <<
" frame '" << costmap_frame <<
"' failed");
421 double x = point.point.x;
422 double y = point.point.y;
427 if (!costmap->getCostmap()->worldToMap(x, y, mx, my))
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 <<
")");
436 boost::unique_lock<costmap_2d::Costmap2D::mutex_t> lock(*(costmap->getCostmap()->getMutex()));
439 response.cost = costmap->getCostmap()->getCost(mx, my);
440 switch (response.cost)
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 <<
")");
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 <<
")");
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 <<
")");
455 response.state =
static_cast<uint8_t
>(mbf_msgs::CheckPoint::Response::FREE);
456 ROS_DEBUG_STREAM(
"Point [" << x <<
", " << y <<
"] is free (cost = " << response.cost <<
")");
466 mbf_msgs::CheckPose::Response &response)
470 std::string costmap_name;
471 switch (request.costmap)
473 case mbf_msgs::CheckPose::Request::LOCAL_COSTMAP:
475 costmap_name =
"local costmap";
477 case mbf_msgs::CheckPose::Request::GLOBAL_COSTMAP:
479 costmap_name =
"global costmap";
483 << mbf_msgs::CheckPose::Request::LOCAL_COSTMAP <<
": local costmap, " 484 << mbf_msgs::CheckPose::Request::GLOBAL_COSTMAP <<
": global costmap");
489 std::string costmap_frame = costmap->getGlobalFrameID();
491 geometry_msgs::PoseStamped pose;
492 if (request.current_pose)
496 ROS_ERROR_STREAM(
"Get robot pose on " << costmap_name <<
" frame '" << costmap_frame <<
"' failed");
505 ROS_ERROR_STREAM(
"Transform target pose to " << costmap_name <<
" frame '" << costmap_frame <<
"' failed");
510 double x = pose.pose.position.x;
511 double y = pose.pose.position.y;
512 double yaw =
tf::getYaw(pose.pose.orientation);
518 std::vector<geometry_msgs::Point> footprint = costmap->getUnpaddedRobotFootprint();
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())
529 response.state = std::max(response.state, static_cast<uint8_t>(mbf_msgs::CheckPose::Response::OUTSIDE));
534 boost::unique_lock<costmap_2d::Costmap2D::mutex_t> lock(*(costmap->getCostmap()->getMutex()));
537 for (
int i = 0; i < footprint_cells.size(); ++i)
539 unsigned char cost = costmap->getCostmap()->getCost(footprint_cells[i].x, footprint_cells[i].y);
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);
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);
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);
554 default:response.cost += cost;
561 switch (response.state)
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 <<
")");
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 <<
")");
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 <<
")");
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 <<
")");
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 <<
")");
590 mbf_msgs::CheckPath::Response &response)
594 std::string costmap_name;
595 switch (request.costmap)
597 case mbf_msgs::CheckPath::Request::LOCAL_COSTMAP:
599 costmap_name =
"local costmap";
601 case mbf_msgs::CheckPath::Request::GLOBAL_COSTMAP:
603 costmap_name =
"global costmap";
606 << mbf_msgs::CheckPath::Request::LOCAL_COSTMAP <<
": local costmap, " 607 << mbf_msgs::CheckPath::Request::GLOBAL_COSTMAP <<
": global costmap");
615 std::string costmap_frame = costmap->getGlobalFrameID();
620 std::vector<geometry_msgs::Point> footprint;
621 if (!request.path_cells_only)
625 footprint = costmap->getUnpaddedRobotFootprint();
630 boost::unique_lock<costmap_2d::Costmap2D::mutex_t> lock(*(costmap->getCostmap()->getMutex()));
632 geometry_msgs::PoseStamped pose;
634 response.state = mbf_msgs::CheckPath::Response::FREE;
636 for (
int i = 0; i < request.path.poses.size(); ++i)
638 response.last_checked = i;
643 ROS_ERROR_STREAM(
"Transform target pose to " << costmap_name <<
" frame '" << costmap_frame <<
"' failed");
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)
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);
659 cells_to_check = fph.
getFootprintCells(Eigen::Vector3f(x, y, yaw), footprint, *costmap->getCostmap(),
true);
662 if (cells_to_check.empty())
666 response.state = std::max(response.state, static_cast<uint8_t>(mbf_msgs::CheckPath::Response::OUTSIDE));
672 for (
int j = 0; j < cells_to_check.size(); ++j)
674 unsigned char cost = costmap->getCostmap()->getCost(cells_to_check[j].x, cells_to_check[j].y);
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);
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);
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);
689 default:response.cost += cost;
695 if (request.return_on && response.state >= request.return_on)
698 switch (response.state)
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 <<
")");
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 <<
")");
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 <<
")");
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 <<
")");
716 case mbf_msgs::CheckPath::Response::FREE:
718 << response.cost <<
"; safety distance = " << request.safety_dist <<
")");
725 i += request.skip_poses;
733 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...
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.
const TFPtr tf_listener_ptr_
std::string global_frame_
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 ~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...
static double getYaw(const Quaternion &bt_q)
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
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 ¶m_name, T ¶m_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.
virtual void startActionServers()
#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 void initializeServerComponents()
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.
ros::NodeHandle private_nh_
pluginlib::ClassLoader< mbf_costmap_core::CostmapPlanner > planner_plugin_loader_