$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 the Willow Garage 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 #ifndef TRAJECTORY_ROLLOUT_TRAJECTORY_PLANNER_H_ 00038 #define TRAJECTORY_ROLLOUT_TRAJECTORY_PLANNER_H_ 00039 00040 #include <vector> 00041 #include <string> 00042 #include <sstream> 00043 #include <math.h> 00044 #include <ros/console.h> 00045 #include <angles/angles.h> 00046 00047 //for creating a local cost grid 00048 #include <base_local_planner/map_cell.h> 00049 #include <base_local_planner/map_grid.h> 00050 00051 //for obstacle data access 00052 #include <costmap_2d/costmap_2d.h> 00053 #include <base_local_planner/world_model.h> 00054 00055 #include <base_local_planner/trajectory.h> 00056 00057 //we'll take in a path as a vector of poses 00058 #include <geometry_msgs/PoseStamped.h> 00059 #include <geometry_msgs/Point.h> 00060 #include <base_local_planner/Position2DInt.h> 00061 00062 //for computing path distance 00063 #include <queue> 00064 00065 //for some datatypes 00066 #include <tf/transform_datatypes.h> 00067 00068 #include <base_local_planner/BaseLocalPlannerConfig.h> 00069 #include <boost/algorithm/string.hpp> 00070 00071 namespace base_local_planner { 00076 class TrajectoryPlanner{ 00077 friend class TrajectoryPlannerTest; //Need this for gtest to work 00078 public: 00114 TrajectoryPlanner(WorldModel& world_model, 00115 const costmap_2d::Costmap2D& costmap, 00116 std::vector<geometry_msgs::Point> footprint_spec, 00117 double acc_lim_x = 1.0, double acc_lim_y = 1.0, double acc_lim_theta = 1.0, 00118 double sim_time = 1.0, double sim_granularity = 0.025, 00119 int vx_samples = 20, int vtheta_samples = 20, 00120 double pdist_scale = 0.6, double gdist_scale = 0.8, double occdist_scale = 0.2, 00121 double heading_lookahead = 0.325, double oscillation_reset_dist = 0.05, 00122 double escape_reset_dist = 0.10, double escape_reset_theta = M_PI_2, 00123 bool holonomic_robot = true, 00124 double max_vel_x = 0.5, double min_vel_x = 0.1, 00125 double max_vel_th = 1.0, double min_vel_th = -1.0, double min_in_place_vel_th = 0.4, 00126 double backup_vel = -0.1, 00127 bool dwa = false, bool heading_scoring = false, double heading_scoring_timestep = 0.1, 00128 bool simple_attractor = false, 00129 std::vector<double> y_vels = std::vector<double>(0), 00130 double stop_time_buffer = 0.2, 00131 double sim_period = 0.1, double angular_sim_granularity = 0.025); 00132 00136 ~TrajectoryPlanner(); 00137 00141 void reconfigure(BaseLocalPlannerConfig &cfg); 00142 00150 Trajectory findBestPath(tf::Stamped<tf::Pose> global_pose, tf::Stamped<tf::Pose> global_vel, 00151 tf::Stamped<tf::Pose>& drive_velocities); 00152 00158 void updatePlan(const std::vector<geometry_msgs::PoseStamped>& new_plan, bool compute_dists = false); 00159 00165 void getLocalGoal(double& x, double& y); 00166 00180 bool checkTrajectory(double x, double y, double theta, double vx, double vy, 00181 double vtheta, double vx_samp, double vy_samp, double vtheta_samp); 00182 00196 double scoreTrajectory(double x, double y, double theta, double vx, double vy, 00197 double vtheta, double vx_samp, double vy_samp, double vtheta_samp); 00198 00209 bool getCellCosts(int cx, int cy, float &path_cost, float &goal_cost, float &occ_cost, float &total_cost); 00210 private: 00224 Trajectory createTrajectories(double x, double y, double theta, double vx, double vy, double vtheta, 00225 double acc_x, double acc_y, double acc_theta); 00226 00244 void generateTrajectory(double x, double y, double theta, double vx, double vy, 00245 double vtheta, double vx_samp, double vy_samp, double vtheta_samp, double acc_x, double acc_y, 00246 double acc_theta, double impossible_cost, Trajectory& traj); 00247 00255 double footprintCost(double x_i, double y_i, double theta_i); 00256 00265 std::vector<base_local_planner::Position2DInt> getFootprintCells(double x_i, double y_i, double theta_i, bool fill); 00266 00275 void getLineCells(int x0, int x1, int y0, int y1, std::vector<base_local_planner::Position2DInt>& pts); 00276 00281 void getFillCells(std::vector<base_local_planner::Position2DInt>& footprint); 00282 00283 MapGrid map_; 00284 const costmap_2d::Costmap2D& costmap_; 00285 WorldModel& world_model_; 00286 00287 std::vector<geometry_msgs::Point> footprint_spec_; 00288 00289 std::vector<geometry_msgs::PoseStamped> global_plan_; 00290 00291 bool stuck_left, stuck_right; 00292 bool rotating_left, rotating_right; 00293 00294 bool stuck_left_strafe, stuck_right_strafe; 00295 bool strafe_right, strafe_left; 00296 00297 bool escaping_; 00298 00299 double goal_x_,goal_y_; 00300 00301 00302 double sim_time_; 00303 double sim_granularity_; 00304 double angular_sim_granularity_; 00305 00306 int vx_samples_; 00307 int vtheta_samples_; 00308 00309 double pdist_scale_, gdist_scale_, occdist_scale_; 00310 double acc_lim_x_, acc_lim_y_, acc_lim_theta_; 00311 00312 double prev_x_, prev_y_; 00313 double escape_x_, escape_y_, escape_theta_; 00314 00315 Trajectory traj_one, traj_two; 00316 00317 double heading_lookahead_; 00318 double oscillation_reset_dist_; 00319 double escape_reset_dist_, escape_reset_theta_; 00320 bool holonomic_robot_; 00321 00322 double max_vel_x_, min_vel_x_, max_vel_th_, min_vel_th_, min_in_place_vel_th_; 00323 00324 double backup_vel_; 00325 00326 bool dwa_; 00327 bool heading_scoring_; 00328 double heading_scoring_timestep_; 00329 bool simple_attractor_; 00330 00331 std::vector<double> y_vels_; 00332 00333 double stop_time_buffer_; 00334 double sim_period_; 00335 00336 boost::mutex configuration_mutex_; 00337 00347 inline double computeNewXPosition(double xi, double vx, double vy, double theta, double dt){ 00348 return xi + (vx * cos(theta) + vy * cos(M_PI_2 + theta)) * dt; 00349 } 00350 00360 inline double computeNewYPosition(double yi, double vx, double vy, double theta, double dt){ 00361 return yi + (vx * sin(theta) + vy * sin(M_PI_2 + theta)) * dt; 00362 } 00363 00371 inline double computeNewThetaPosition(double thetai, double vth, double dt){ 00372 return thetai + vth * dt; 00373 } 00374 00375 //compute velocity based on acceleration 00384 inline double computeNewVelocity(double vg, double vi, double a_max, double dt){ 00385 if((vg - vi) >= 0) 00386 return std::min(vg, vi + a_max * dt); 00387 return std::max(vg, vi - a_max * dt); 00388 } 00389 00390 void getMaxSpeedToStopInTime(double time, double& vx, double& vy, double& vth){ 00391 vx = acc_lim_x_ * std::max(time, 0.0); 00392 vy = acc_lim_y_ * std::max(time, 0.0); 00393 vth = acc_lim_theta_ * std::max(time, 0.0); 00394 } 00395 00396 double lineCost(int x0, int x1, int y0, int y1); 00397 double pointCost(int x, int y); 00398 double headingDiff(int cell_x, int cell_y, double x, double y, double heading); 00399 }; 00400 }; 00401 00402 #endif