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> 66 return static_cast<std::string
>(value[tag]);
86 throw std::runtime_error(
"No parameter " + resource);
89 if (raw.
getType() != XmlRpcValue::TypeArray)
90 throw std::runtime_error(resource +
" must be an XmlRpcValue::TypeArray");
95 mapping[
"global"] = global_costmap_ptr;
96 mapping[
"local"] = local_costmap_ptr;
98 const int size = raw.
size();
99 for (
int ii = 0; ii != size; ++ii)
104 if (element.
getType() != XmlRpcValue::TypeStruct)
119 output[name] = mapping.at(costmap);
125 catch (
const std::out_of_range& _ex)
127 ROS_ERROR_STREAM(
"Unknown costmap name. It must be either 'local' or 'global'");
149 catch (
const std::exception& _ex)
157 AbstractNavigationServer(tf_listener_ptr),
158 recovery_plugin_loader_(
"mbf_costmap_core",
"mbf_costmap_core::CostmapRecovery"),
159 nav_core_recovery_plugin_loader_(
"nav_core",
"nav_core::RecoveryBehavior"),
160 controller_plugin_loader_(
"mbf_costmap_core",
"mbf_costmap_core::CostmapController"),
161 nav_core_controller_plugin_loader_(
"nav_core",
"nav_core::BaseLocalPlanner"),
162 planner_plugin_loader_(
"mbf_costmap_core",
"mbf_costmap_core::CostmapPlanner"),
163 nav_core_planner_plugin_loader_(
"nav_core",
"nav_core::BaseGlobalPlanner"),
164 global_costmap_ptr_(new
CostmapWrapper(
"global_costmap", tf_listener_ptr_)),
165 local_costmap_ptr_(new
CostmapWrapper(
"local_costmap", tf_listener_ptr_)),
166 setup_reconfigure_(false)
207 template <
typename Key,
typename Value>
208 const Value&
findWithDefault(
const boost::unordered_map<Key, Value>& map,
const Key& key,
const Value& default_value)
210 typedef boost::unordered_map<Key, Value> MapType;
211 typename MapType::const_iterator iter = map.find(key);
212 if (iter == map.end())
213 return default_value;
218 const std::string &plugin_name,
223 return boost::make_shared<mbf_costmap_nav::CostmapPlannerExecution>(
229 const std::string &plugin_name,
234 return boost::make_shared<mbf_costmap_nav::CostmapControllerExecution>(
240 const std::string &plugin_name,
243 return boost::make_shared<mbf_costmap_nav::CostmapRecoveryExecution>(
260 ROS_DEBUG_STREAM(
"mbf_costmap_core-based planner plugin " << planner_name <<
" loaded.");
264 ROS_DEBUG_STREAM(
"Failed to load the " << planner_type <<
" planner as a mbf_costmap_core-based plugin." 265 <<
" Try to load as a nav_core-based plugin. " << ex_mbf_core.what());
270 planner_ptr = boost::make_shared<mbf_nav_core_wrapper::WrapperGlobalPlanner>(nav_core_planner_ptr);
272 ROS_DEBUG_STREAM(
"nav_core-based planner plugin " << planner_name <<
" loaded");
276 ROS_FATAL_STREAM(
"Failed to load the " << planner_type <<
" planner, are you sure it's properly registered" 277 <<
" and that the containing library is built? " << ex_mbf_core.what() <<
" " << ex_nav_core.what());
285 const std::string &name,
301 costmap_planner_ptr->initialize(name, costmap_ptr.get());
313 ROS_DEBUG_STREAM(
"mbf_costmap_core-based controller plugin " << controller_name <<
" loaded.");
317 ROS_DEBUG_STREAM(
"Failed to load the " << controller_type <<
" controller as a mbf_costmap_core-based plugin;" 318 <<
" we will retry to load as a nav_core-based plugin. " << ex_mbf_core.what());
324 controller_ptr = boost::make_shared<mbf_nav_core_wrapper::WrapperLocalPlanner>(nav_core_controller_ptr);
326 ROS_DEBUG_STREAM(
"nav_core-based controller plugin " << controller_name <<
" loaded.");
330 ROS_FATAL_STREAM(
"Failed to load the " << controller_type <<
" controller, are you sure it's properly registered" 331 <<
" and that the containing library is built? " << ex_mbf_core.what() <<
" " << ex_nav_core.what());
334 return controller_ptr;
338 const std::string &name,
359 costmap_controller_ptr->initialize(name,
tf_listener_ptr_.get(), costmap_ptr.get());
365 const std::string &recovery_type)
374 ROS_DEBUG_STREAM(
"mbf_costmap_core-based recovery behavior plugin " << recovery_name <<
" loaded.");
378 ROS_DEBUG_STREAM(
"Failed to load the " << recovery_type <<
" recovery behavior as a mbf_costmap_core-based plugin;" 379 <<
" Retry to load as a nav_core-based plugin. " << ex_mbf_core.what());
386 recovery_ptr = boost::make_shared<mbf_nav_core_wrapper::WrapperRecoveryBehavior>(nav_core_recovery_ptr);
388 ROS_DEBUG_STREAM(
"nav_core-based recovery behavior plugin " << recovery_name <<
" loaded.");
393 ROS_FATAL_STREAM(
"Failed to load the " << recovery_type <<
" recovery behavior, are you sure it's properly registered" 394 <<
" and that the containing library is built? " << ex_mbf_core.what() <<
" " << ex_nav_core.what());
402 const std::string &name,
428 ROS_DEBUG_STREAM(
"Recovery behavior plugin \"" << name <<
"\" initialized.");
435 AbstractNavigationServer::stop();
450 if (config.restore_defaults)
454 config.restore_defaults =
false;
458 mbf_abstract_nav::MoveBaseFlexConfig abstract_config;
459 abstract_config.planner_frequency = config.planner_frequency;
460 abstract_config.planner_patience = config.planner_patience;
461 abstract_config.planner_max_retries = config.planner_max_retries;
462 abstract_config.controller_frequency = config.controller_frequency;
463 abstract_config.controller_patience = config.controller_patience;
464 abstract_config.controller_max_retries = config.controller_max_retries;
465 abstract_config.recovery_enabled = config.recovery_enabled;
466 abstract_config.recovery_patience = config.recovery_patience;
467 abstract_config.oscillation_timeout = config.oscillation_timeout;
468 abstract_config.oscillation_distance = config.oscillation_distance;
469 abstract_config.restore_defaults = config.restore_defaults;
473 local_costmap_ptr_->reconfigure(config.shutdown_costmaps, config.shutdown_costmaps_delay);
474 global_costmap_ptr_->reconfigure(config.shutdown_costmaps, config.shutdown_costmaps_delay);
480 mbf_msgs::CheckPoint::Response &response)
484 std::string costmap_name;
485 switch (request.costmap)
487 case mbf_msgs::CheckPoint::Request::LOCAL_COSTMAP:
489 costmap_name =
"local costmap";
491 case mbf_msgs::CheckPoint::Request::GLOBAL_COSTMAP:
493 costmap_name =
"global costmap";
497 << mbf_msgs::CheckPoint::Request::LOCAL_COSTMAP <<
": local costmap, " 498 << mbf_msgs::CheckPoint::Request::GLOBAL_COSTMAP <<
": global costmap");
503 std::string costmap_frame = costmap->getGlobalFrameID();
505 geometry_msgs::PointStamped point;
508 ROS_ERROR_STREAM(
"Transform target point to " << costmap_name <<
" frame '" << costmap_frame <<
"' failed");
512 double x = point.point.x;
513 double y = point.point.y;
516 costmap->checkActivate();
518 if (!costmap->getCostmap()->worldToMap(x, y, mx, my))
521 response.state =
static_cast<uint8_t
>(mbf_msgs::CheckPoint::Response::OUTSIDE);
522 ROS_DEBUG_STREAM(
"Point [" << x <<
", " << y <<
"] is outside the map (cost = " << response.cost <<
")");
527 boost::unique_lock<costmap_2d::Costmap2D::mutex_t> lock(*(costmap->getCostmap()->getMutex()));
530 response.cost = costmap->getCostmap()->getCost(mx, my);
531 switch (response.cost)
534 response.state =
static_cast<uint8_t
>(mbf_msgs::CheckPoint::Response::UNKNOWN);
535 ROS_DEBUG_STREAM(
"Point [" << x <<
", " << y <<
"] is in unknown space! (cost = " << response.cost <<
")");
538 response.state =
static_cast<uint8_t
>(mbf_msgs::CheckPoint::Response::LETHAL);
539 ROS_DEBUG_STREAM(
"Point [" << x <<
", " << y <<
"] is in collision! (cost = " << response.cost <<
")");
542 response.state =
static_cast<uint8_t
>(mbf_msgs::CheckPoint::Response::INSCRIBED);
543 ROS_DEBUG_STREAM(
"Point [" << x <<
", " << y <<
"] is near an obstacle (cost = " << response.cost <<
")");
546 response.state =
static_cast<uint8_t
>(mbf_msgs::CheckPoint::Response::FREE);
547 ROS_DEBUG_STREAM(
"Point [" << x <<
", " << y <<
"] is free (cost = " << response.cost <<
")");
552 costmap->checkDeactivate();
557 mbf_msgs::CheckPose::Response &response)
561 std::string costmap_name;
562 switch (request.costmap)
564 case mbf_msgs::CheckPose::Request::LOCAL_COSTMAP:
566 costmap_name =
"local costmap";
568 case mbf_msgs::CheckPose::Request::GLOBAL_COSTMAP:
570 costmap_name =
"global costmap";
574 << mbf_msgs::CheckPose::Request::LOCAL_COSTMAP <<
": local costmap, " 575 << mbf_msgs::CheckPose::Request::GLOBAL_COSTMAP <<
": global costmap");
580 std::string costmap_frame = costmap->getGlobalFrameID();
582 geometry_msgs::PoseStamped pose;
583 if (request.current_pose)
587 ROS_ERROR_STREAM(
"Get robot pose on " << costmap_name <<
" frame '" << costmap_frame <<
"' failed");
595 ROS_ERROR_STREAM(
"Transform target pose to " << costmap_name <<
" frame '" << costmap_frame <<
"' failed");
600 double x = pose.pose.position.x;
601 double y = pose.pose.position.y;
602 double yaw =
tf::getYaw(pose.pose.orientation);
605 costmap->checkActivate();
608 std::vector<geometry_msgs::Point> footprint = costmap->getUnpaddedRobotFootprint();
612 std::vector<Cell> footprint_cells =
614 response.state = mbf_msgs::CheckPose::Response::FREE;
615 if (footprint_cells.empty())
618 response.state = std::max(response.state, static_cast<uint8_t>(mbf_msgs::CheckPose::Response::OUTSIDE));
623 boost::unique_lock<costmap_2d::Costmap2D::mutex_t> lock(*(costmap->getCostmap()->getMutex()));
626 for (
int i = 0; i < footprint_cells.size(); ++i)
628 unsigned char cost = costmap->getCostmap()->getCost(footprint_cells[i].x, footprint_cells[i].y);
632 response.state = std::max(response.state, static_cast<uint8_t>(mbf_msgs::CheckPose::Response::UNKNOWN));
633 response.cost += cost * (request.unknown_cost_mult ? request.unknown_cost_mult : 1.0);
636 response.state = std::max(response.state, static_cast<uint8_t>(mbf_msgs::CheckPose::Response::LETHAL));
637 response.cost += cost * (request.lethal_cost_mult ? request.lethal_cost_mult : 1.0);
640 response.state = std::max(response.state, static_cast<uint8_t>(mbf_msgs::CheckPose::Response::INSCRIBED));
641 response.cost += cost * (request.inscrib_cost_mult ? request.inscrib_cost_mult : 1.0);
644 response.cost += cost;
651 switch (response.state)
653 case mbf_msgs::CheckPose::Response::OUTSIDE:
654 ROS_DEBUG_STREAM(
"Pose [" << x <<
", " << y <<
", " << yaw <<
"] is outside the map (cost = " << response.cost
655 <<
"; safety distance = " << request.safety_dist <<
")");
657 case mbf_msgs::CheckPose::Response::UNKNOWN:
658 ROS_DEBUG_STREAM(
"Pose [" << x <<
", " << y <<
", " << yaw <<
"] is in unknown space! (cost = " << response.cost
659 <<
"; safety distance = " << request.safety_dist <<
")");
661 case mbf_msgs::CheckPose::Response::LETHAL:
662 ROS_DEBUG_STREAM(
"Pose [" << x <<
", " << y <<
", " << yaw <<
"] is in collision! (cost = " << response.cost
663 <<
"; safety distance = " << request.safety_dist <<
")");
665 case mbf_msgs::CheckPose::Response::INSCRIBED:
666 ROS_DEBUG_STREAM(
"Pose [" << x <<
", " << y <<
", " << yaw <<
"] is near an obstacle (cost = " << response.cost
667 <<
"; safety distance = " << request.safety_dist <<
")");
669 case mbf_msgs::CheckPose::Response::FREE:
670 ROS_DEBUG_STREAM(
"Pose [" << x <<
", " << y <<
", " << yaw <<
"] is free (cost = " << response.cost
671 <<
"; safety distance = " << request.safety_dist <<
")");
675 costmap->checkDeactivate();
680 mbf_msgs::CheckPath::Response &response)
684 std::string costmap_name;
685 switch (request.costmap)
687 case mbf_msgs::CheckPath::Request::LOCAL_COSTMAP:
689 costmap_name =
"local costmap";
691 case mbf_msgs::CheckPath::Request::GLOBAL_COSTMAP:
693 costmap_name =
"global costmap";
697 << mbf_msgs::CheckPath::Request::LOCAL_COSTMAP <<
": local costmap, " 698 << mbf_msgs::CheckPath::Request::GLOBAL_COSTMAP <<
": global costmap");
703 costmap->checkActivate();
706 std::string costmap_frame = costmap->getGlobalFrameID();
708 std::vector<geometry_msgs::Point> footprint;
709 if (!request.path_cells_only)
713 footprint = costmap->getUnpaddedRobotFootprint();
718 boost::unique_lock<costmap_2d::Costmap2D::mutex_t> lock(*(costmap->getCostmap()->getMutex()));
720 geometry_msgs::PoseStamped pose;
722 response.state = mbf_msgs::CheckPath::Response::FREE;
724 for (
int i = 0; i < request.path.poses.size(); ++i)
726 response.last_checked = i;
730 ROS_ERROR_STREAM(
"Transform target pose to " << costmap_name <<
" frame '" << costmap_frame <<
"' failed");
734 double x = pose.pose.position.x;
735 double y = pose.pose.position.y;
736 double yaw =
tf::getYaw(pose.pose.orientation);
737 std::vector<Cell> cells_to_check;
738 if (request.path_cells_only)
741 if (costmap->getCostmap()->worldToMap(x, y, cell.
x, cell.
y))
743 cells_to_check.push_back(cell);
752 if (cells_to_check.empty())
756 response.state = std::max(response.state, static_cast<uint8_t>(mbf_msgs::CheckPath::Response::OUTSIDE));
762 for (
int j = 0; j < cells_to_check.size(); ++j)
764 unsigned char cost = costmap->getCostmap()->getCost(cells_to_check[j].x, cells_to_check[j].y);
768 response.state = std::max(response.state, static_cast<uint8_t>(mbf_msgs::CheckPose::Response::UNKNOWN));
769 response.cost += cost * (request.unknown_cost_mult ? request.unknown_cost_mult : 1.0);
772 response.state = std::max(response.state, static_cast<uint8_t>(mbf_msgs::CheckPath::Response::LETHAL));
773 response.cost += cost * (request.lethal_cost_mult ? request.lethal_cost_mult : 1.0);
776 response.state = std::max(response.state, static_cast<uint8_t>(mbf_msgs::CheckPath::Response::INSCRIBED));
777 response.cost += cost * (request.inscrib_cost_mult ? request.inscrib_cost_mult : 1.0);
779 default:response.cost += cost;
785 if (request.return_on && response.state >= request.return_on)
788 switch (response.state)
790 case mbf_msgs::CheckPath::Response::OUTSIDE:
791 ROS_DEBUG_STREAM(
"At pose " << i <<
" [" << x <<
", " << y <<
", " << yaw <<
"] path goes outside the map " 792 <<
"(cost = " << response.cost <<
"; safety distance = " << request.safety_dist <<
")");
794 case mbf_msgs::CheckPath::Response::UNKNOWN:
795 ROS_DEBUG_STREAM(
"At pose " << i <<
" [" << x <<
", " << y <<
", " << yaw <<
"] path goes in unknown space! " 796 <<
"(cost = " << response.cost <<
"; safety distance = " << request.safety_dist <<
")");
798 case mbf_msgs::CheckPath::Response::LETHAL:
799 ROS_DEBUG_STREAM(
"At pose " << i <<
" [" << x <<
", " << y <<
", " << yaw <<
"] path goes in collision! " 800 <<
"(cost = " << response.cost <<
"; safety distance = " << request.safety_dist <<
")");
802 case mbf_msgs::CheckPath::Response::INSCRIBED:
803 ROS_DEBUG_STREAM(
"At pose " << i <<
" [" << x <<
", " << y <<
", " << yaw <<
"] path goes near an obstacle " 804 <<
"(cost = " << response.cost <<
"; safety distance = " << request.safety_dist <<
")");
806 case mbf_msgs::CheckPath::Response::FREE:
808 << response.cost <<
"; safety distance = " << request.safety_dist <<
")");
815 i += request.skip_poses;
818 costmap->checkDeactivate();
823 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.
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.
StringToMap controller_name_to_costmap_ptr_
Maps the controller names to the costmap ptr.
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.
StringToMap loadStringToMaps(const std::string &resource, const ros::NodeHandle &nh, const CostmapWrapper::Ptr &global_costmap_ptr, const CostmapWrapper::Ptr &local_costmap_ptr)
Non-throwing version of loadStringToMapsImpl.
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.
StringToMap planner_name_to_costmap_ptr_
Maps planner names to the costmap ptr.
boost::shared_ptr< T > createInstance(const std::string &lookup_name)
static double getYaw(const Quaternion &bt_q)
const std::string & getMessage() const
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.
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.
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.
ros::ServiceServer clear_costmaps_srv_
Service Server for the clear_costmap service.
ActionServerGetPathPtr action_server_get_path_ptr_
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.
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.
Type const & getType() const
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.
bool getParam(const std::string &key, std::string &s) const
void padFootprint(std::vector< geometry_msgs::Point > &footprint, double padding)
static std::string getStringElement(const XmlRpc::XmlRpcValue &value, const std::string &tag)
Returns a string element with the tag from value.
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)
StringToMap loadStringToMapsImpl(const std::string &resource, const ros::NodeHandle &nh, const CostmapWrapper::Ptr &global_costmap_ptr, const CostmapWrapper::Ptr &local_costmap_ptr)
Returns the mapping from 'names' to 'costmaps' for the defined resource.
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)
bool hasMember(const std::string &name) const
boost::unordered_map< std::string, CostmapWrapper::Ptr > StringToMap
A mapping from a string to a map-ptr.
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_
const Value & findWithDefault(const boost::unordered_map< Key, Value > &map, const Key &key, const Value &default_value)