00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef TRAJECTORY_ROLLOUT_TRAJECTORY_PLANNER_H_
00038 #define TRAJECTORY_ROLLOUT_TRAJECTORY_PLANNER_H_
00039
00040 #include <vector>
00041 #include <math.h>
00042 #include <ros/console.h>
00043 #include <angles/angles.h>
00044
00045
00046 #include <base_local_planner/map_cell.h>
00047 #include <base_local_planner/map_grid.h>
00048
00049
00050 #include <costmap_2d/costmap_2d.h>
00051 #include <base_local_planner/world_model.h>
00052
00053 #include <base_local_planner/trajectory.h>
00054
00055
00056 #include <geometry_msgs/PoseStamped.h>
00057 #include <geometry_msgs/Point.h>
00058 #include <base_local_planner/Position2DInt.h>
00059
00060
00061 #include <queue>
00062
00063
00064 #include <tf/transform_datatypes.h>
00065
00066 namespace base_local_planner {
00071 class TrajectoryPlanner{
00072 friend class TrajectoryPlannerTest;
00073 public:
00109 TrajectoryPlanner(WorldModel& world_model,
00110 const costmap_2d::Costmap2D& costmap,
00111 std::vector<geometry_msgs::Point> footprint_spec,
00112 double inscribed_radius, double circumscribed_radius,
00113 double acc_lim_x = 1.0, double acc_lim_y = 1.0, double acc_lim_theta = 1.0,
00114 double sim_time = 1.0, double sim_granularity = 0.025,
00115 int vx_samples = 20, int vtheta_samples = 20,
00116 double pdist_scale = 0.6, double gdist_scale = 0.8, double occdist_scale = 0.2,
00117 double heading_lookahead = 0.325, double oscillation_reset_dist = 0.05,
00118 double escape_reset_dist = 0.10, double escape_reset_theta = M_PI_2,
00119 bool holonomic_robot = true,
00120 double max_vel_x = 0.5, double min_vel_x = 0.1,
00121 double max_vel_th = 1.0, double min_vel_th = -1.0, double min_in_place_vel_th = 0.4,
00122 double backup_vel = -0.1,
00123 bool dwa = false, bool heading_scoring = false, double heading_scoring_timestep = 0.1,
00124 bool simple_attractor = false,
00125 std::vector<double> y_vels = std::vector<double>(0),
00126 double stop_time_buffer = 0.2,
00127 double sim_period = 0.1, double angular_sim_granularity = 0.025);
00128
00132 ~TrajectoryPlanner();
00133
00141 Trajectory findBestPath(tf::Stamped<tf::Pose> global_pose, tf::Stamped<tf::Pose> global_vel,
00142 tf::Stamped<tf::Pose>& drive_velocities);
00143
00149 void updatePlan(const std::vector<geometry_msgs::PoseStamped>& new_plan, bool compute_dists = false);
00150
00156 void getLocalGoal(double& x, double& y);
00157
00171 bool checkTrajectory(double x, double y, double theta, double vx, double vy,
00172 double vtheta, double vx_samp, double vy_samp, double vtheta_samp);
00173
00187 double scoreTrajectory(double x, double y, double theta, double vx, double vy,
00188 double vtheta, double vx_samp, double vy_samp, double vtheta_samp);
00189
00200 bool getCellCosts(int cx, int cy, float &path_cost, float &goal_cost, float &occ_cost, float &total_cost);
00201 private:
00215 Trajectory createTrajectories(double x, double y, double theta, double vx, double vy, double vtheta,
00216 double acc_x, double acc_y, double acc_theta);
00217
00235 void generateTrajectory(double x, double y, double theta, double vx, double vy,
00236 double vtheta, double vx_samp, double vy_samp, double vtheta_samp, double acc_x, double acc_y,
00237 double acc_theta, double impossible_cost, Trajectory& traj);
00238
00246 double footprintCost(double x_i, double y_i, double theta_i);
00247
00256 std::vector<base_local_planner::Position2DInt> getFootprintCells(double x_i, double y_i, double theta_i, bool fill);
00257
00266 void getLineCells(int x0, int x1, int y0, int y1, std::vector<base_local_planner::Position2DInt>& pts);
00267
00272 void getFillCells(std::vector<base_local_planner::Position2DInt>& footprint);
00273
00274 MapGrid map_;
00275 const costmap_2d::Costmap2D& costmap_;
00276 WorldModel& world_model_;
00277
00278 std::vector<geometry_msgs::Point> footprint_spec_;
00279
00280 double inscribed_radius_, circumscribed_radius_;
00281
00282 std::vector<geometry_msgs::PoseStamped> global_plan_;
00283
00284 bool stuck_left, stuck_right;
00285 bool rotating_left, rotating_right;
00286
00287 bool stuck_left_strafe, stuck_right_strafe;
00288 bool strafe_right, strafe_left;
00289
00290 bool escaping_;
00291
00292 double goal_x_,goal_y_;
00293
00294
00295 double sim_time_;
00296 double sim_granularity_;
00297 double angular_sim_granularity_;
00298
00299 int vx_samples_;
00300 int vtheta_samples_;
00301
00302 double pdist_scale_, gdist_scale_, occdist_scale_;
00303 double acc_lim_x_, acc_lim_y_, acc_lim_theta_;
00304
00305 double prev_x_, prev_y_;
00306 double escape_x_, escape_y_, escape_theta_;
00307
00308 Trajectory traj_one, traj_two;
00309
00310 double heading_lookahead_;
00311 double oscillation_reset_dist_;
00312 double escape_reset_dist_, escape_reset_theta_;
00313 bool holonomic_robot_;
00314
00315 double max_vel_x_, min_vel_x_, max_vel_th_, min_vel_th_, min_in_place_vel_th_;
00316
00317 double backup_vel_;
00318
00319 bool dwa_;
00320 bool heading_scoring_;
00321 double heading_scoring_timestep_;
00322 bool simple_attractor_;
00323
00324 std::vector<double> y_vels_;
00325
00326 double stop_time_buffer_;
00327 double sim_period_;
00328
00329
00339 inline double computeNewXPosition(double xi, double vx, double vy, double theta, double dt){
00340 return xi + (vx * cos(theta) + vy * cos(M_PI_2 + theta)) * dt;
00341 }
00342
00352 inline double computeNewYPosition(double yi, double vx, double vy, double theta, double dt){
00353 return yi + (vx * sin(theta) + vy * sin(M_PI_2 + theta)) * dt;
00354 }
00355
00363 inline double computeNewThetaPosition(double thetai, double vth, double dt){
00364 return thetai + vth * dt;
00365 }
00366
00367
00376 inline double computeNewVelocity(double vg, double vi, double a_max, double dt){
00377 if((vg - vi) >= 0)
00378 return std::min(vg, vi + a_max * dt);
00379 return std::max(vg, vi - a_max * dt);
00380 }
00381
00382 void getMaxSpeedToStopInTime(double time, double& vx, double& vy, double& vth){
00383 vx = acc_lim_x_ * std::max(time, 0.0);
00384 vy = acc_lim_y_ * std::max(time, 0.0);
00385 vth = acc_lim_theta_ * std::max(time, 0.0);
00386 }
00387
00388 double lineCost(int x0, int x1, int y0, int y1);
00389 double pointCost(int x, int y);
00390 double headingDiff(int cell_x, int cell_y, double x, double y, double heading);
00391 };
00392 };
00393
00394 #endif