46 global_costmap_(NULL),
60 std::string plan_topic;
61 p_nh.
param(
"plan_topic", plan_topic, std::string(
"NavfnROS/plan"));
62 p_nh.
param(
"control_frequency", control_frequency_, 10.0);
63 p_nh.
param(
"controller_patience", controller_patience_, 5.0);
64 p_nh.
param(
"planning_attempts", planning_attempts_, 3);
65 p_nh.
param(
"attempts_per_run", attempts_per_run_, 3);
66 p_nh.
param(
"use_local_frame", use_local_frame_,
true);
68 double planning_distance;
69 p_nh.
param(
"planning_distance", planning_distance, 2.0);
70 sq_planning_distance_ = planning_distance * planning_distance;
73 global_costmap_ = global_costmap;
74 local_costmap_ = local_costmap;
79 global_planner_.initialize(n +
"/sbpl_lattice_planner", local_costmap_);
81 global_planner_.initialize(n +
"/sbpl_lattice_planner", global_costmap_);
83 local_planner_.initialize(n +
"/pose_follower",
tf, local_costmap_);
86 vel_pub_ = nh.
advertise<geometry_msgs::Twist>(
"cmd_vel", 1);
89 plan_sub_ = node_nh.subscribe<nav_msgs::Path>(plan_topic, 1, boost::bind(&SBPLRecovery::planCB,
this, _1));
93 void SBPLRecovery::planCB(
const nav_msgs::Path::ConstPtr& plan)
97 geometry_msgs::PoseStamped global_pose;
98 local_costmap_->getRobotPose(global_pose);
101 costmap = *(local_costmap_->getCostmap());
105 std::vector<geometry_msgs::PoseStamped> transformed_plan;
108 boost::mutex::scoped_lock l(plan_mutex_);
109 if(!transformed_plan.empty())
110 plan_.header = transformed_plan[0].header;
111 plan_.poses = transformed_plan;
114 ROS_WARN(
"Could not transform to frame of the local recovery");
118 boost::mutex::scoped_lock l(plan_mutex_);
123 double SBPLRecovery::sqDistance(
const geometry_msgs::PoseStamped& p1,
124 const geometry_msgs::PoseStamped& p2)
126 return (p1.pose.position.x - p2.pose.position.x) * (p1.pose.position.x - p2.pose.position.x) +
127 (p1.pose.position.y - p2.pose.position.y) * (p1.pose.position.y - p2.pose.position.y);
130 std::vector<geometry_msgs::PoseStamped> SBPLRecovery::makePlan()
132 boost::mutex::scoped_lock l(plan_mutex_);
133 std::vector<geometry_msgs::PoseStamped> sbpl_plan;
135 geometry_msgs::PoseStamped
start;
138 if(!local_costmap_->getRobotPose(
start))
140 ROS_ERROR(
"SBPL recovery behavior could not get the current pose of the robot. Doing nothing.");
146 if(!global_costmap_->getRobotPose(start))
148 ROS_ERROR(
"SBPL recovery behavior could not get the current pose of the robot. Doing nothing.");
156 unsigned int index = 0;
157 for(index=0; index < plan_.poses.size(); ++index)
159 if(sqDistance(
start, plan_.poses[index]) < sq_planning_distance_)
165 int unsuccessful_attempts = 0;
166 for(
unsigned int i = index; i < plan_.poses.size(); ++i)
168 ROS_DEBUG(
"SQ Distance: %.2f, spd: %.2f, start (%.2f, %.2f), goal (%.2f, %.2f)",
169 sqDistance(
start, plan_.poses[i]),
170 sq_planning_distance_,
172 plan_.poses[i].pose.position.x,
173 plan_.poses[i].pose.position.y);
174 if(sqDistance(
start, plan_.poses[i]) >= sq_planning_distance_ || i == (plan_.poses.size() - 1))
176 ROS_INFO(
"Calling sbpl planner with start (%.2f, %.2f), goal (%.2f, %.2f)",
178 plan_.poses[i].pose.position.x,
179 plan_.poses[i].pose.position.y);
180 if(global_planner_.makePlan(
start, plan_.poses[i], sbpl_plan) && !sbpl_plan.empty())
188 unsuccessful_attempts++;
189 if(unsuccessful_attempts >= attempts_per_run_)
197 void SBPLRecovery::runBehavior()
201 ROS_ERROR(
"Please initialize this recovery behavior before attempting to run it.");
205 ROS_INFO(
"Starting the sbpl recovery behavior");
207 for(
int i=0; i <= planning_attempts_; ++i)
209 std::vector<geometry_msgs::PoseStamped> sbpl_plan = makePlan();
211 if(sbpl_plan.empty())
213 ROS_ERROR(
"Unable to find a valid pose to plan to on the global plan.");
218 local_planner_.setPlan(sbpl_plan);
223 !local_planner_.isGoalReached())
225 geometry_msgs::Twist cmd_vel;
226 bool valid_control = local_planner_.computeVelocityCommands(cmd_vel);
231 vel_pub_.publish(cmd_vel);
235 if(local_planner_.isGoalReached())
236 ROS_INFO(
"The sbpl recovery behavior made it to its desired goal");
238 ROS_WARN(
"The sbpl recovery behavior failed to make it to its desired goal");