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 *********************************************************************/
39 #include <tf2/utils.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  std::vector<geometry_msgs::PoseStamped>::iterator it = plan.begin();
80  std::vector<geometry_msgs::PoseStamped>::iterator global_it = global_plan.begin();
81  while(it != plan.end()){
82  const geometry_msgs::PoseStamped& w = *it;
83  // Fixed error bound of 2 meters for now. Can reduce to a portion of the map size or based on the resolution
84  double x_diff = global_pose.pose.position.x - w.pose.position.x;
85  double y_diff = global_pose.pose.position.y - w.pose.position.y;
86  double distance_sq = x_diff * x_diff + y_diff * y_diff;
87  if(distance_sq < 1){
88  ROS_DEBUG("Nearest waypoint to <%f, %f> is <%f, %f>\n", global_pose.pose.position.x, global_pose.pose.position.y, w.pose.position.x, w.pose.position.y);
89  break;
90  }
91  it = plan.erase(it);
92  global_it = global_plan.erase(global_it);
93  }
94  }
95 
97  const tf2_ros::Buffer& tf,
98  const std::vector<geometry_msgs::PoseStamped>& global_plan,
99  const geometry_msgs::PoseStamped& global_pose,
100  const costmap_2d::Costmap2D& costmap,
101  const std::string& global_frame,
102  std::vector<geometry_msgs::PoseStamped>& transformed_plan){
103  transformed_plan.clear();
104 
105  if (global_plan.empty()) {
106  ROS_ERROR("Received plan with zero length");
107  return false;
108  }
109 
110  const geometry_msgs::PoseStamped& plan_pose = global_plan[0];
111  try {
112  // get plan_to_global_transform from plan frame to global_frame
113  geometry_msgs::TransformStamped plan_to_global_transform = tf.lookupTransform(global_frame, ros::Time(),
114  plan_pose.header.frame_id, plan_pose.header.stamp, plan_pose.header.frame_id, ros::Duration(0.5));
115 
116  //let's get the pose of the robot in the frame of the plan
117  geometry_msgs::PoseStamped robot_pose;
118  tf.transform(global_pose, robot_pose, plan_pose.header.frame_id);
119 
120  //we'll discard points on the plan that are outside the local costmap
121  double dist_threshold = std::max(costmap.getSizeInCellsX() * costmap.getResolution() / 2.0,
122  costmap.getSizeInCellsY() * costmap.getResolution() / 2.0);
123 
124  unsigned int i = 0;
125  double sq_dist_threshold = dist_threshold * dist_threshold;
126  double sq_dist = 0;
127 
128  //we need to loop to a point on the plan that is within a certain distance of the robot
129  while(i < (unsigned int)global_plan.size()) {
130  double x_diff = robot_pose.pose.position.x - global_plan[i].pose.position.x;
131  double y_diff = robot_pose.pose.position.y - global_plan[i].pose.position.y;
132  sq_dist = x_diff * x_diff + y_diff * y_diff;
133  if (sq_dist <= sq_dist_threshold) {
134  break;
135  }
136  ++i;
137  }
138 
139  geometry_msgs::PoseStamped newer_pose;
140 
141  //now we'll transform until points are outside of our distance threshold
142  while(i < (unsigned int)global_plan.size() && sq_dist <= sq_dist_threshold) {
143  const geometry_msgs::PoseStamped& pose = global_plan[i];
144  tf2::doTransform(pose, newer_pose, plan_to_global_transform);
145 
146  transformed_plan.push_back(newer_pose);
147 
148  double x_diff = robot_pose.pose.position.x - global_plan[i].pose.position.x;
149  double y_diff = robot_pose.pose.position.y - global_plan[i].pose.position.y;
150  sq_dist = x_diff * x_diff + y_diff * y_diff;
151 
152  ++i;
153  }
154  }
155  catch(tf2::LookupException& ex) {
156  ROS_ERROR("No Transform available Error: %s\n", ex.what());
157  return false;
158  }
159  catch(tf2::ConnectivityException& ex) {
160  ROS_ERROR("Connectivity Error: %s\n", ex.what());
161  return false;
162  }
163  catch(tf2::ExtrapolationException& ex) {
164  ROS_ERROR("Extrapolation Error: %s\n", ex.what());
165  if (!global_plan.empty())
166  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());
167 
168  return false;
169  }
170 
171  return true;
172  }
173 
175  const std::vector<geometry_msgs::PoseStamped>& global_plan,
176  const std::string& global_frame, geometry_msgs::PoseStamped &goal_pose) {
177  if (global_plan.empty())
178  {
179  ROS_ERROR("Received plan with zero length");
180  return false;
181  }
182 
183  const geometry_msgs::PoseStamped& plan_goal_pose = global_plan.back();
184  try{
185  geometry_msgs::TransformStamped transform = tf.lookupTransform(global_frame, ros::Time(),
186  plan_goal_pose.header.frame_id, plan_goal_pose.header.stamp,
187  plan_goal_pose.header.frame_id, ros::Duration(0.5));
188 
189  tf2::doTransform(plan_goal_pose, goal_pose, transform);
190  }
191  catch(tf2::LookupException& ex) {
192  ROS_ERROR("No Transform available Error: %s\n", ex.what());
193  return false;
194  }
195  catch(tf2::ConnectivityException& ex) {
196  ROS_ERROR("Connectivity Error: %s\n", ex.what());
197  return false;
198  }
199  catch(tf2::ExtrapolationException& ex) {
200  ROS_ERROR("Extrapolation Error: %s\n", ex.what());
201  if (global_plan.size() > 0)
202  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());
203 
204  return false;
205  }
206  return true;
207  }
208 
210  const std::vector<geometry_msgs::PoseStamped>& global_plan,
212  const std::string& global_frame,
213  geometry_msgs::PoseStamped& global_pose,
214  const nav_msgs::Odometry& base_odom,
215  double rot_stopped_vel, double trans_stopped_vel,
216  double xy_goal_tolerance, double yaw_goal_tolerance){
217 
218  //we assume the global goal is the last point in the global plan
219  geometry_msgs::PoseStamped goal_pose;
220  getGoalPose(tf, global_plan, global_frame, goal_pose);
221 
222  double goal_x = goal_pose.pose.position.x;
223  double goal_y = goal_pose.pose.position.y;
224  double goal_th = tf2::getYaw(goal_pose.pose.orientation);
225 
226  //check to see if we've reached the goal position
227  if(getGoalPositionDistance(global_pose, goal_x, goal_y) <= xy_goal_tolerance) {
228  //check to see if the goal orientation has been reached
229  if(fabs(getGoalOrientationAngleDifference(global_pose, goal_th)) <= yaw_goal_tolerance) {
230  //make sure that we're actually stopped before returning success
231  if(stopped(base_odom, rot_stopped_vel, trans_stopped_vel))
232  return true;
233  }
234  }
235 
236  return false;
237  }
238 
239  bool stopped(const nav_msgs::Odometry& base_odom,
240  const double& rot_stopped_velocity, const double& trans_stopped_velocity){
241  return fabs(base_odom.twist.twist.angular.z) <= rot_stopped_velocity
242  && fabs(base_odom.twist.twist.linear.x) <= trans_stopped_velocity
243  && fabs(base_odom.twist.twist.linear.y) <= trans_stopped_velocity;
244  }
245 };
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.
angles::shortest_angular_distance
static double shortest_angular_distance(double from, double to)
ros::Publisher
tf2::getYaw
double getYaw(const A &a)
utils.h
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:174
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:96
costmap_2d::Costmap2D
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
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ROS_DEBUG
#define ROS_DEBUG(...)
tf2::ExtrapolationException
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
tf2_ros::Buffer
tf2::LookupException
tf2::ConnectivityException
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
ros::Time
tf2::doTransform
void doTransform(const T &data_in, T &data_out, const geometry_msgs::TransformStamped &transform)
ROS_ERROR
#define ROS_ERROR(...)
tf2_geometry_msgs.h
costmap_2d::Costmap2D::getResolution
double getResolution() const
tf
costmap_2d::Costmap2D::getSizeInCellsX
unsigned int getSizeInCellsX() const
base_local_planner
Definition: costmap_model.h:44
ROS_ASSERT
#define ROS_ASSERT(cond)
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
ros::Duration
Matrix3x3.h
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:239


base_local_planner
Author(s): Eitan Marder-Eppstein, Eric Perko, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:24