base_local_planner
goal_functions.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 *********************************************************************/
38 #include <tf2/LinearMath/Matrix3x3.h>
39 #include <tf2/utils.h>
40 #include <tf2_geometry_msgs/tf2_geometry_msgs.h>
41 #ifdef _MSC_VER
42 #define GOAL_ATTRIBUTE_UNUSED
43 #else
44 #define GOAL_ATTRIBUTE_UNUSED __attribute__ ((unused))
45 #endif
46 
47 namespace base_local_planner {
48 
49  double getGoalPositionDistance(const geometry_msgs::PoseStamped& global_pose, double goal_x, double goal_y) {
50  return hypot(goal_x - global_pose.pose.position.x, goal_y - global_pose.pose.position.y);
51  }
52 
53  double getGoalOrientationAngleDifference(const geometry_msgs::PoseStamped& global_pose, double goal_th) {
54  double yaw = tf2::getYaw(global_pose.pose.orientation);
55  return angles::shortest_angular_distance(yaw, goal_th);
56  }
57 
58  void publishPlan(const std::vector<geometry_msgs::PoseStamped>& path, const ros::Publisher& pub) {
59  //given an empty path we won't do anything
60  if(path.empty())
61  return;
62 
63  //create a path message
64  nav_msgs::Path gui_path;
65  gui_path.poses.resize(path.size());
66  gui_path.header.frame_id = path[0].header.frame_id;
67  gui_path.header.stamp = path[0].header.stamp;
68 
69  // Extract the plan in world co-ordinates, we assume the path is all in the same frame
70  for(unsigned int i=0; i < path.size(); i++){
71  gui_path.poses[i] = path[i];
72  }
73 
74  pub.publish(gui_path);
75  }
76 
77  void prunePlan(const geometry_msgs::PoseStamped& global_pose, std::vector<geometry_msgs::PoseStamped>& plan, std::vector<geometry_msgs::PoseStamped>& global_plan){
78  ROS_ASSERT(global_plan.size() >= plan.size());
79  double min_plan_sq_dist = 1e6;
80  int current_waypoint_index = -1;
81 
82  for(unsigned int i = 0; i < plan.size(); ++i){
83  double x_diff = global_pose.pose.position.x - plan[i].pose.position.x;
84  double y_diff = global_pose.pose.position.y - plan[i].pose.position.y;
85  double sq_plan_dist = x_diff * x_diff + y_diff * y_diff;
86 
87  if (sq_plan_dist < min_plan_sq_dist){
88  current_waypoint_index = i;
89  min_plan_sq_dist = sq_plan_dist;
90  }
91  }
92 
94  if (current_waypoint_index >= 0)
95  {
96  ROS_DEBUG("Nearest waypoint to <%f, %f> is <%f, %f>\n", global_pose.pose.position.x, global_pose.pose.position.y,
97  plan[current_waypoint_index].pose.position.x, plan[current_waypoint_index].pose.position.y);
98  plan = std::vector<geometry_msgs::PoseStamped>(plan.begin() + current_waypoint_index, plan.end());
99  global_plan = std::vector<geometry_msgs::PoseStamped>(global_plan.begin() + current_waypoint_index, global_plan.end());
100  }
101  }
102 
104  double waypoint_dist_sum = 0;
105  unsigned int target_waypoint_index = plan.size() - 1;
106  for(unsigned int i = 1; i < plan.size(); ++i){
107  double x_diff = plan[i].pose.position.x - plan[i-1].pose.position.x;
108  double y_diff = plan[i].pose.position.y - plan[i-1].pose.position.y;
109  double waypoint_dist = sqrt(x_diff * x_diff + y_diff * y_diff);
110  waypoint_dist_sum += waypoint_dist;
111  if (waypoint_dist_sum > lookahead)
112  {
113  target_waypoint_index = i;
114  break;
115  }
116  }
117 
118  new_plan = std::vector<geometry_msgs::PoseStamped>(plan.begin()+target_waypoint_index, plan.end());
119  }
120 
122  const tf2_ros::Buffer& tf,
123  const std::vector<geometry_msgs::PoseStamped>& global_plan,
124  const geometry_msgs::PoseStamped& global_pose,
125  const costmap_2d::Costmap2D& costmap,
126  const std::string& global_frame,
127  std::vector<geometry_msgs::PoseStamped>& transformed_plan){
128  transformed_plan.clear();
129 
130  if (global_plan.empty()) {
131  ROS_ERROR("Received plan with zero length");
132  return false;
133  }
134 
135  const geometry_msgs::PoseStamped& plan_pose = global_plan[0];
136  try {
137  // get plan_to_global_transform from plan frame to global_frame
138  geometry_msgs::TransformStamped plan_to_global_transform = tf.lookupTransform(global_frame, ros::Time(),
139  plan_pose.header.frame_id, plan_pose.header.stamp, plan_pose.header.frame_id, ros::Duration(0.5));
140 
141  //let's get the pose of the robot in the frame of the plan
142  geometry_msgs::PoseStamped robot_pose;
143  tf.transform(global_pose, robot_pose, plan_pose.header.frame_id);
144 
145  //we'll discard points on the plan that are outside the local costmap
146  double dist_threshold = std::max(costmap.getSizeInCellsX() * costmap.getResolution() / 2.0,
147  costmap.getSizeInCellsY() * costmap.getResolution() / 2.0);
148 
149  unsigned int i = 0;
150  double sq_dist_threshold = dist_threshold * dist_threshold;
151  double sq_dist = 0;
152 
153  //we need to loop to a point on the plan that is within a certain distance of the robot
154  while(i < (unsigned int)global_plan.size()) {
155  double x_diff = robot_pose.pose.position.x - global_plan[i].pose.position.x;
156  double y_diff = robot_pose.pose.position.y - global_plan[i].pose.position.y;
157  sq_dist = x_diff * x_diff + y_diff * y_diff;
158  if (sq_dist <= sq_dist_threshold) {
159  break;
160  }
161  ++i;
162  }
163 
164  geometry_msgs::PoseStamped newer_pose;
165 
166  //now we'll transform until points are outside of our distance threshold
167  while(i < (unsigned int)global_plan.size() && sq_dist <= sq_dist_threshold) {
168  const geometry_msgs::PoseStamped& pose = global_plan[i];
169  tf2::doTransform(pose, newer_pose, plan_to_global_transform);
170 
171  transformed_plan.push_back(newer_pose);
172 
173  double x_diff = robot_pose.pose.position.x - global_plan[i].pose.position.x;
174  double y_diff = robot_pose.pose.position.y - global_plan[i].pose.position.y;
175  sq_dist = x_diff * x_diff + y_diff * y_diff;
176 
177  ++i;
178  }
179  }
180  catch(tf2::LookupException& ex) {
181  ROS_ERROR("No Transform available Error: %s\n", ex.what());
182  return false;
183  }
184  catch(tf2::ConnectivityException& ex) {
185  ROS_ERROR("Connectivity Error: %s\n", ex.what());
186  return false;
187  }
188  catch(tf2::ExtrapolationException& ex) {
189  ROS_ERROR("Extrapolation Error: %s\n", ex.what());
190  if (!global_plan.empty())
191  ROS_ERROR("Global Frame: %s Plan Frame size %d: %s\n", global_frame.c_str(), (unsigned int)global_plan.size(), global_plan[0].header.frame_id.c_str());
192 
193  return false;
194  }
195 
196  return true;
197  }
198 
199  bool getGoalPose(const tf2_ros::Buffer& tf,
200  const std::vector<geometry_msgs::PoseStamped>& global_plan,
201  const std::string& global_frame, geometry_msgs::PoseStamped &goal_pose) {
202  if (global_plan.empty())
203  {
204  ROS_ERROR("Received plan with zero length");
205  return false;
206  }
207 
208  const geometry_msgs::PoseStamped& plan_goal_pose = global_plan.back();
209  try{
210  geometry_msgs::TransformStamped transform = tf.lookupTransform(global_frame, ros::Time(),
211  plan_goal_pose.header.frame_id, plan_goal_pose.header.stamp,
212  plan_goal_pose.header.frame_id, ros::Duration(0.5));
213 
214  tf2::doTransform(plan_goal_pose, goal_pose, transform);
215  }
216  catch(tf2::LookupException& ex) {
217  ROS_ERROR("No Transform available Error: %s\n", ex.what());
218  return false;
219  }
220  catch(tf2::ConnectivityException& ex) {
221  ROS_ERROR("Connectivity Error: %s\n", ex.what());
222  return false;
223  }
224  catch(tf2::ExtrapolationException& ex) {
225  ROS_ERROR("Extrapolation Error: %s\n", ex.what());
226  if (global_plan.size() > 0)
227  ROS_ERROR("Global Frame: %s Plan Frame size %d: %s\n", global_frame.c_str(), (unsigned int)global_plan.size(), global_plan[0].header.frame_id.c_str());
228 
229  return false;
230  }
231  return true;
232  }
233 
234  bool isGoalReached(const tf2_ros::Buffer& tf,
235  const std::vector<geometry_msgs::PoseStamped>& global_plan,
237  const std::string& global_frame,
238  geometry_msgs::PoseStamped& global_pose,
239  const nav_msgs::Odometry& base_odom,
240  double rot_stopped_vel, double trans_stopped_vel,
241  double xy_goal_tolerance, double yaw_goal_tolerance){
242 
243  //we assume the global goal is the last point in the global plan
244  geometry_msgs::PoseStamped goal_pose;
245  getGoalPose(tf, global_plan, global_frame, goal_pose);
246 
247  double goal_x = goal_pose.pose.position.x;
248  double goal_y = goal_pose.pose.position.y;
249  double goal_th = tf2::getYaw(goal_pose.pose.orientation);
250 
251  //check to see if we've reached the goal position
252  if(getGoalPositionDistance(global_pose, goal_x, goal_y) <= xy_goal_tolerance) {
253  //check to see if the goal orientation has been reached
254  if(fabs(getGoalOrientationAngleDifference(global_pose, goal_th)) <= yaw_goal_tolerance) {
255  //make sure that we're actually stopped before returning success
256  if(stopped(base_odom, rot_stopped_vel, trans_stopped_vel))
257  return true;
258  }
259  }
260 
261  return false;
262  }
263 
264  bool stopped(const nav_msgs::Odometry& base_odom,
265  const double& rot_stopped_velocity, const double& trans_stopped_velocity){
266  return fabs(base_odom.twist.twist.angular.z) <= rot_stopped_velocity
267  && fabs(base_odom.twist.twist.linear.x) <= trans_stopped_velocity
268  && fabs(base_odom.twist.twist.linear.y) <= trans_stopped_velocity;
269  }
270 
271  bool stopped(const geometry_msgs::PoseStamped& robot_vel, const double& rot_stopped_velocity, const double& trans_stopped_velocity){
272  nav_msgs::Odometry base_odom;
273  base_odom.twist.twist.linear.x = robot_vel.pose.position.x;
274  base_odom.twist.twist.linear.y = robot_vel.pose.position.y;
275  base_odom.twist.twist.angular.z = tf2::getYaw(robot_vel.pose.orientation);
276  return stopped(base_odom, rot_stopped_velocity, trans_stopped_velocity);
277  }
278 };
base_local_planner::isGoalReached
bool isGoalReached(const tf2_ros::Buffer &tf, const std::vector< geometry_msgs::PoseStamped > &global_plan, const costmap_2d::Costmap2D &costmap, const std::string &global_frame, geometry_msgs::PoseStamped &global_pose, const nav_msgs::Odometry &base_odom, double rot_stopped_vel, double trans_stopped_vel, double xy_goal_tolerance, double yaw_goal_tolerance)
Check if the goal pose has been achieved.
std::string
std::vector< geometry_msgs::PoseStamped >
base_local_planner::getGoalPose
bool getGoalPose(const tf2_ros::Buffer &tf, const std::vector< geometry_msgs::PoseStamped > &global_plan, const std::string &global_frame, geometry_msgs::PoseStamped &goal_pose)
Returns last pose in plan.
Definition: goal_functions.cpp:199
std::vector::size
T size(T... args)
GOAL_ATTRIBUTE_UNUSED
#define GOAL_ATTRIBUTE_UNUSED
Definition: goal_functions.cpp:44
base_local_planner::transformGlobalPlan
bool transformGlobalPlan(const tf2_ros::Buffer &tf, const std::vector< geometry_msgs::PoseStamped > &global_plan, const geometry_msgs::PoseStamped &global_robot_pose, const costmap_2d::Costmap2D &costmap, const std::string &global_frame, std::vector< geometry_msgs::PoseStamped > &transformed_plan)
Transforms the global plan of the robot from the planner frame to the frame of the costmap,...
Definition: goal_functions.cpp:121
costmap_2d::Costmap2D
std::vector::back
T back(T... args)
base_local_planner::getGoalPositionDistance
double getGoalPositionDistance(const geometry_msgs::PoseStamped &global_pose, double goal_x, double goal_y)
return squared distance to check if the goal position has been achieved
Definition: goal_functions.cpp:49
std::vector::clear
T clear(T... args)
std::vector::push_back
T push_back(T... args)
std::string::c_str
T c_str(T... args)
base_local_planner::getGoalOrientationAngleDifference
double getGoalOrientationAngleDifference(const geometry_msgs::PoseStamped &global_pose, double goal_th)
return angle difference to goal to check if the goal orientation has been achieved
Definition: goal_functions.cpp:53
goal_functions.h
costmap_2d::Costmap2D::getSizeInCellsY
unsigned int getSizeInCellsY() const
base_local_planner::prunePlan
void prunePlan(const geometry_msgs::PoseStamped &global_pose, std::vector< geometry_msgs::PoseStamped > &plan, std::vector< geometry_msgs::PoseStamped > &global_plan)
Trim off parts of the global plan that are far enough behind the robot.
Definition: goal_functions.cpp:77
std::vector::begin
T begin(T... args)
std::vector::empty
T empty(T... args)
costmap_2d::Costmap2D::getResolution
double getResolution() const
std::vector::end
T end(T... args)
costmap_2d::Costmap2D::getSizeInCellsX
unsigned int getSizeInCellsX() const
std::max
T max(T... args)
base_local_planner
Definition: alignment_cost_function.h:7
base_local_planner::planFromLookahead
void planFromLookahead(const std::vector< geometry_msgs::PoseStamped > &plan, double lookahead, std::vector< geometry_msgs::PoseStamped > &new_plan)
Filters the plan from the lookahead distance up to the end.
Definition: goal_functions.cpp:103
base_local_planner::publishPlan
void publishPlan(const std::vector< geometry_msgs::PoseStamped > &path, const ros::Publisher &pub)
Publish a plan for visualization purposes.
Definition: goal_functions.cpp:58
base_local_planner::stopped
bool stopped(const nav_msgs::Odometry &base_odom, const double &rot_stopped_velocity, const double &trans_stopped_velocity)
Check whether the robot is stopped or not.
Definition: goal_functions.cpp:264