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 <goal_functions.h>
00038 
00039 namespace iri_ackermann_local_planner {
00040   double distance(double x1, double y1, double x2, double y2){
00041     return sqrt((x2 - x1) * (x2 - x1) + (y2 - y1) * (y2 - y1));
00042   }
00043 
00044   bool goalPositionReached(const tf::Stamped<tf::Pose>& global_pose, double goal_x, double goal_y, double xy_goal_tolerance){
00045     double dist = distance(global_pose.getOrigin().x(), global_pose.getOrigin().y(), goal_x, goal_y);
00046     return fabs(dist) <= xy_goal_tolerance;
00047   }
00048 
00049   bool goalOrientationReached(const tf::Stamped<tf::Pose>& global_pose, double goal_th, double yaw_goal_tolerance){
00050     double yaw = tf::getYaw(global_pose.getRotation());
00051     return fabs(angles::shortest_angular_distance(yaw, goal_th)) <= yaw_goal_tolerance;
00052   }
00053 
00054   void publishPlan(const std::vector<geometry_msgs::PoseStamped>& path, const ros::Publisher& pub, double r, double g, double b, double a){
00055     //given an empty path we won't do anything
00056     if(path.empty())
00057       return;
00058 
00059     //create a path message
00060     nav_msgs::Path gui_path;
00061     gui_path.poses.resize(path.size());
00062     gui_path.header.frame_id = path[0].header.frame_id;
00063     gui_path.header.stamp = path[0].header.stamp;
00064 
00065     // Extract the plan in world co-ordinates, we assume the path is all in the same frame
00066     for(unsigned int i=0; i < path.size(); i++){
00067       gui_path.poses[i] = path[i];
00068     }
00069 
00070     pub.publish(gui_path);
00071   }
00072 
00073   void prunePlan(const tf::Stamped<tf::Pose>& global_pose, std::vector<geometry_msgs::PoseStamped>& plan, std::vector<geometry_msgs::PoseStamped>& global_plan){
00074     ROS_ASSERT(global_plan.size() >= plan.size());
00075     std::vector<geometry_msgs::PoseStamped>::iterator it = plan.begin();
00076     std::vector<geometry_msgs::PoseStamped>::iterator global_it = global_plan.begin();
00077     while(it != plan.end()){
00078       const geometry_msgs::PoseStamped& w = *it;
00079       // Fixed error bound of 2 meters for now. Can reduce to a portion of the map size or based on the resolution
00080       double x_diff = global_pose.getOrigin().x() - w.pose.position.x;
00081       double y_diff = global_pose.getOrigin().y() - w.pose.position.y;
00082       double distance_sq = x_diff * x_diff + y_diff * y_diff;
00083       if(distance_sq < 1){
00084         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);
00085         break;
00086       }
00087       it = plan.erase(it);
00088       global_it = global_plan.erase(global_it);
00089     }
00090   }
00091 
00092   bool transformGlobalPlan(const tf::TransformListener& tf, const std::vector<geometry_msgs::PoseStamped>& global_plan, 
00093       const costmap_2d::Costmap2DROS& costmap, const std::string& global_frame, 
00094       std::vector<geometry_msgs::PoseStamped>& transformed_plan){
00095     const geometry_msgs::PoseStamped& plan_pose = global_plan[0];
00096 
00097     transformed_plan.clear();
00098 
00099     try{
00100       if (!global_plan.size() > 0)
00101       {
00102         ROS_ERROR("Recieved plan with zero length");
00103         return false;
00104       }
00105 
00106       tf::StampedTransform transform;
00107       tf.lookupTransform(global_frame, ros::Time(), 
00108           plan_pose.header.frame_id, plan_pose.header.stamp, 
00109           plan_pose.header.frame_id, transform);
00110 
00111       //let's get the pose of the robot in the frame of the plan
00112       tf::Stamped<tf::Pose> robot_pose;
00113       robot_pose.setIdentity();
00114       robot_pose.frame_id_ = costmap.getBaseFrameID();
00115       robot_pose.stamp_ = ros::Time();
00116       tf.transformPose(plan_pose.header.frame_id, robot_pose, robot_pose);
00117 
00118       //we'll keep points on the plan that are within the window that we're looking at
00119       double dist_threshold = std::max(costmap.getSizeInCellsX() * costmap.getResolution() / 2.0, costmap.getSizeInCellsY() * costmap.getResolution() / 2.0);
00120 
00121       unsigned int i = 0;
00122       double sq_dist_threshold = dist_threshold * dist_threshold;
00123       double sq_dist = DBL_MAX;
00124 
00125       //we need to loop to a point on the plan that is within a certain distance of the robot
00126       while(i < (unsigned int)global_plan.size() && sq_dist > sq_dist_threshold){
00127         double x_diff = robot_pose.getOrigin().x() - global_plan[i].pose.position.x;
00128         double y_diff = robot_pose.getOrigin().y() - global_plan[i].pose.position.y;
00129         sq_dist = x_diff * x_diff + y_diff * y_diff;
00130         ++i;
00131       }
00132 
00133       //make sure not to count the first point that is too far away
00134       if(i > 0)
00135         --i;
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         double x_diff = robot_pose.getOrigin().x() - global_plan[i].pose.position.x;
00143         double y_diff = robot_pose.getOrigin().y() - global_plan[i].pose.position.y;
00144         sq_dist = x_diff * x_diff + y_diff * y_diff;
00145 
00146         const geometry_msgs::PoseStamped& pose = global_plan[i];
00147         poseStampedMsgToTF(pose, tf_pose);
00148         tf_pose.setData(transform * tf_pose);
00149         tf_pose.stamp_ = transform.stamp_;
00150         tf_pose.frame_id_ = global_frame;
00151         poseStampedTFToMsg(tf_pose, newer_pose);
00152 
00153         transformed_plan.push_back(newer_pose);
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 isGoalReached(const tf::TransformListener& tf, const std::vector<geometry_msgs::PoseStamped>& global_plan, 
00178       const costmap_2d::Costmap2DROS& costmap_ros, const std::string& global_frame, 
00179       const nav_msgs::Odometry& base_odom, double rot_stopped_vel, double trans_stopped_vel,
00180       double xy_goal_tolerance, double yaw_goal_tolerance){
00181     const geometry_msgs::PoseStamped& plan_goal_pose = global_plan.back();
00182     tf::Stamped<tf::Pose> goal_pose;
00183 
00184     try{
00185       if (!global_plan.size() > 0)
00186       {
00187         ROS_ERROR("Recieved plan with zero length");
00188         return false;
00189       }
00190 
00191       tf::StampedTransform transform;
00192       tf.lookupTransform(global_frame, ros::Time(), 
00193           plan_goal_pose.header.frame_id, plan_goal_pose.header.stamp, 
00194           plan_goal_pose.header.frame_id, transform);
00195 
00196       poseStampedMsgToTF(plan_goal_pose, goal_pose);
00197       goal_pose.setData(transform * goal_pose);
00198       goal_pose.stamp_ = transform.stamp_;
00199       goal_pose.frame_id_ = global_frame;
00200 
00201     }
00202     catch(tf::LookupException& ex) {
00203       ROS_ERROR("No Transform available Error: %s\n", ex.what());
00204       return false;
00205     }
00206     catch(tf::ConnectivityException& ex) {
00207       ROS_ERROR("Connectivity Error: %s\n", ex.what());
00208       return false;
00209     }
00210     catch(tf::ExtrapolationException& ex) {
00211       ROS_ERROR("Extrapolation Error: %s\n", ex.what());
00212       if (global_plan.size() > 0)
00213         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());
00214 
00215       return false;
00216     }
00217 
00218     //we assume the global goal is the last point in the global plan
00219     double goal_x = goal_pose.getOrigin().getX();
00220     double goal_y = goal_pose.getOrigin().getY();
00221 
00222     double yaw = tf::getYaw(goal_pose.getRotation());
00223 
00224     double goal_th = yaw;
00225 
00226     tf::Stamped<tf::Pose> global_pose;
00227     if(!costmap_ros.getRobotPose(global_pose))
00228       return false;
00229 
00230     //check to see if we've reached the goal position
00231     if(goalPositionReached(global_pose, goal_x, goal_y, xy_goal_tolerance)){
00232       //check to see if the goal orientation has been reached
00233       if(goalOrientationReached(global_pose, goal_th, yaw_goal_tolerance)){
00234         //make sure that we're actually stopped before returning success
00235         if(stopped(base_odom, rot_stopped_vel, trans_stopped_vel))
00236           return true;
00237       }
00238     }
00239 
00240     return false;
00241   }
00242 
00243   bool stopped(const nav_msgs::Odometry& base_odom, 
00244       const double& rot_stopped_velocity, const double& trans_stopped_velocity){
00245     return fabs(base_odom.twist.twist.angular.z) <= rot_stopped_velocity 
00246       && fabs(base_odom.twist.twist.linear.x) <= trans_stopped_velocity
00247       && fabs(base_odom.twist.twist.linear.y) <= trans_stopped_velocity;
00248   }
00249 };


iri_ackermann_local_planner
Author(s): Sergi Hernandez Juan
autogenerated on Fri Dec 6 2013 23:50:17