carrot_planner.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 *
00003 * Software License Agreement (BSD License)
00004 *
00005 *  Copyright (c) 2008, 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 * Authors: Eitan Marder-Eppstein, Sachin Chitta
00036 *********************************************************************/
00037 #include <carrot_planner/carrot_planner.h>
00038 #include <pluginlib/class_list_macros.h>
00039 
00040 //register this planner as a BaseGlobalPlanner plugin
00041 PLUGINLIB_EXPORT_CLASS(carrot_planner::CarrotPlanner, nav_core::BaseGlobalPlanner)
00042 
00043 namespace carrot_planner {
00044 
00045   CarrotPlanner::CarrotPlanner()
00046   : costmap_ros_(NULL), initialized_(false){}
00047 
00048   CarrotPlanner::CarrotPlanner(std::string name, costmap_2d::Costmap2DROS* costmap_ros)
00049   : costmap_ros_(NULL), initialized_(false){
00050     initialize(name, costmap_ros);
00051   }
00052   
00053   void CarrotPlanner::initialize(std::string name, costmap_2d::Costmap2DROS* costmap_ros){
00054     if(!initialized_){
00055       costmap_ros_ = costmap_ros;
00056       costmap_ = costmap_ros_->getCostmap();
00057 
00058       ros::NodeHandle private_nh("~/" + name);
00059       private_nh.param("step_size", step_size_, costmap_->getResolution());
00060       private_nh.param("min_dist_from_robot", min_dist_from_robot_, 0.10);
00061       world_model_ = new base_local_planner::CostmapModel(*costmap_); 
00062 
00063       initialized_ = true;
00064     }
00065     else
00066       ROS_WARN("This planner has already been initialized... doing nothing");
00067   }
00068 
00069   //we need to take the footprint of the robot into account when we calculate cost to obstacles
00070   double CarrotPlanner::footprintCost(double x_i, double y_i, double theta_i){
00071     if(!initialized_){
00072       ROS_ERROR("The planner has not been initialized, please call initialize() to use the planner");
00073       return -1.0;
00074     }
00075 
00076     std::vector<geometry_msgs::Point> footprint = costmap_ros_->getRobotFootprint();
00077     //if we have no footprint... do nothing
00078     if(footprint.size() < 3)
00079       return -1.0;
00080 
00081     //check if the footprint is legal
00082     double footprint_cost = world_model_->footprintCost(x_i, y_i, theta_i, footprint);
00083     return footprint_cost;
00084   }
00085 
00086 
00087   bool CarrotPlanner::makePlan(const geometry_msgs::PoseStamped& start, 
00088       const geometry_msgs::PoseStamped& goal, std::vector<geometry_msgs::PoseStamped>& plan){
00089 
00090     if(!initialized_){
00091       ROS_ERROR("The planner has not been initialized, please call initialize() to use the planner");
00092       return false;
00093     }
00094 
00095     ROS_DEBUG("Got a start: %.2f, %.2f, and a goal: %.2f, %.2f", start.pose.position.x, start.pose.position.y, goal.pose.position.x, goal.pose.position.y);
00096 
00097     plan.clear();
00098     costmap_ = costmap_ros_->getCostmap();
00099 
00100     if(goal.header.frame_id != costmap_ros_->getGlobalFrameID()){
00101       ROS_ERROR("This planner as configured will only accept goals in the %s frame, but a goal was sent in the %s frame.", 
00102           costmap_ros_->getGlobalFrameID().c_str(), goal.header.frame_id.c_str());
00103       return false;
00104     }
00105 
00106     tf::Stamped<tf::Pose> goal_tf;
00107     tf::Stamped<tf::Pose> start_tf;
00108 
00109     poseStampedMsgToTF(goal,goal_tf);
00110     poseStampedMsgToTF(start,start_tf);
00111 
00112     double useless_pitch, useless_roll, goal_yaw, start_yaw;
00113     start_tf.getBasis().getEulerYPR(start_yaw, useless_pitch, useless_roll);
00114     goal_tf.getBasis().getEulerYPR(goal_yaw, useless_pitch, useless_roll);
00115 
00116     //we want to step back along the vector created by the robot's position and the goal pose until we find a legal cell
00117     double goal_x = goal.pose.position.x;
00118     double goal_y = goal.pose.position.y;
00119     double start_x = start.pose.position.x;
00120     double start_y = start.pose.position.y;
00121 
00122     double diff_x = goal_x - start_x;
00123     double diff_y = goal_y - start_y;
00124     double diff_yaw = angles::normalize_angle(goal_yaw-start_yaw);
00125 
00126     double target_x = goal_x;
00127     double target_y = goal_y;
00128     double target_yaw = goal_yaw;
00129 
00130     bool done = false;
00131     double scale = 1.0;
00132     double dScale = 0.01;
00133 
00134     while(!done)
00135     {
00136       if(scale < 0)
00137       {
00138         target_x = start_x;
00139         target_y = start_y;
00140         target_yaw = start_yaw;
00141         ROS_WARN("The carrot planner could not find a valid plan for this goal");
00142         break;
00143       }
00144       target_x = start_x + scale * diff_x;
00145       target_y = start_y + scale * diff_y;
00146       target_yaw = angles::normalize_angle(start_yaw + scale * diff_yaw);
00147       
00148       double footprint_cost = footprintCost(target_x, target_y, target_yaw);
00149       if(footprint_cost >= 0)
00150       {
00151           done = true;
00152       }
00153       scale -=dScale;
00154     }
00155 
00156     plan.push_back(start);
00157     geometry_msgs::PoseStamped new_goal = goal;
00158     tf::Quaternion goal_quat = tf::createQuaternionFromYaw(target_yaw);
00159 
00160     new_goal.pose.position.x = target_x;
00161     new_goal.pose.position.y = target_y;
00162 
00163     new_goal.pose.orientation.x = goal_quat.x();
00164     new_goal.pose.orientation.y = goal_quat.y();
00165     new_goal.pose.orientation.z = goal_quat.z();
00166     new_goal.pose.orientation.w = goal_quat.w();
00167 
00168     plan.push_back(new_goal);
00169     return (done);
00170   }
00171 
00172 };


carrot_planner
Author(s): Eitan Marder-Eppstein, Sachin Chitta, contradict@gmail.com
autogenerated on Wed Aug 2 2017 03:12:51