locomove_base.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2017, Locus Robotics
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the copyright holder nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  */
00034 
00035 #include <locomove_base/locomove_base.h>
00036 #include <nav_core_adapter/costmap_adapter.h>
00037 #include <nav_2d_utils/conversions.h>
00038 #include <nav_2d_utils/path_ops.h>
00039 #include <string>
00040 #include <vector>
00041 
00042 namespace locomove_base
00043 {
00049 std::string getNamespace(const std::string& s)
00050 {
00051   std::vector<std::string> split;
00052   boost::split(split, s, boost::is_any_of("/:"));
00053   return split.back();
00054 }
00055 
00065 const ros::NodeHandle& loadBackwardsCompatibleParameters(const ros::NodeHandle& nh)
00066 {
00067   // Double check robot_base_frame parameters for backwards compatibility
00068   if (!nh.hasParam("robot_base_frame"))
00069   {
00070     // If robot_base_frame was not set, use one of the values from the costmaps
00071     std::string planner_frame, controller_frame, value_to_use;
00072     nh.param("global_costmap/robot_base_frame", planner_frame, std::string(""));
00073     nh.param("local_costmap/robot_base_frame", controller_frame, std::string(""));
00074     if (planner_frame != controller_frame)
00075     {
00076       if (planner_frame.length() == 0)
00077       {
00078         value_to_use = controller_frame;
00079       }
00080       else if (controller_frame.length() == 0)
00081       {
00082         value_to_use = planner_frame;
00083       }
00084       else
00085       {
00086         ROS_WARN_NAMED("LocoMoveBase", "Two different robot_base_frames set for global and local planner. "
00087                        "This could be problematic. Using the global base frame.");
00088         value_to_use = planner_frame;
00089       }
00090     }
00091     else
00092     {
00093       value_to_use = planner_frame;
00094     }
00095     nh.setParam("robot_base_frame", value_to_use);
00096   }
00097 
00098   // Set the Global Planner Parameters
00099   std::string planner_class, planner_namespace;
00100   std::vector<std::string> plugin_namespaces;
00101 
00102   // Load the name of the nav_core1 global planner
00103   nh.param("base_global_planner", planner_class, std::string("navfn/NavfnROS"));
00104   planner_namespace = getNamespace(planner_class);
00105   if (planner_class == "nav_core_adapter::GlobalPlannerAdapter2")
00106   {
00107     // If the planner class is the adapter, then get and use the nav_core2 planner
00108     nh.param(planner_namespace + "/planner_name", planner_class, std::string("global_planner::GlobalPlanner"));
00109     planner_namespace = getNamespace(planner_class);
00110     nh.setParam(planner_namespace + "/plugin_class", planner_class);
00111     plugin_namespaces.push_back(planner_namespace);
00112     nh.setParam("global_planner_namespaces", plugin_namespaces);
00113   }
00114   else
00115   {
00116     // Otherwise, we need to inject the routing through the adapter
00117     std::string adapter_namespace = "global_planner_adapter";
00118     plugin_namespaces.push_back(adapter_namespace);
00119     nh.setParam("global_planner_namespaces", plugin_namespaces);
00120     nh.setParam(adapter_namespace + "/planner_name", planner_class);
00121     nh.setParam(adapter_namespace + "/plugin_class", "nav_core_adapter::GlobalPlannerAdapter2");
00122   }
00123   plugin_namespaces.clear();
00124 
00125   // Since the nav_core1 local planners are not compatible with nav_core2, we either need to load the
00126   // class that is being adapted, or we just load DWB instead
00127   nh.param("base_local_planner", planner_class, std::string("base_local_planner/TrajectoryPlannerROS"));
00128   planner_namespace = getNamespace(planner_class);
00129   if (planner_namespace == "LocalPlannerAdapter")
00130   {
00131     nh.param(planner_namespace + "/planner_name", planner_class, std::string("dwb_local_planner::DWBLocalPlanner"));
00132     planner_namespace = getNamespace(planner_class);
00133     nh.setParam(planner_namespace + "/plugin_class", planner_class);
00134     plugin_namespaces.push_back(planner_namespace);
00135     nh.setParam("local_planner_namespaces", plugin_namespaces);
00136   }
00137   else if (planner_namespace == "DWAPlannerROS")
00138   {
00139     ROS_WARN_NAMED("LocoMoveBase", "Using DWB as the local planner instead of DWA.");
00140     nh.setParam(planner_namespace + "/plugin_class", "dwb_local_planner::DWBLocalPlanner");
00141     plugin_namespaces.push_back(planner_namespace);
00142     nh.setParam("local_planner_namespaces", plugin_namespaces);
00143   }
00144   else
00145   {
00146     ROS_FATAL_NAMED("LocoMoveBase", "%s is unsupported in LocoMoveBase because it is not forwards compatible.",
00147                     planner_class.c_str());
00148   }
00149 
00150   return nh;
00151 }
00152 
00153 LocoMoveBase::LocoMoveBase(const ros::NodeHandle& nh) :
00154   private_nh_(nh), locomotor_(loadBackwardsCompatibleParameters(nh)),
00155   server_(ros::NodeHandle(), "move_base", false),
00156   recovery_loader_("nav_core", "nav_core::RecoveryBehavior"),
00157   local_planning_ex_(private_nh_, false), global_planning_ex_(private_nh_)
00158 {
00159   private_nh_.param("planner_frequency", planner_frequency_, planner_frequency_);
00160   if (planner_frequency_ > 0.0)
00161   {
00162     desired_plan_duration_ = ros::Duration(1.0 / planner_frequency_);
00163     plan_loop_timer_ = private_nh_.createTimer(desired_plan_duration_, &LocoMoveBase::planLoopCallback,
00164                                                this, false, false);  // one_shot=false(default), auto_start=false
00165   }
00166 
00167   private_nh_.param("controller_frequency", controller_frequency_, controller_frequency_);
00168   desired_control_duration_ = ros::Duration(1.0 / controller_frequency_);
00169   control_loop_timer_ = private_nh_.createTimer(desired_control_duration_,
00170                                                 &LocoMoveBase::controlLoopCallback,
00171                                                 this, false, false);  // one_shot=false(default), auto_start=false
00172   locomotor_.initializeGlobalCostmap(global_planning_ex_);
00173   locomotor_.initializeGlobalPlanners(global_planning_ex_);
00174   locomotor_.initializeLocalCostmap(local_planning_ex_);
00175   locomotor_.initializeLocalPlanners(local_planning_ex_);
00176 
00177   planner_costmap_ros_ = getCostmapPointer(locomotor_.getGlobalCostmap());
00178   controller_costmap_ros_ = getCostmapPointer(locomotor_.getLocalCostmap());
00179 
00180   goal_pub_ = private_nh_.advertise<geometry_msgs::PoseStamped>("current_goal", 1);
00181 
00182   private_nh_.param("recovery_behavior_enabled", recovery_behavior_enabled_, recovery_behavior_enabled_);
00183 
00184   // load any user specified recovery behaviors, and if that fails load the defaults
00185   if (!loadRecoveryBehaviors(private_nh_))
00186   {
00187     loadDefaultRecoveryBehaviors();
00188   }
00189 
00190   // Patience
00191   private_nh_.param("planner_patience", planner_patience_, planner_patience_);
00192   private_nh_.param("controller_patience", controller_patience_, controller_patience_);
00193   private_nh_.param("max_planning_retries", max_planning_retries_, max_planning_retries_);
00194 
00195   // Oscillation
00196   private_nh_.param("oscillation_timeout", oscillation_timeout_, oscillation_timeout_);
00197   private_nh_.param("oscillation_distance", oscillation_distance_, oscillation_distance_);
00198 
00199   // we'll provide a mechanism for some people to send goals as PoseStamped messages over a topic
00200   // they won't get any useful information back about its status, but this is useful for tools
00201   // like nav_view and rviz
00202   ros::NodeHandle simple_nh("move_base_simple");
00203   goal_sub_ = simple_nh.subscribe<geometry_msgs::PoseStamped>("goal", 1, boost::bind(&LocoMoveBase::goalCB, this, _1));
00204 
00205   server_.registerGoalCallback(std::bind(&LocoMoveBase::executeCB, this));
00206   server_.start();
00207 
00208   resetState();
00209 }
00210 
00211 void LocoMoveBase::setGoal(nav_2d_msgs::Pose2DStamped goal)
00212 {
00213   resetState();
00214   locomotor_.setGoal(goal);
00215   goal_pub_.publish(nav_2d_utils::pose2DToPoseStamped(goal));
00216   if (planner_frequency_ > 0.0)
00217   {
00218     plan_loop_timer_.start();
00219   }
00220   else
00221   {
00222     requestGlobalCostmapUpdate();
00223   }
00224 }
00225 
00226 costmap_2d::Costmap2DROS* LocoMoveBase::getCostmapPointer(const nav_core2::Costmap::Ptr& costmap)
00227 {
00228   std::shared_ptr<nav_core_adapter::CostmapAdapter> ptr =
00229     std::dynamic_pointer_cast<nav_core_adapter::CostmapAdapter>(costmap);
00230 
00231   if (!ptr)
00232   {
00233     ROS_FATAL_NAMED("LocoMoveBase", "LocoMoveBase can only be used with the CostmapAdapter, not other Costmaps!");
00234     exit(-1);
00235   }
00236   return ptr->getCostmap2DROS();
00237 }
00238 
00239 void LocoMoveBase::resetState()
00240 {
00241   // we'll start executing recovery behaviors at the beginning of our list
00242   recovery_index_ = 0;
00243   recovery_trigger_ = PLANNING_R;
00244 
00245   // we want to make sure that we reset the last time we had a valid plan and control
00246   last_valid_plan_ = ros::Time::now();
00247   last_valid_control_ = ros::Time::now();
00248   last_oscillation_reset_ = ros::Time::now();
00249   planning_retries_ = 0;
00250   has_global_plan_ = false;
00251 }
00252 
00253 void LocoMoveBase::publishZeroVelocity()
00254 {
00255   locomotor_.publishTwist(nav_2d_msgs::Twist2DStamped());
00256 }
00257 
00258 void LocoMoveBase::requestNavigationFailure(const locomotor_msgs::ResultCode& result)
00259 {
00260   locomotor_.requestNavigationFailure(local_planning_ex_, result,
00261     std::bind(&LocoMoveBase::onNavigationFailure, this, std::placeholders::_1));
00262 }
00263 
00264 void LocoMoveBase::planLoopCallback(const ros::TimerEvent& event)
00265 {
00266   requestGlobalCostmapUpdate();
00267 }
00268 
00269 void LocoMoveBase::requestGlobalCostmapUpdate()
00270 {
00271   locomotor_.requestGlobalCostmapUpdate(global_planning_ex_, global_planning_ex_,
00272     std::bind(&LocoMoveBase::onGlobalCostmapUpdate, this, std::placeholders::_1),
00273     std::bind(&LocoMoveBase::onGlobalCostmapException, this, std::placeholders::_1, std::placeholders::_2));
00274 }
00275 
00276 void LocoMoveBase::onGlobalCostmapUpdate(const ros::Duration& planning_time)
00277 {
00278   // Run the global planning on the separate executor, but put the result on the main executor
00279   locomotor_.requestGlobalPlan(global_planning_ex_, local_planning_ex_,
00280     std::bind(&LocoMoveBase::onNewGlobalPlan, this, std::placeholders::_1, std::placeholders::_2),
00281     std::bind(&LocoMoveBase::onGlobalPlanningException, this, std::placeholders::_1, std::placeholders::_2));
00282 }
00283 
00284 void LocoMoveBase::onGlobalCostmapException(nav_core2::NavCore2ExceptionPtr e_ptr, const ros::Duration& planning_time)
00285 {
00286   // If the planner_frequency is non-zero, the costmap will attempt to update again on its own (via the Timer).
00287   // If it is zero, then we manually request a new update
00288   if (planner_frequency_ == 0.0)
00289   {
00290     requestGlobalCostmapUpdate();
00291   }
00292 }
00293 
00294 void LocoMoveBase::onNewGlobalPlan(nav_2d_msgs::Path2D new_global_plan, const ros::Duration& planning_time)
00295 {
00296   has_global_plan_ = true;
00297   last_valid_plan_ = ros::Time::now();
00298   planning_retries_ = 0;
00299   locomotor_.publishPath(new_global_plan);
00300   locomotor_.getCurrentLocalPlanner().setPlan(new_global_plan);
00301   if (planning_time > desired_plan_duration_)
00302   {
00303     ROS_WARN_NAMED("locomotor", "Global planning missed its desired rate of %.4fHz... "
00304                    "the loop actually took %.4f seconds (>%.4f).",
00305                    planner_frequency_, planning_time.toSec(), desired_plan_duration_.toSec());
00306   }
00307   if (recovery_trigger_ == PLANNING_R)
00308   {
00309     recovery_index_ = 0;
00310   }
00311   control_loop_timer_.start();
00312 }
00313 
00314 void LocoMoveBase::onGlobalPlanningException(nav_core2::NavCore2ExceptionPtr e_ptr, const ros::Duration& planning_time)
00315 {
00316   if (has_global_plan_)
00317   {
00318     // If we have a global plan already, we can ignore this exception for the time being
00319     return;
00320   }
00321 
00322   ++planning_retries_;
00323   if (ros::Time::now() > last_valid_plan_ + ros::Duration(planner_patience_) ||
00324       planning_retries_ > max_planning_retries_)
00325   {
00326     publishZeroVelocity();
00327     recovery_trigger_ = PLANNING_R;
00328     recovery();
00329   }
00330 }
00331 
00332 void LocoMoveBase::controlLoopCallback(const ros::TimerEvent& event)
00333 {
00334   locomotor_.requestLocalCostmapUpdate(local_planning_ex_, local_planning_ex_,
00335     std::bind(&LocoMoveBase::onLocalCostmapUpdate, this, std::placeholders::_1),
00336     std::bind(&LocoMoveBase::onLocalCostmapException, this, std::placeholders::_1, std::placeholders::_2));
00337 }
00338 
00339 void LocoMoveBase::onLocalCostmapUpdate(const ros::Duration& planning_time)
00340 {
00341   // check for an oscillation condition
00342   if (oscillation_timeout_ > 0.0 && last_oscillation_reset_ + ros::Duration(oscillation_timeout_) < ros::Time::now())
00343   {
00344     publishZeroVelocity();
00345     recovery_trigger_ = OSCILLATION_R;
00346     recovery();
00347     return;
00348   }
00349   locomotor_.requestLocalPlan(local_planning_ex_, local_planning_ex_,
00350     std::bind(&LocoMoveBase::onNewLocalPlan, this, std::placeholders::_1, std::placeholders::_2),
00351     std::bind(&LocoMoveBase::onLocalPlanningException, this, std::placeholders::_1, std::placeholders::_2),
00352     std::bind(&LocoMoveBase::onNavigationCompleted, this));
00353 }
00354 
00355 void LocoMoveBase::onLocalCostmapException(nav_core2::NavCore2ExceptionPtr e_ptr, const ros::Duration& planning_time)
00356 {
00357   ROS_WARN_NAMED("LocoMoveBase",
00358                  "Sensor data is out of date, we're not going to allow commanding of the base for safety");
00359   publishZeroVelocity();
00360 }
00361 
00362 void LocoMoveBase::onNewLocalPlan(nav_2d_msgs::Twist2DStamped new_command, const ros::Duration& planning_time)
00363 {
00364   if (recovery_trigger_ == CONTROLLING_R)
00365   {
00366     recovery_index_ = 0;
00367   }
00368   last_valid_control_ = ros::Time::now();
00369   locomotor_.publishTwist(new_command);
00370 
00371   nav_2d_msgs::Pose2DStamped current_pose = locomotor_.getLocalRobotPose();
00372 
00373   // check to see if we've moved far enough to reset our oscillation timeout
00374   if (nav_2d_utils::poseDistance(current_pose.pose, oscillation_pose_) >= oscillation_distance_)
00375   {
00376     last_oscillation_reset_ = ros::Time::now();
00377     oscillation_pose_ = current_pose.pose;
00378 
00379     // if our last recovery was caused by oscillation, we want to reset the recovery index
00380     if (recovery_trigger_ == OSCILLATION_R)
00381     {
00382       recovery_index_ = 0;
00383     }
00384   }
00385 
00386   if (!server_.isActive())
00387   {
00388     return;
00389   }
00390 
00391   // publish feedback
00392   move_base_msgs::MoveBaseFeedback feedback;
00393   feedback.base_position = nav_2d_utils::pose2DToPoseStamped(current_pose);
00394   server_.publishFeedback(feedback);
00395 }
00396 
00397 void LocoMoveBase::onLocalPlanningException(nav_core2::NavCore2ExceptionPtr e_ptr, const ros::Duration& planning_time)
00398 {
00399   // check if we've tried to find a valid control for longer than our time limit
00400   if (ros::Time::now() > last_valid_control_ + ros::Duration(controller_patience_))
00401   {
00402     recovery_trigger_ = CONTROLLING_R;
00403     recovery();
00404   }
00405   else
00406   {
00407     ROS_WARN_NAMED("Locomotor", "Local planning error. Creating new global plan.");
00408     control_loop_timer_.stop();
00409     requestGlobalCostmapUpdate();
00410     planning_retries_ = 0;
00411     publishZeroVelocity();
00412   }
00413 }
00414 
00415 void LocoMoveBase::onNavigationCompleted()
00416 {
00417   ROS_INFO_NAMED("Locomotor", "Plan completed! Stopping.");
00418   if (server_.isActive())
00419   {
00420     server_.setSucceeded();
00421   }
00422   plan_loop_timer_.stop();
00423   control_loop_timer_.stop();
00424 }
00425 
00426 void LocoMoveBase::onNavigationFailure(const locomotor_msgs::ResultCode result)
00427 {
00428   if (server_.isActive())
00429   {
00430     server_.setAborted();
00431   }
00432   plan_loop_timer_.stop();
00433   control_loop_timer_.stop();
00434 }
00435 
00436 void LocoMoveBase::recovery()
00437 {
00438   ROS_DEBUG_NAMED("locomotor", "In clearing/recovery state");
00439 
00440   // we'll invoke whatever recovery behavior we're currently on if they're enabled
00441   if (recovery_behavior_enabled_ && recovery_index_ < recovery_behaviors_.size())
00442   {
00443     ROS_DEBUG_NAMED("locomotor_recovery", "Executing behavior %u of %zu",
00444                     recovery_index_, recovery_behaviors_.size());
00445     recovery_behaviors_[recovery_index_]->runBehavior();
00446 
00447     // we'll check if the recovery behavior actually worked
00448     // ROS_DEBUG_NAMED("locomotor_recovery","Going back to planning state");
00449     control_loop_timer_.stop();
00450     requestGlobalCostmapUpdate();
00451 
00452     // we at least want to give the robot some time to stop oscillating after executing the behavior
00453     last_valid_plan_ = ros::Time::now();
00454     last_oscillation_reset_ = ros::Time::now();
00455     planning_retries_ = 0;
00456 
00457     // update the index of the next recovery behavior that we'll try
00458     recovery_index_++;
00459   }
00460   else
00461   {
00462     ROS_DEBUG_NAMED("locomotor_recovery",
00463                     "All recovery behaviors have failed, locking the planner and disabling it.");
00464 
00465     if (recovery_trigger_ == CONTROLLING_R)
00466     {
00467       ROS_ERROR("Aborting because a valid control could not be found."
00468                 "Even after executing all recovery behaviors");
00469       requestNavigationFailure(locomotor::makeResultCode(locomotor_msgs::ResultCode::LOCAL_PLANNER, CONTROLLING_R,
00470         "Failed to find a valid control. Even after executing recovery behaviors."));
00471     }
00472     else if (recovery_trigger_ == PLANNING_R)
00473     {
00474       ROS_ERROR("Aborting because a valid plan could not be found. Even after executing all recovery behaviors");
00475       requestNavigationFailure(locomotor::makeResultCode(locomotor_msgs::ResultCode::GLOBAL_PLANNER, PLANNING_R,
00476         "Failed to find a valid plan. Even after executing recovery behaviors."));
00477     }
00478     else if (recovery_trigger_ == OSCILLATION_R)
00479     {
00480       ROS_ERROR("Aborting because the robot appears to be oscillating over and over."
00481                 "Even after executing all recovery behaviors");
00482       requestNavigationFailure(locomotor::makeResultCode(locomotor_msgs::ResultCode::LOCAL_PLANNER, OSCILLATION_R,
00483         "Robot is oscillating. Even after executing recovery behaviors."));
00484     }
00485   }
00486 }
00487 
00488 bool LocoMoveBase::loadRecoveryBehaviors(ros::NodeHandle node)
00489 {
00490   XmlRpc::XmlRpcValue behavior_list;
00491   if (!node.getParam("recovery_behaviors", behavior_list))
00492   {
00493     // if no recovery_behaviors are specified, we'll just load the defaults
00494     return false;
00495   }
00496 
00497   if (behavior_list.getType() != XmlRpc::XmlRpcValue::TypeArray)
00498   {
00499     ROS_ERROR("The recovery behavior specification must be a list, but is of XmlRpcType %d. "
00500               "We'll use the default recovery behaviors instead.",
00501               behavior_list.getType());
00502     return false;
00503   }
00504 
00505   for (int i = 0; i < behavior_list.size(); ++i)
00506   {
00507     if (behavior_list[i].getType() != XmlRpc::XmlRpcValue::TypeStruct)
00508     {
00509       ROS_ERROR("Recovery behaviors must be specified as maps, but they are XmlRpcType %d. "
00510                 "We'll use the default recovery behaviors instead.",
00511                 behavior_list[i].getType());
00512       return false;
00513     }
00514 
00515     if (!behavior_list[i].hasMember("name") || !behavior_list[i].hasMember("type"))
00516     {
00517       ROS_ERROR("Recovery behaviors must have a name and a type and this does not. "
00518                 "Using the default recovery behaviors instead.");
00519       return false;
00520     }
00521 
00522     // check for recovery behaviors with the same name
00523     std::string name_i = behavior_list[i]["name"];
00524     for (int j = i + 1; j < behavior_list.size(); j++)
00525     {
00526       if (behavior_list[j].getType() != XmlRpc::XmlRpcValue::TypeStruct || !behavior_list[j].hasMember("name"))
00527       {
00528         continue;
00529       }
00530 
00531       std::string name_j = behavior_list[j]["name"];
00532       if (name_i == name_j)
00533       {
00534         ROS_ERROR("A recovery behavior with the name %s already exists, "
00535                   "this is not allowed. Using the default recovery behaviors instead.",
00536                   name_i.c_str());
00537         return false;
00538       }
00539     }
00540   }
00541 
00542   TFListenerPtr tf = locomotor_.getTFListener();
00543   // if we've made it to this point, we know that the list is legal so we'll create all the recovery behaviors
00544   for (int i = 0; i < behavior_list.size(); ++i)
00545   {
00546     try
00547     {
00548       boost::shared_ptr<nav_core::RecoveryBehavior> behavior(recovery_loader_.createInstance(behavior_list[i]["type"]));
00549 
00550       // shouldn't be possible, but it won't hurt to check
00551       if (behavior.get() == nullptr)
00552       {
00553         ROS_ERROR("The ClassLoader returned a null pointer without throwing an exception. "
00554                   "This should not happen");
00555         return false;
00556       }
00557 
00558       // initialize the recovery behavior with its name
00559       behavior->initialize(behavior_list[i]["name"], tf.get(), planner_costmap_ros_, controller_costmap_ros_);
00560       recovery_behaviors_.push_back(behavior);
00561     }
00562     catch (pluginlib::PluginlibException& ex)
00563     {
00564       ROS_ERROR("Failed to load a plugin. Using default recovery behaviors. Error: %s", ex.what());
00565       return false;
00566     }
00567   }
00568   // if we've made it here... we've constructed a recovery behavior list successfully
00569   return true;
00570 }
00571 
00572 // we'll load our default recovery behaviors here
00573 void LocoMoveBase::loadDefaultRecoveryBehaviors()
00574 {
00575   recovery_behaviors_.clear();
00576   // Transform shared pointers to raw pointers for backwards compatibility with the recovery behaviors
00577   TFListenerPtr tf = locomotor_.getTFListener();
00578   try
00579   {
00580     // we need to set some parameters based on what's been passed in to us to maintain backwards compatibility
00581     ros::NodeHandle n("~");
00582 
00583     // first, we'll load a recovery behavior to clear the costmap
00584     boost::shared_ptr<nav_core::RecoveryBehavior> cons_clear(
00585       recovery_loader_.createInstance("clear_costmap_recovery/ClearCostmapRecovery"));
00586     cons_clear->initialize("conservative_reset", tf.get(), planner_costmap_ros_, controller_costmap_ros_);
00587     recovery_behaviors_.push_back(cons_clear);
00588 
00589     // next, we'll load a recovery behavior to rotate in place
00590     bool clearing_rotation_allowed;
00591     n.param("clearing_rotation_allowed", clearing_rotation_allowed, true);
00592 
00593     boost::shared_ptr<nav_core::RecoveryBehavior> rotate(
00594       recovery_loader_.createInstance("rotate_recovery/RotateRecovery"));
00595     if (clearing_rotation_allowed)
00596     {
00597       rotate->initialize("rotate_recovery", tf.get(), planner_costmap_ros_, controller_costmap_ros_);
00598       recovery_behaviors_.push_back(rotate);
00599     }
00600 
00601     // next, we'll load a recovery behavior that will do an aggressive reset of the costmap
00602     boost::shared_ptr<nav_core::RecoveryBehavior> ags_clear(
00603       recovery_loader_.createInstance("clear_costmap_recovery/ClearCostmapRecovery"));
00604     ags_clear->initialize("aggressive_reset", tf.get(), planner_costmap_ros_, controller_costmap_ros_);
00605     recovery_behaviors_.push_back(ags_clear);
00606 
00607     // we'll rotate in-place one more time
00608     if (clearing_rotation_allowed)
00609       recovery_behaviors_.push_back(rotate);
00610   }
00611   catch (pluginlib::PluginlibException& ex)
00612   {
00613     ROS_FATAL("Failed to load a plugin. This should not happen on default recovery behaviors. Error: %s",
00614               ex.what());
00615   }
00616 
00617   return;
00618 }
00619 
00620 void LocoMoveBase::goalCB(const geometry_msgs::PoseStamped::ConstPtr& goal)
00621 {
00622   setGoal(nav_2d_utils::poseStampedToPose2D(*goal));
00623 }
00624 
00625 void LocoMoveBase::executeCB()
00626 {
00627   auto move_base_goal = server_.acceptNewGoal();
00628   setGoal(nav_2d_utils::poseStampedToPose2D(move_base_goal->target_pose));
00629 }
00630 
00631 }  // namespace locomove_base
00632 
00633 int main(int argc, char** argv)
00634 {
00635   ros::init(argc, argv, "move_base");
00636   ros::NodeHandle nh("~");
00637   locomove_base::LocoMoveBase locomotor(nh);
00638   ros::spin();
00639   return 0;
00640 }


locomove_base
Author(s):
autogenerated on Wed Jun 26 2019 20:09:50