$search
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_DECLARE_CLASS(carrot_planner, CarrotPlanner, 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 ros::NodeHandle private_nh("~/" + name); 00057 private_nh.param("step_size", step_size_, costmap_ros_->getResolution()); 00058 private_nh.param("min_dist_from_robot", min_dist_from_robot_, 0.10); 00059 costmap_ros_->getCostmapCopy(costmap_); 00060 world_model_ = new base_local_planner::CostmapModel(costmap_); 00061 //we'll get the parameters for the robot radius from the costmap we're associated with 00062 inscribed_radius_ = costmap_ros_->getInscribedRadius(); 00063 circumscribed_radius_ = costmap_ros_->getCircumscribedRadius(); 00064 footprint_spec_ = costmap_ros_->getRobotFootprint(); 00065 00066 initialized_ = true; 00067 } 00068 else 00069 ROS_WARN("This planner has already been initialized... doing nothing"); 00070 } 00071 00072 00073 00074 00075 00076 //we need to take the footprint of the robot into account when we calculate cost to obstacles 00077 double CarrotPlanner::footprintCost(double x_i, double y_i, double theta_i){ 00078 if(!initialized_){ 00079 ROS_ERROR("The planner has not been initialized, please call initialize() to use the planner"); 00080 return -1.0; 00081 } 00082 //if we have no footprint... do nothing 00083 if(footprint_spec_.size() < 3) 00084 return -1.0; 00085 00086 //build the oriented footprint 00087 double cos_th = cos(theta_i); 00088 double sin_th = sin(theta_i); 00089 std::vector<geometry_msgs::Point> oriented_footprint; 00090 for(unsigned int i = 0; i < footprint_spec_.size(); ++i){ 00091 geometry_msgs::Point new_pt; 00092 new_pt.x = x_i + (footprint_spec_[i].x * cos_th - footprint_spec_[i].y * sin_th); 00093 new_pt.y = y_i + (footprint_spec_[i].x * sin_th + footprint_spec_[i].y * cos_th); 00094 oriented_footprint.push_back(new_pt); 00095 } 00096 00097 geometry_msgs::Point robot_position; 00098 robot_position.x = x_i; 00099 robot_position.y = y_i; 00100 00101 //check if the footprint is legal 00102 double footprint_cost = world_model_->footprintCost(robot_position, oriented_footprint, inscribed_radius_, circumscribed_radius_); 00103 return footprint_cost; 00104 } 00105 00106 00107 bool CarrotPlanner::makePlan(const geometry_msgs::PoseStamped& start, 00108 const geometry_msgs::PoseStamped& goal, std::vector<geometry_msgs::PoseStamped>& plan){ 00109 00110 if(!initialized_){ 00111 ROS_ERROR("The planner has not been initialized, please call initialize() to use the planner"); 00112 return false; 00113 } 00114 00115 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); 00116 00117 plan.clear(); 00118 costmap_ros_->getCostmapCopy(costmap_); 00119 00120 if(goal.header.frame_id != costmap_ros_->getGlobalFrameID()){ 00121 ROS_ERROR("This planner as configured will only accept goals in the %s frame, but a goal was sent in the %s frame.", 00122 costmap_ros_->getGlobalFrameID().c_str(), goal.header.frame_id.c_str()); 00123 return false; 00124 } 00125 00126 tf::Stamped<tf::Pose> goal_tf; 00127 tf::Stamped<tf::Pose> start_tf; 00128 00129 poseStampedMsgToTF(goal,goal_tf); 00130 poseStampedMsgToTF(start,start_tf); 00131 00132 double useless_pitch, useless_roll, goal_yaw, start_yaw; 00133 start_tf.getBasis().getEulerYPR(start_yaw, useless_pitch, useless_roll); 00134 goal_tf.getBasis().getEulerYPR(goal_yaw, useless_pitch, useless_roll); 00135 00136 //we want to step back along the vector created by the robot's position and the goal pose until we find a legal cell 00137 double goal_x = goal.pose.position.x; 00138 double goal_y = goal.pose.position.y; 00139 double start_x = start.pose.position.x; 00140 double start_y = start.pose.position.y; 00141 00142 double diff_x = goal_x - start_x; 00143 double diff_y = goal_y - start_y; 00144 double diff_yaw = angles::normalize_angle(goal_yaw-start_yaw); 00145 00146 double target_x = goal_x; 00147 double target_y = goal_y; 00148 double target_yaw = goal_yaw; 00149 00150 bool done = false; 00151 double scale = 1.0; 00152 double dScale = 0.01; 00153 00154 while(!done) 00155 { 00156 if(scale < 0) 00157 { 00158 target_x = start_x; 00159 target_y = start_y; 00160 target_yaw = start_yaw; 00161 ROS_WARN("The carrot planner could not find a valid plan for this goal"); 00162 break; 00163 } 00164 target_x = start_x + scale * diff_x; 00165 target_y = start_y + scale * diff_y; 00166 target_yaw = angles::normalize_angle(start_yaw + scale * diff_yaw); 00167 00168 double footprint_cost = footprintCost(target_x, target_y, target_yaw); 00169 if(footprint_cost >= 0) 00170 { 00171 done = true; 00172 } 00173 scale -=dScale; 00174 } 00175 00176 plan.push_back(start); 00177 geometry_msgs::PoseStamped new_goal = goal; 00178 tf::Quaternion goal_quat = tf::createQuaternionFromYaw(target_yaw); 00179 00180 new_goal.pose.position.x = target_x; 00181 new_goal.pose.position.y = target_y; 00182 00183 new_goal.pose.orientation.x = goal_quat.x(); 00184 new_goal.pose.orientation.y = goal_quat.y(); 00185 new_goal.pose.orientation.z = goal_quat.z(); 00186 new_goal.pose.orientation.w = goal_quat.w(); 00187 00188 plan.push_back(new_goal); 00189 return (done); 00190 } 00191 00192 };