41 #include <boost/algorithm/string.hpp>    42 #include <boost/thread.hpp>    44 #include <geometry_msgs/Twist.h>    51     planner_costmap_ros_(NULL), controller_costmap_ros_(NULL),
    52     bgp_loader_(
"nav_core", 
"nav_core::BaseGlobalPlanner"),
    53     blp_loader_(
"nav_core", 
"nav_core::BaseLocalPlanner"), 
    54     recovery_loader_(
"nav_core", 
"nav_core::RecoveryBehavior"),
    55     planner_plan_(NULL), latest_plan_(NULL), controller_plan_(NULL),
    56     runPlanner_(false), setup_(false), p_freq_change_(false), c_freq_change_(false), new_global_plan_(false) {
    66     std::string global_planner, local_planner;
    67     private_nh.
param(
"base_global_planner", global_planner, std::string(
"navfn/NavfnROS"));
    68     private_nh.
param(
"base_local_planner", local_planner, std::string(
"base_local_planner/TrajectoryPlannerROS"));
    81     planner_plan_ = 
new std::vector<geometry_msgs::PoseStamped>();
    82     latest_plan_ = 
new std::vector<geometry_msgs::PoseStamped>();
    93     action_goal_pub_ = action_nh.advertise<move_base_msgs::MoveBaseActionGoal>(
"goal", 1);
   120       ROS_FATAL(
"Failed to create the %s planner, are you sure it is properly registered and that the containing library is built? Exception: %s", global_planner.c_str(), ex.what());
   131       ROS_INFO(
"Created local_planner %s", local_planner.c_str());
   134       ROS_FATAL(
"Failed to create the %s planner, are you sure it is properly registered and that the containing library is built? Exception: %s", local_planner.c_str(), ex.what());
   170     dynamic_reconfigure::Server<move_base::MoveBaseConfig>::CallbackType cb = boost::bind(&
MoveBase::reconfigureCB, 
this, _1, _2);
   171     dsrv_->setCallback(cb);
   187     if(config.restore_defaults) {
   190       config.restore_defaults = 
false;
   216     if(config.base_global_planner != 
last_config_.base_global_planner) {
   219       ROS_INFO(
"Loading global planner %s", config.base_global_planner.c_str());
   235         ROS_FATAL(
"Failed to create the %s planner, are you sure it is properly registered and that the \   236                    containing library is built? Exception: %s", config.base_global_planner.c_str(), ex.what());
   238         config.base_global_planner = 
last_config_.base_global_planner;
   242     if(config.base_local_planner != 
last_config_.base_local_planner){
   254         ROS_FATAL(
"Failed to create the %s planner, are you sure it is properly registered and that the \   255                    containing library is built? Exception: %s", config.base_local_planner.c_str(), ex.what());
   257         config.base_local_planner = 
last_config_.base_local_planner;
   265     ROS_DEBUG_NAMED(
"move_base",
"In ROS goal callback, wrapping the PoseStamped in the action message and re-sending to the server.");
   266     move_base_msgs::MoveBaseActionGoal action_goal;
   268     action_goal.goal.target_pose = *goal;
   279     std::vector<geometry_msgs::Point> clear_poly;
   280     double x = global_pose.getOrigin().x();
   281     double y = global_pose.getOrigin().y();
   282     geometry_msgs::Point pt;
   284     pt.x = x - size_x / 2;
   285     pt.y = y - size_y / 2;
   286     clear_poly.push_back(pt);
   288     pt.x = x + size_x / 2;
   289     pt.y = y - size_y / 2;
   290     clear_poly.push_back(pt);
   292     pt.x = x + size_x / 2;
   293     pt.y = y + size_y / 2;
   294     clear_poly.push_back(pt);
   296     pt.x = x - size_x / 2;
   297     pt.y = y + size_y / 2;
   298     clear_poly.push_back(pt);
   306     x = global_pose.getOrigin().x();
   307     y = global_pose.getOrigin().y();
   309     pt.x = x - size_x / 2;
   310     pt.y = y - size_y / 2;
   311     clear_poly.push_back(pt);
   313     pt.x = x + size_x / 2;
   314     pt.y = y - size_y / 2;
   315     clear_poly.push_back(pt);
   317     pt.x = x + size_x / 2;
   318     pt.y = y + size_y / 2;
   319     clear_poly.push_back(pt);
   321     pt.x = x - size_x / 2;
   322     pt.y = y + size_y / 2;
   323     clear_poly.push_back(pt);
   341       ROS_ERROR(
"move_base must be in an inactive state to make a plan for an external user");
   346       ROS_ERROR(
"move_base cannot make a plan for you because it doesn't have a costmap");
   350     geometry_msgs::PoseStamped 
start;
   352     if(req.start.header.frame_id.empty())
   356           ROS_ERROR(
"move_base cannot make a plan for you because it could not get the start pose of the robot");
   370     std::vector<geometry_msgs::PoseStamped> global_plan;
   371     if(!
planner_->makePlan(start, req.goal, global_plan) || global_plan.empty()){
   372       ROS_DEBUG_NAMED(
"move_base",
"Failed to find a plan to exact goal of (%.2f, %.2f), searching for a feasible goal within tolerance", 
   373           req.goal.pose.position.x, req.goal.pose.position.y);
   376       geometry_msgs::PoseStamped p;
   378       bool found_legal = 
false;
   380       float search_increment = resolution*3.0;
   381       if(req.tolerance > 0.0 && req.tolerance < search_increment) search_increment = req.tolerance;
   382       for(
float max_offset = search_increment; max_offset <= req.tolerance && !found_legal; max_offset += search_increment) {
   383         for(
float y_offset = 0; y_offset <= max_offset && !found_legal; y_offset += search_increment) {
   384           for(
float x_offset = 0; x_offset <= max_offset && !found_legal; x_offset += search_increment) {
   387             if(x_offset < max_offset-1e-9 && y_offset < max_offset-1e-9) 
continue;
   390             for(
float y_mult = -1.0; y_mult <= 1.0 + 1e-9 && !found_legal; y_mult += 2.0) {
   393               if(y_offset < 1e-9 && y_mult < -1.0 + 1e-9) 
continue;
   395               for(
float x_mult = -1.0; x_mult <= 1.0 + 1e-9 && !found_legal; x_mult += 2.0) {
   396                 if(x_offset < 1e-9 && x_mult < -1.0 + 1e-9) 
continue;
   398                 p.pose.position.y = req.goal.pose.position.y + y_offset * y_mult;
   399                 p.pose.position.x = req.goal.pose.position.x + x_offset * x_mult;
   401                 if(
planner_->makePlan(start, p, global_plan)){
   402                   if(!global_plan.empty()){
   406                     global_plan.push_back(req.goal);
   409                     ROS_DEBUG_NAMED(
"move_base", 
"Found a plan to point (%.2f, %.2f)", p.pose.position.x, p.pose.position.y);
   414                   ROS_DEBUG_NAMED(
"move_base",
"Failed to find a plan to point (%.2f, %.2f)", p.pose.position.x, p.pose.position.y);
   424     resp.plan.poses.resize(global_plan.size());
   425     for(
unsigned int i = 0; i < global_plan.size(); ++i){
   426       resp.plan.poses[i] = global_plan[i];
   459   bool MoveBase::makePlan(
const geometry_msgs::PoseStamped& goal, std::vector<geometry_msgs::PoseStamped>& plan){
   467       ROS_ERROR(
"Planner costmap ROS is NULL, unable to create global plan");
   474       ROS_WARN(
"Unable to get starting pose of robot, unable to create global plan");
   478     geometry_msgs::PoseStamped 
start;
   482     if(!
planner_->makePlan(start, goal, plan) || plan.empty()){
   483       ROS_DEBUG_NAMED(
"move_base",
"Failed to find a  plan to point (%.2f, %.2f)", goal.pose.position.x, goal.pose.position.y);
   491     geometry_msgs::Twist cmd_vel;
   492     cmd_vel.linear.x = 0.0;
   493     cmd_vel.linear.y = 0.0;
   494     cmd_vel.angular.z = 0.0;
   500     if(!std::isfinite(q.x) || !std::isfinite(q.y) || !std::isfinite(q.z) || !std::isfinite(q.w)){
   501       ROS_ERROR(
"Quaternion has nans or infs... discarding as a navigation goal");
   509       ROS_ERROR(
"Quaternion has length close to zero... discarding as navigation goal");
   520     if(fabs(dot - 1) > 1e-3){
   521       ROS_ERROR(
"Quaternion is invalid... for navigation the z-axis of the quaternion must be close to vertical.");
   531     poseStampedMsgToTF(goal_pose_msg, goal_pose);
   541       ROS_WARN(
"Failed to transform the goal pose from %s into the %s frame: %s",
   542           goal_pose.
frame_id_.c_str(), global_frame.c_str(), ex.what());
   543       return goal_pose_msg;
   546     geometry_msgs::PoseStamped global_pose_msg;
   548     return global_pose_msg;
   561     bool wait_for_wake = 
false;
   567         ROS_DEBUG_NAMED(
"move_base_plan_thread",
"Planner thread is suspending");
   569         wait_for_wake = 
false;
   585         std::vector<geometry_msgs::PoseStamped>* temp_plan = 
planner_plan_;
   594         ROS_DEBUG_NAMED(
"move_base_plan_thread",
"Generated a plan from the base_global_planner");
   632           wait_for_wake = 
true;
   642       as_->
setAborted(move_base_msgs::MoveBaseResult(), 
"Aborting on goal because it was sent with an invalid quaternion");
   656     std::vector<geometry_msgs::PoseStamped> global_plan;
   660       ROS_DEBUG_NAMED(
"move_base",
"Starting up costmaps that were shut down previously");
   687             as_->
setAborted(move_base_msgs::MoveBaseResult(), 
"Aborting on goal because it was sent with an invalid quaternion");
   705           ROS_DEBUG_NAMED(
"move_base",
"move_base has received a goal of x: %.2f, y: %.2f", goal.pose.position.x, goal.pose.position.y);
   743         ROS_DEBUG_NAMED(
"move_base",
"The global frame for move_base has changed, new frame: %s, new goal position x: %.2f, y: %.2f", goal.header.frame_id.c_str(), goal.pose.position.x, goal.pose.position.y);
   781     as_->
setAborted(move_base_msgs::MoveBaseResult(), 
"Aborting on the goal because the node has been killed");
   785   double MoveBase::distance(
const geometry_msgs::PoseStamped& p1, 
const geometry_msgs::PoseStamped& p2)
   787     return hypot(p1.pose.position.x - p2.pose.position.x, p1.pose.position.y - p2.pose.position.y);
   793     geometry_msgs::Twist cmd_vel;
   798     geometry_msgs::PoseStamped current_position;
   802     move_base_msgs::MoveBaseFeedback feedback;
   803     feedback.base_position = current_position;
   842         ROS_ERROR(
"Failed to pass global plan to the controller, aborting.");
   850         as_->
setAborted(move_base_msgs::MoveBaseResult(), 
"Failed to pass global plan to the controller.");
   868         ROS_DEBUG_NAMED(
"move_base",
"Waiting for plan, in the planning state.");
   876         if(
tc_->isGoalReached()){
   901         if(
tc_->computeVelocityCommands(cmd_vel)){
   902           ROS_DEBUG_NAMED( 
"move_base", 
"Got a valid command from the local planner: %.3lf, %.3lf, %.3lf",
   903                            cmd_vel.linear.x, cmd_vel.linear.y, cmd_vel.angular.z );
   911           ROS_DEBUG_NAMED(
"move_base", 
"The local planner could not find a valid plan.");
   960           ROS_DEBUG_NAMED(
"move_base_recovery",
"All recovery behaviors have failed, locking the planner and disabling it.");
   966           ROS_DEBUG_NAMED(
"move_base_recovery",
"Something should abort after this.");
   969             ROS_ERROR(
"Aborting because a valid control could not be found. Even after executing all recovery behaviors");
   970             as_->
setAborted(move_base_msgs::MoveBaseResult(), 
"Failed to find a valid control. Even after executing recovery behaviors.");
   973             ROS_ERROR(
"Aborting because a valid plan could not be found. Even after executing all recovery behaviors");
   974             as_->
setAborted(move_base_msgs::MoveBaseResult(), 
"Failed to find a valid plan. Even after executing recovery behaviors.");
   977             ROS_ERROR(
"Aborting because the robot appears to be oscillating over and over. Even after executing all recovery behaviors");
   978             as_->
setAborted(move_base_msgs::MoveBaseResult(), 
"Robot is oscillating. Even after executing recovery behaviors.");
   985         ROS_ERROR(
"This case should never be reached, something is wrong, aborting");
   991         as_->
setAborted(move_base_msgs::MoveBaseResult(), 
"Reached a case that should not be hit in move_base. This is a bug, please report it.");
  1001     if(node.
getParam(
"recovery_behaviors", behavior_list)){
  1003         for(
int i = 0; i < behavior_list.
size(); ++i){
  1005             if(behavior_list[i].hasMember(
"name") && behavior_list[i].
hasMember(
"type")){
  1007               for(
int j = i + 1; j < behavior_list.
size(); j++){
  1009                   if(behavior_list[j].hasMember(
"name") && behavior_list[j].
hasMember(
"type")){
  1010                     std::string name_i = behavior_list[i][
"name"];
  1011                     std::string name_j = behavior_list[j][
"name"];
  1012                     if(name_i == name_j){
  1013                       ROS_ERROR(
"A recovery behavior with the name %s already exists, this is not allowed. Using the default recovery behaviors instead.", 
  1022               ROS_ERROR(
"Recovery behaviors must have a name and a type and this does not. Using the default recovery behaviors instead.");
  1027             ROS_ERROR(
"Recovery behaviors must be specified as maps, but they are XmlRpcType %d. We'll use the default recovery behaviors instead.",
  1028                 behavior_list[i].getType());
  1034         for(
int i = 0; i < behavior_list.
size(); ++i){
  1039               for(
unsigned int i = 0; i < classes.size(); ++i){
  1042                   ROS_WARN(
"Recovery behavior specifications should now include the package name. You are using a deprecated API. Please switch from %s to %s in your yaml file.",
  1043                       std::string(behavior_list[i][
"type"]).c_str(), classes[i].c_str());
  1044                   behavior_list[i][
"type"] = classes[i];
  1053             if(behavior.get() == NULL){
  1054               ROS_ERROR(
"The ClassLoader returned a null pointer without throwing an exception. This should not happen");
  1063             ROS_ERROR(
"Failed to load a plugin. Using default recovery behaviors. Error: %s", ex.what());
  1069         ROS_ERROR(
"The recovery behavior specification must be a list, but is of XmlRpcType %d. We'll use the default recovery behaviors instead.", 
  1114       ROS_FATAL(
"Failed to load a plugin. This should not happen on default recovery behaviors. Error: %s", ex.what());
  1142     global_pose.setIdentity();
  1144     robot_pose.setIdentity();
  1156       ROS_ERROR_THROTTLE(1.0, 
"No Transform available Error looking up robot pose: %s\n", ex.what());
  1161       ROS_ERROR_THROTTLE(1.0, 
"Connectivity Error looking up robot pose: %s\n", ex.what());
  1166       ROS_ERROR_THROTTLE(1.0, 
"Extrapolation Error looking up robot pose: %s\n", ex.what());
  1174                         "Current time: %.4f, pose stamp: %.4f, tolerance: %.4f", costmap->
getName().c_str(),
 void executeCb(const move_base_msgs::MoveBaseGoalConstPtr &move_base_goal)
boost::condition_variable_any planner_cond_
boost::thread * planner_thread_
void wakePlanner(const ros::TimerEvent &event)
This is used to wake the planner at periodic intervals. 
ros::ServiceServer make_plan_srv_
double distance(const geometry_msgs::PoseStamped &p1, const geometry_msgs::PoseStamped &p2)
boost::shared_ptr< const Goal > acceptNewGoal()
void publishFeedback(const FeedbackConstPtr &feedback)
pluginlib::ClassLoader< nav_core::BaseLocalPlanner > blp_loader_
MoveBaseActionServer * as_
tfScalar getAngle() const 
bool isQuaternionValid(const geometry_msgs::Quaternion &q)
void publish(const boost::shared_ptr< M > &message) const 
costmap_2d::Costmap2DROS * controller_costmap_ros_
int32_t max_planning_retries_
bool getRobotPose(tf::Stamped< tf::Pose > &global_pose) const 
bool planService(nav_msgs::GetPlan::Request &req, nav_msgs::GetPlan::Response &resp)
A service call that can be made when the action is inactive that will return a plan. 
pluginlib::ClassLoader< nav_core::BaseGlobalPlanner > bgp_loader_
boost::recursive_mutex configuration_mutex_
double planner_frequency_
static void poseStampedTFToMsg(const Stamped< Pose > &bt, geometry_msgs::PoseStamped &msg)
Duration cycleTime() const 
std::string getGlobalFrameID()
void notify_one() BOOST_NOEXCEPT
ros::Publisher action_goal_pub_
virtual ~MoveBase()
Destructor - Cleans up. 
ROSCPP_DECL const std::string & getName()
ros::Time last_oscillation_reset_
bool getRobotPose(tf::Stamped< tf::Pose > &global_posee, costmap_2d::Costmap2DROS *costmap)
bool recovery_behavior_enabled_
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
actionlib::SimpleActionServer< move_base_msgs::MoveBaseAction > MoveBaseActionServer
std::string global_frame_
Type const & getType() const 
TFSIMD_FORCE_INLINE const tfScalar & y() const 
static const unsigned char FREE_SPACE
std::vector< geometry_msgs::PoseStamped > * planner_plan_
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
boost::shared_ptr< nav_core::BaseGlobalPlanner > planner_
std::string getName() const 
bool clearing_rotation_allowed_
#define ROS_DEBUG_NAMED(name,...)
unsigned int recovery_index_
dynamic_reconfigure::Server< move_base::MoveBaseConfig > * dsrv_
RecoveryTrigger recovery_trigger_
TFSIMD_FORCE_INLINE tfScalar dot(const Vector3 &v) const 
void setPreempted(const Result &result=Result(), const std::string &text=std::string(""))
TFSIMD_FORCE_INLINE Vector3 rotate(const Vector3 &wAxis, const tfScalar angle) const 
ros::ServiceServer clear_costmaps_srv_
#define ROS_WARN_THROTTLE(period,...)
move_base::MoveBaseConfig default_config_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const 
std::vector< std::string > getDeclaredClasses()
#define ROS_ERROR_THROTTLE(period,...)
ros::Time last_valid_plan_
void loadDefaultRecoveryBehaviors()
Loads the default recovery behaviors for the navigation stack. 
std::vector< boost::shared_ptr< nav_core::RecoveryBehavior > > recovery_behaviors_
bool loadRecoveryBehaviors(ros::NodeHandle node)
Load the recovery behaviors for the navigation stack from the parameter server. 
void reconfigureCB(move_base::MoveBaseConfig &config, uint32_t level)
double controller_patience_
double getTransformTolerance() const 
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const 
void goalCB(const geometry_msgs::PoseStamped::ConstPtr &goal)
pluginlib::ClassLoader< nav_core::RecoveryBehavior > recovery_loader_
TFSIMD_FORCE_INLINE const tfScalar & x() const 
double controller_frequency_
bool isPreemptRequested()
bool setConvexPolygonCost(const std::vector< geometry_msgs::Point > &polygon, unsigned char cost_value)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
costmap_2d::Costmap2DROS * planner_costmap_ros_
boost::recursive_mutex planner_mutex_
virtual std::string getName(const std::string &lookup_name)
void publishZeroVelocity()
Publishes a velocity command of zero to the base. 
geometry_msgs::PoseStamped goalToGlobalFrame(const geometry_msgs::PoseStamped &goal_pose_msg)
TFSIMD_FORCE_INLINE tfScalar dot(const Quaternion &q1, const Quaternion &q2)
double oscillation_distance_
boost::shared_ptr< nav_core::BaseLocalPlanner > tc_
void resetState()
Reset the state of the move_base action and send a zero velocity command to the base. 
void setAborted(const Result &result=Result(), const std::string &text=std::string(""))
bool hasMember(const std::string &name) const 
ros::Publisher current_goal_pub_
geometry_msgs::PoseStamped planner_goal_
ros::Subscriber goal_sub_
tf::TransformListener & tf_
TFSIMD_FORCE_INLINE Vector3 rotate(const Vector3 &wAxis, const tfScalar angle) const 
bool getParam(const std::string &key, std::string &s) const 
std::vector< geometry_msgs::PoseStamped > * latest_plan_
move_base::MoveBaseConfig last_config_
MoveBase(tf::TransformListener &tf)
Constructor for the actions. 
bool clearCostmapsService(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
A service call that clears the costmaps of obstacles. 
uint32_t planning_retries_
double circumscribed_radius_
double getResolution() const 
std::string robot_base_frame_
bool makePlan(const geometry_msgs::PoseStamped &goal, std::vector< geometry_msgs::PoseStamped > &plan)
Make a new global plan. 
double conservative_reset_dist_
bool executeCycle(geometry_msgs::PoseStamped &goal, std::vector< geometry_msgs::PoseStamped > &global_plan)
Performs a control cycle. 
virtual bool isClassAvailable(const std::string &lookup_name)
ros::Time last_valid_control_
double oscillation_timeout_
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const 
geometry_msgs::PoseStamped oscillation_pose_
void clearCostmapWindows(double size_x, double size_y)
Clears obstacles within a window around the robot. 
bool isNewGoalAvailable()
std::vector< geometry_msgs::PoseStamped > * controller_plan_