00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <sbpl_recovery/sbpl_recovery.h>
00038 #include <pluginlib/class_list_macros.h>
00039
00040 PLUGINLIB_DECLARE_CLASS(sbpl_recovery, SBPLRecovery, sbpl_recovery::SBPLRecovery,
00041 nav_core::RecoveryBehavior)
00042
00043 namespace sbpl_recovery
00044 {
00045 SBPLRecovery::SBPLRecovery():
00046 global_costmap_(NULL),
00047 local_costmap_(NULL),
00048 tf_(NULL),
00049 initialized_(false)
00050 {
00051 }
00052
00053 void SBPLRecovery::initialize (std::string n, tf::TransformListener* tf,
00054 costmap_2d::Costmap2DROS* global_costmap,
00055 costmap_2d::Costmap2DROS* local_costmap)
00056 {
00057 ros::NodeHandle nh = ros::NodeHandle();
00058 ros::NodeHandle p_nh = ros::NodeHandle("~/" + n);
00059
00060 std::string plan_topic;
00061 p_nh.param("plan_topic", plan_topic, std::string("NavfnROS/plan"));
00062 p_nh.param("control_frequency", control_frequency_, 10.0);
00063 p_nh.param("controller_patience", controller_patience_, 5.0);
00064 p_nh.param("planning_attempts", planning_attempts_, 3);
00065 p_nh.param("attempts_per_run", attempts_per_run_, 3);
00066 p_nh.param("use_local_frame", use_local_frame_, true);
00067
00068 double planning_distance;
00069 p_nh.param("planning_distance", planning_distance, 2.0);
00070 sq_planning_distance_ = planning_distance * planning_distance;
00071
00072
00073 global_costmap_ = global_costmap;
00074 local_costmap_ = local_costmap;
00075 tf_ = tf;
00076
00077
00078 if(use_local_frame_)
00079 global_planner_.initialize(n + "/sbpl_lattice_planner", local_costmap_);
00080 else
00081 global_planner_.initialize(n + "/sbpl_lattice_planner", global_costmap_);
00082
00083 local_planner_.initialize(n + "/pose_follower", tf, local_costmap_);
00084
00085
00086 vel_pub_ = nh.advertise<geometry_msgs::Twist>("cmd_vel", 1);
00087
00088 ros::NodeHandle node_nh("~/");
00089 plan_sub_ = node_nh.subscribe<nav_msgs::Path>(plan_topic, 1, boost::bind(&SBPLRecovery::planCB, this, _1));
00090 initialized_ = true;
00091 }
00092
00093 void SBPLRecovery::planCB(const nav_msgs::Path::ConstPtr& plan)
00094 {
00095
00096 if(use_local_frame_)
00097 {
00098 std::vector<geometry_msgs::PoseStamped> transformed_plan;
00099 if(base_local_planner::transformGlobalPlan(*tf_, plan->poses, *local_costmap_, local_costmap_->getGlobalFrameID(), transformed_plan))
00100 {
00101 boost::mutex::scoped_lock l(plan_mutex_);
00102 if(!transformed_plan.empty())
00103 plan_.header = transformed_plan[0].header;
00104 plan_.poses = transformed_plan;
00105 }
00106 else
00107 ROS_WARN("Could not transform to frame of the local recovery");
00108 }
00109 else
00110 {
00111 boost::mutex::scoped_lock l(plan_mutex_);
00112 plan_ = *plan;
00113 }
00114 }
00115
00116 double SBPLRecovery::sqDistance(const geometry_msgs::PoseStamped& p1,
00117 const geometry_msgs::PoseStamped& p2)
00118 {
00119 return (p1.pose.position.x - p2.pose.position.x) * (p1.pose.position.x - p2.pose.position.x) +
00120 (p1.pose.position.y - p2.pose.position.y) * (p1.pose.position.y - p2.pose.position.y);
00121 }
00122
00123 std::vector<geometry_msgs::PoseStamped> SBPLRecovery::makePlan()
00124 {
00125 boost::mutex::scoped_lock l(plan_mutex_);
00126 std::vector<geometry_msgs::PoseStamped> sbpl_plan;
00127
00128 tf::Stamped<tf::Pose> global_pose;
00129 if(use_local_frame_)
00130 {
00131 if(!local_costmap_->getRobotPose(global_pose))
00132 {
00133 ROS_ERROR("SBPL recovery behavior could not get the current pose of the robot. Doing nothing.");
00134 return sbpl_plan;
00135 }
00136 }
00137 else
00138 {
00139 if(!global_costmap_->getRobotPose(global_pose))
00140 {
00141 ROS_ERROR("SBPL recovery behavior could not get the current pose of the robot. Doing nothing.");
00142 return sbpl_plan;
00143 }
00144 }
00145
00146 geometry_msgs::PoseStamped start;
00147 tf::poseStampedTFToMsg(global_pose, start);
00148
00149
00150
00151
00152 unsigned int index = 0;
00153 for(index=0; index < plan_.poses.size(); ++index)
00154 {
00155 if(sqDistance(start, plan_.poses[index]) < sq_planning_distance_)
00156 break;
00157 }
00158
00159
00160
00161 int unsuccessful_attempts = 0;
00162 for(unsigned int i = index; i < plan_.poses.size(); ++i)
00163 {
00164 ROS_DEBUG("SQ Distance: %.2f, spd: %.2f, start (%.2f, %.2f), goal (%.2f, %.2f)",
00165 sqDistance(start, plan_.poses[i]),
00166 sq_planning_distance_,
00167 start.pose.position.x, start.pose.position.y,
00168 plan_.poses[i].pose.position.x,
00169 plan_.poses[i].pose.position.y);
00170 if(sqDistance(start, plan_.poses[i]) >= sq_planning_distance_ || i == (plan_.poses.size() - 1))
00171 {
00172 ROS_INFO("Calling sbpl planner with start (%.2f, %.2f), goal (%.2f, %.2f)",
00173 start.pose.position.x, start.pose.position.y,
00174 plan_.poses[i].pose.position.x,
00175 plan_.poses[i].pose.position.y);
00176 if(global_planner_.makePlan(start, plan_.poses[i], sbpl_plan) && !sbpl_plan.empty())
00177 {
00178 ROS_INFO("Got a valid plan");
00179 return sbpl_plan;
00180 }
00181 sbpl_plan.clear();
00182
00183
00184 unsuccessful_attempts++;
00185 if(unsuccessful_attempts >= attempts_per_run_)
00186 return sbpl_plan;
00187 }
00188 }
00189
00190 return sbpl_plan;
00191 }
00192
00193 void SBPLRecovery::runBehavior()
00194 {
00195 if(!initialized_)
00196 {
00197 ROS_ERROR("Please initialize this recovery behavior before attempting to run it.");
00198 return;
00199 }
00200
00201 ROS_INFO("Starting the sbpl recovery behavior");
00202
00203 for(int i=0; i <= planning_attempts_; ++i)
00204 {
00205 std::vector<geometry_msgs::PoseStamped> sbpl_plan = makePlan();
00206
00207 if(sbpl_plan.empty())
00208 {
00209 ROS_ERROR("Unable to find a valid pose to plan to on the global plan.");
00210 return;
00211 }
00212
00213
00214
00215 double window_size = 2 * sqrt(sq_planning_distance_);
00216 global_costmap_->clearNonLethalWindow(window_size, window_size);
00217 local_costmap_->clearNonLethalWindow(window_size, window_size);
00218
00219
00220 local_planner_.setPlan(sbpl_plan);
00221 ros::Rate r(control_frequency_);
00222 ros::Time last_valid_control = ros::Time::now();
00223 while(ros::ok() &&
00224 last_valid_control + ros::Duration(controller_patience_) >= ros::Time::now() &&
00225 !local_planner_.isGoalReached())
00226 {
00227 geometry_msgs::Twist cmd_vel;
00228 bool valid_control = local_planner_.computeVelocityCommands(cmd_vel);
00229
00230 if(valid_control)
00231 last_valid_control = ros::Time::now();
00232
00233 vel_pub_.publish(cmd_vel);
00234 r.sleep();
00235 }
00236
00237 if(local_planner_.isGoalReached())
00238 ROS_INFO("The sbpl recovery behavior made it to its desired goal");
00239 else
00240 ROS_WARN("The sbpl recovery behavior failed to make it to its desired goal");
00241 }
00242 }
00243 };