goal_functions.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 *
00003 * Software License Agreement (BSD License)
00004 *
00005 *  Copyright (c) 2009, Willow Garage, Inc.
00006 *  All rights reserved.
00007 *
00008 *  Redistribution and use in source and binary forms, with or without
00009 *  modification, are permitted provided that the following conditions
00010 *  are met:
00011 *
00012 *   * Redistributions of source code must retain the above copyright
00013 *     notice, this list of conditions and the following disclaimer.
00014 *   * Redistributions in binary form must reproduce the above
00015 *     copyright notice, this list of conditions and the following
00016 *     disclaimer in the documentation and/or other materials provided
00017 *     with the distribution.
00018 *   * Neither the name of Willow Garage, Inc. nor the names of its
00019 *     contributors may be used to endorse or promote products derived
00020 *     from this software without specific prior written permission.
00021 *
00022 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033 *  POSSIBILITY OF SUCH DAMAGE.
00034 *
00035 * Author: Eitan Marder-Eppstein
00036 *********************************************************************/
00037 #include <base_local_planner/goal_functions.h>
00038 
00039 namespace base_local_planner {
00040 
00041   double getGoalPositionDistance(const tf::Stamped<tf::Pose>& global_pose, double goal_x, double goal_y) {
00042     double dist =
00043         (goal_x - global_pose.getOrigin().x()) * (goal_x - global_pose.getOrigin().x()) +
00044         (goal_y - global_pose.getOrigin().y()) * (goal_y - global_pose.getOrigin().y());
00045     return sqrt(dist);
00046   }
00047 
00048   double getGoalOrientationAngleDifference(const tf::Stamped<tf::Pose>& global_pose, double goal_th) {
00049     double yaw = tf::getYaw(global_pose.getRotation());
00050     return angles::shortest_angular_distance(yaw, goal_th);
00051   }
00052 
00053   void publishPlan(const std::vector<geometry_msgs::PoseStamped>& path, const ros::Publisher& pub) {
00054     //given an empty path we won't do anything
00055     if(path.empty())
00056       return;
00057 
00058     //create a path message
00059     nav_msgs::Path gui_path;
00060     gui_path.poses.resize(path.size());
00061     gui_path.header.frame_id = path[0].header.frame_id;
00062     gui_path.header.stamp = path[0].header.stamp;
00063 
00064     // Extract the plan in world co-ordinates, we assume the path is all in the same frame
00065     for(unsigned int i=0; i < path.size(); i++){
00066       gui_path.poses[i] = path[i];
00067     }
00068 
00069     pub.publish(gui_path);
00070   }
00071 
00072   void prunePlan(const tf::Stamped<tf::Pose>& global_pose, std::vector<geometry_msgs::PoseStamped>& plan, std::vector<geometry_msgs::PoseStamped>& global_plan){
00073     ROS_ASSERT(global_plan.size() >= plan.size());
00074     std::vector<geometry_msgs::PoseStamped>::iterator it = plan.begin();
00075     std::vector<geometry_msgs::PoseStamped>::iterator global_it = global_plan.begin();
00076     while(it != plan.end()){
00077       const geometry_msgs::PoseStamped& w = *it;
00078       // Fixed error bound of 2 meters for now. Can reduce to a portion of the map size or based on the resolution
00079       double x_diff = global_pose.getOrigin().x() - w.pose.position.x;
00080       double y_diff = global_pose.getOrigin().y() - w.pose.position.y;
00081       double distance_sq = x_diff * x_diff + y_diff * y_diff;
00082       if(distance_sq < 1){
00083         ROS_DEBUG("Nearest waypoint to <%f, %f> is <%f, %f>\n", global_pose.getOrigin().x(), global_pose.getOrigin().y(), w.pose.position.x, w.pose.position.y);
00084         break;
00085       }
00086       it = plan.erase(it);
00087       global_it = global_plan.erase(global_it);
00088     }
00089   }
00090 
00091   bool transformGlobalPlan(
00092       const tf::TransformListener& tf,
00093       const std::vector<geometry_msgs::PoseStamped>& global_plan,
00094       const tf::Stamped<tf::Pose>& global_pose,
00095       const costmap_2d::Costmap2D& costmap,
00096       const std::string& global_frame,
00097       std::vector<geometry_msgs::PoseStamped>& transformed_plan){
00098     const geometry_msgs::PoseStamped& plan_pose = global_plan[0];
00099 
00100     transformed_plan.clear();
00101 
00102     try {
00103       if (!global_plan.size() > 0) {
00104         ROS_ERROR("Received plan with zero length");
00105         return false;
00106       }
00107 
00108       // get plan_to_global_transform from plan frame to global_frame
00109       tf::StampedTransform plan_to_global_transform;
00110       tf.lookupTransform(global_frame, ros::Time(), 
00111           plan_pose.header.frame_id, plan_pose.header.stamp, 
00112           plan_pose.header.frame_id, plan_to_global_transform);
00113 
00114       //let's get the pose of the robot in the frame of the plan
00115       tf::Stamped<tf::Pose> robot_pose;
00116       tf.transformPose(plan_pose.header.frame_id, global_pose, robot_pose);
00117 
00118       //we'll discard points on the plan that are outside the local costmap
00119       double dist_threshold = std::max(costmap.getSizeInCellsX() * costmap.getResolution() / 2.0,
00120                                        costmap.getSizeInCellsY() * costmap.getResolution() / 2.0);
00121 
00122       unsigned int i = 0;
00123       double sq_dist_threshold = dist_threshold * dist_threshold;
00124       double sq_dist = 0;
00125 
00126       //we need to loop to a point on the plan that is within a certain distance of the robot
00127       while(i < (unsigned int)global_plan.size()) {
00128         double x_diff = robot_pose.getOrigin().x() - global_plan[i].pose.position.x;
00129         double y_diff = robot_pose.getOrigin().y() - global_plan[i].pose.position.y;
00130         sq_dist = x_diff * x_diff + y_diff * y_diff;
00131         if (sq_dist <= sq_dist_threshold) {
00132           break;
00133         }
00134         ++i;
00135       }
00136 
00137       tf::Stamped<tf::Pose> tf_pose;
00138       geometry_msgs::PoseStamped newer_pose;
00139 
00140       //now we'll transform until points are outside of our distance threshold
00141       while(i < (unsigned int)global_plan.size() && sq_dist <= sq_dist_threshold) {
00142         const geometry_msgs::PoseStamped& pose = global_plan[i];
00143         poseStampedMsgToTF(pose, tf_pose);
00144         tf_pose.setData(plan_to_global_transform * tf_pose);
00145         tf_pose.stamp_ = plan_to_global_transform.stamp_;
00146         tf_pose.frame_id_ = global_frame;
00147         poseStampedTFToMsg(tf_pose, newer_pose);
00148 
00149         transformed_plan.push_back(newer_pose);
00150 
00151         double x_diff = robot_pose.getOrigin().x() - global_plan[i].pose.position.x;
00152         double y_diff = robot_pose.getOrigin().y() - global_plan[i].pose.position.y;
00153         sq_dist = x_diff * x_diff + y_diff * y_diff;
00154 
00155         ++i;
00156       }
00157     }
00158     catch(tf::LookupException& ex) {
00159       ROS_ERROR("No Transform available Error: %s\n", ex.what());
00160       return false;
00161     }
00162     catch(tf::ConnectivityException& ex) {
00163       ROS_ERROR("Connectivity Error: %s\n", ex.what());
00164       return false;
00165     }
00166     catch(tf::ExtrapolationException& ex) {
00167       ROS_ERROR("Extrapolation Error: %s\n", ex.what());
00168       if (global_plan.size() > 0)
00169         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());
00170 
00171       return false;
00172     }
00173 
00174     return true;
00175   }
00176 
00177   bool getGoalPose(const tf::TransformListener& tf,
00178       const std::vector<geometry_msgs::PoseStamped>& global_plan,
00179       const std::string& global_frame, tf::Stamped<tf::Pose> &goal_pose) {
00180     const geometry_msgs::PoseStamped& plan_goal_pose = global_plan.back();
00181     try{
00182       if (!global_plan.size() > 0)
00183       {
00184         ROS_ERROR("Recieved plan with zero length");
00185         return false;
00186       }
00187 
00188       tf::StampedTransform transform;
00189       tf.lookupTransform(global_frame, ros::Time(),
00190           plan_goal_pose.header.frame_id, plan_goal_pose.header.stamp,
00191           plan_goal_pose.header.frame_id, transform);
00192 
00193       poseStampedMsgToTF(plan_goal_pose, goal_pose);
00194       goal_pose.setData(transform * goal_pose);
00195       goal_pose.stamp_ = transform.stamp_;
00196       goal_pose.frame_id_ = global_frame;
00197 
00198     }
00199     catch(tf::LookupException& ex) {
00200       ROS_ERROR("No Transform available Error: %s\n", ex.what());
00201       return false;
00202     }
00203     catch(tf::ConnectivityException& ex) {
00204       ROS_ERROR("Connectivity Error: %s\n", ex.what());
00205       return false;
00206     }
00207     catch(tf::ExtrapolationException& ex) {
00208       ROS_ERROR("Extrapolation Error: %s\n", ex.what());
00209       if (global_plan.size() > 0)
00210         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());
00211 
00212       return false;
00213     }
00214     return true;
00215   }
00216 
00217   bool isGoalReached(const tf::TransformListener& tf,
00218       const std::vector<geometry_msgs::PoseStamped>& global_plan,
00219       const costmap_2d::Costmap2D& costmap,
00220       const std::string& global_frame,
00221       tf::Stamped<tf::Pose>& global_pose,
00222       const nav_msgs::Odometry& base_odom,
00223       double rot_stopped_vel, double trans_stopped_vel,
00224       double xy_goal_tolerance, double yaw_goal_tolerance){
00225 
00226         //we assume the global goal is the last point in the global plan
00227     tf::Stamped<tf::Pose> goal_pose;
00228     getGoalPose(tf, global_plan, global_frame, goal_pose);
00229 
00230     double goal_x = goal_pose.getOrigin().getX();
00231     double goal_y = goal_pose.getOrigin().getY();
00232     double goal_th = tf::getYaw(goal_pose.getRotation());
00233 
00234     //check to see if we've reached the goal position
00235     if(getGoalPositionDistance(global_pose, goal_x, goal_y) <= xy_goal_tolerance) {
00236       //check to see if the goal orientation has been reached
00237       if(fabs(getGoalOrientationAngleDifference(global_pose, goal_th)) <= yaw_goal_tolerance) {
00238         //make sure that we're actually stopped before returning success
00239         if(stopped(base_odom, rot_stopped_vel, trans_stopped_vel))
00240           return true;
00241       }
00242     }
00243 
00244     return false;
00245   }
00246 
00247   bool stopped(const nav_msgs::Odometry& base_odom, 
00248       const double& rot_stopped_velocity, const double& trans_stopped_velocity){
00249     return fabs(base_odom.twist.twist.angular.z) <= rot_stopped_velocity 
00250       && fabs(base_odom.twist.twist.linear.x) <= trans_stopped_velocity
00251       && fabs(base_odom.twist.twist.linear.y) <= trans_stopped_velocity;
00252   }
00253 };


base_local_planner
Author(s): Eitan Marder-Eppstein, Eric Perko
autogenerated on Mon Oct 6 2014 02:45:34