sbpl_recovery.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2009, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Willow Garage, Inc. nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *
35  * Author: Eitan Marder-Eppstein
36  *********************************************************************/
37 
40 
42 
43 namespace sbpl_recovery
44 {
45  SBPLRecovery::SBPLRecovery():
46  global_costmap_(NULL),
47  local_costmap_(NULL),
48  tf_(NULL),
49  initialized_(false)
50  {
51  }
52 
54  costmap_2d::Costmap2DROS* global_costmap,
55  costmap_2d::Costmap2DROS* local_costmap)
56  {
58  ros::NodeHandle p_nh = ros::NodeHandle("~/" + n);
59 
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);
67 
68  double planning_distance;
69  p_nh.param("planning_distance", planning_distance, 2.0);
70  sq_planning_distance_ = planning_distance * planning_distance;
71 
72  //we need to initialize our costmaps
73  global_costmap_ = global_costmap;
74  local_costmap_ = local_costmap;
75  tf_ = tf;
76 
77  //we need to initialize our local and global planners
79  global_planner_.initialize(n + "/sbpl_lattice_planner", local_costmap_);
80  else
81  global_planner_.initialize(n + "/sbpl_lattice_planner", global_costmap_);
82 
83  local_planner_.initialize(n + "/pose_follower", tf, local_costmap_);
84 
85  //we'll need to subscribe to get the latest plan information
86  vel_pub_ = nh.advertise<geometry_msgs::Twist>("cmd_vel", 1);
87 
88  ros::NodeHandle node_nh("~/");
89  plan_sub_ = node_nh.subscribe<nav_msgs::Path>(plan_topic, 1, boost::bind(&SBPLRecovery::planCB, this, _1));
90  initialized_ = true;
91  }
92 
93  void SBPLRecovery::planCB(const nav_msgs::Path::ConstPtr& plan)
94  {
95  //just copy the plan data over
96 
97  tf::Stamped<tf::Pose> global_pose;
98  local_costmap_->getRobotPose(global_pose);
99 
100  costmap_2d::Costmap2D costmap;
101  costmap = *(local_costmap_->getCostmap());
102 
103  if(use_local_frame_)
104  {
105  std::vector<geometry_msgs::PoseStamped> transformed_plan;
106  if(base_local_planner::transformGlobalPlan(*tf_, plan->poses, global_pose, costmap, local_costmap_->getGlobalFrameID(), transformed_plan))
107  {
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;
112  }
113  else
114  ROS_WARN("Could not transform to frame of the local recovery");
115  }
116  else
117  {
118  boost::mutex::scoped_lock l(plan_mutex_);
119  plan_ = *plan;
120  }
121  }
122 
123  double SBPLRecovery::sqDistance(const geometry_msgs::PoseStamped& p1,
124  const geometry_msgs::PoseStamped& p2)
125  {
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);
128  }
129 
130  std::vector<geometry_msgs::PoseStamped> SBPLRecovery::makePlan()
131  {
132  boost::mutex::scoped_lock l(plan_mutex_);
133  std::vector<geometry_msgs::PoseStamped> sbpl_plan;
134 
135  tf::Stamped<tf::Pose> global_pose;
136  if(use_local_frame_)
137  {
138  if(!local_costmap_->getRobotPose(global_pose))
139  {
140  ROS_ERROR("SBPL recovery behavior could not get the current pose of the robot. Doing nothing.");
141  return sbpl_plan;
142  }
143  }
144  else
145  {
146  if(!global_costmap_->getRobotPose(global_pose))
147  {
148  ROS_ERROR("SBPL recovery behavior could not get the current pose of the robot. Doing nothing.");
149  return sbpl_plan;
150  }
151  }
152 
153  geometry_msgs::PoseStamped start;
154  tf::poseStampedTFToMsg(global_pose, start);
155 
156  //first, we want to walk far enough along the path that we get to a point
157  //that is within the recovery distance from the robot. Otherwise, we might
158  //move backwards along the plan
159  unsigned int index = 0;
160  for(index=0; index < plan_.poses.size(); ++index)
161  {
162  if(sqDistance(start, plan_.poses[index]) < sq_planning_distance_)
163  break;
164  }
165 
166  //next, we want to find a goal point that is far enough away from the robot on the
167  //original plan and attempt to plan to it
168  int unsuccessful_attempts = 0;
169  for(unsigned int i = index; i < plan_.poses.size(); ++i)
170  {
171  ROS_DEBUG("SQ Distance: %.2f, spd: %.2f, start (%.2f, %.2f), goal (%.2f, %.2f)",
172  sqDistance(start, plan_.poses[i]),
174  start.pose.position.x, start.pose.position.y,
175  plan_.poses[i].pose.position.x,
176  plan_.poses[i].pose.position.y);
177  if(sqDistance(start, plan_.poses[i]) >= sq_planning_distance_ || i == (plan_.poses.size() - 1))
178  {
179  ROS_INFO("Calling sbpl planner with start (%.2f, %.2f), goal (%.2f, %.2f)",
180  start.pose.position.x, start.pose.position.y,
181  plan_.poses[i].pose.position.x,
182  plan_.poses[i].pose.position.y);
183  if(global_planner_.makePlan(start, plan_.poses[i], sbpl_plan) && !sbpl_plan.empty())
184  {
185  ROS_INFO("Got a valid plan");
186  return sbpl_plan;
187  }
188  sbpl_plan.clear();
189 
190  //make sure that we don't spend forever planning
191  unsuccessful_attempts++;
192  if(unsuccessful_attempts >= attempts_per_run_)
193  return sbpl_plan;
194  }
195  }
196 
197  return sbpl_plan;
198  }
199 
201  {
202  if(!initialized_)
203  {
204  ROS_ERROR("Please initialize this recovery behavior before attempting to run it.");
205  return;
206  }
207 
208  ROS_INFO("Starting the sbpl recovery behavior");
209 
210  for(int i=0; i <= planning_attempts_; ++i)
211  {
212  std::vector<geometry_msgs::PoseStamped> sbpl_plan = makePlan();
213 
214  if(sbpl_plan.empty())
215  {
216  ROS_ERROR("Unable to find a valid pose to plan to on the global plan.");
217  return;
218  }
219 
220  //ok... now we've got a plan so we need to try to follow it
221  local_planner_.setPlan(sbpl_plan);
223  ros::Time last_valid_control = ros::Time::now();
224  while(ros::ok() &&
225  last_valid_control + ros::Duration(controller_patience_) >= ros::Time::now() &&
227  {
228  geometry_msgs::Twist cmd_vel;
229  bool valid_control = local_planner_.computeVelocityCommands(cmd_vel);
230 
231  if(valid_control)
232  last_valid_control = ros::Time::now();
233 
234  vel_pub_.publish(cmd_vel);
235  r.sleep();
236  }
237 
239  ROS_INFO("The sbpl recovery behavior made it to its desired goal");
240  else
241  ROS_WARN("The sbpl recovery behavior failed to make it to its desired goal");
242  }
243  }
244 };
virtual void initialize(std::string name, costmap_2d::Costmap2DROS *costmap_ros)
void publish(const boost::shared_ptr< M > &message) const
bool getRobotPose(tf::Stamped< tf::Pose > &global_pose) const
costmap_2d::Costmap2DROS * local_costmap_
Definition: sbpl_recovery.h:72
static void poseStampedTFToMsg(const Stamped< Pose > &bt, geometry_msgs::PoseStamped &msg)
std::string getGlobalFrameID()
PLUGINLIB_EXPORT_CLASS(BAGReader, nodelet::Nodelet)
sbpl_lattice_planner::SBPLLatticePlanner global_planner_
Definition: sbpl_recovery.h:74
tf::TransformListener * tf_
bool setPlan(const std::vector< geometry_msgs::PoseStamped > &global_plan)
#define ROS_WARN(...)
tf::TransformListener * tf_
Definition: sbpl_recovery.h:73
costmap_2d::Costmap2DROS * global_costmap_
Definition: sbpl_recovery.h:71
bool transformGlobalPlan(const tf::TransformListener &tf, const std::vector< geometry_msgs::PoseStamped > &global_plan, const tf::Stamped< tf::Pose > &global_robot_pose, const costmap_2d::Costmap2D &costmap, const std::string &global_frame, std::vector< geometry_msgs::PoseStamped > &transformed_plan)
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
bool computeVelocityCommands(geometry_msgs::Twist &cmd_vel)
ROSCPP_DECL bool ok()
pose_follower::PoseFollower local_planner_
Definition: sbpl_recovery.h:75
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
virtual bool makePlan(const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, std::vector< geometry_msgs::PoseStamped > &plan)
void initialize(std::string name, tf::TransformListener *tf, costmap_2d::Costmap2DROS *costmap_ros)
bool sleep()
void initialize(std::string n, tf::TransformListener *tf, costmap_2d::Costmap2DROS *global_costmap, costmap_2d::Costmap2DROS *local_costmap)
static Time now()
Costmap2D * getCostmap()
std::vector< geometry_msgs::PoseStamped > makePlan()
#define ROS_ERROR(...)
double sqDistance(const geometry_msgs::PoseStamped &p1, const geometry_msgs::PoseStamped &p2)
void planCB(const nav_msgs::Path::ConstPtr &plan)
#define ROS_DEBUG(...)


sbpl_recovery
Author(s): Eitan Marder-Eppstein
autogenerated on Tue Apr 2 2019 02:34:50