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 SAFE_TRAJECTORY_PLANNER_H_
00038 #define SAFE_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 <costmap_2d/cost_values.h>
00052 #include <base_local_planner/world_model.h>
00053
00054 #include <base_local_planner/trajectory.h>
00055
00056
00057 #include <geometry_msgs/PoseStamped.h>
00058 #include <geometry_msgs/Point.h>
00059 #include <base_local_planner/Position2DInt.h>
00060
00061
00062 #include <queue>
00063
00064
00065 #include <tf/transform_datatypes.h>
00066
00067 namespace safe_teleop {
00072 class SafeTrajectoryPlanner{
00073 friend class SafeTrajectoryPlannerTest;
00074 public:
00105 SafeTrajectoryPlanner(base_local_planner::WorldModel& world_model,
00106 const costmap_2d::Costmap2D& costmap,
00107 std::vector<geometry_msgs::Point> footprint_spec,
00108 double inscribed_radius, double circumscribed_radius,
00109 double acc_lim_x = 1.0, double acc_lim_y = 1.0, double acc_lim_theta = 1.0,
00110 double sim_time = 1.0, double sim_granularity = 0.025,
00111 int vx_samples = 10, int vy_samples = 10, int vtheta_samples = 10,
00112 double userdist_scale = 0.8, double occdist_scale = 0.2,
00113 double max_vel_x = 0.5, double min_vel_x = 0.1,
00114 double max_vel_y = 0.2, double min_vel_y = -0.2,
00115 double max_vel_th = 1.0, double min_vel_th = -1.0,
00116 bool holonomic_robot = true, bool dwa = false);
00117
00121 ~SafeTrajectoryPlanner();
00122
00130 base_local_planner::Trajectory findBestPath(tf::Stamped<tf::Pose> global_pose, tf::Stamped<tf::Pose> global_vel,
00131 tf::Stamped<tf::Pose> user_vel, tf::Stamped<tf::Pose>& drive_velocities);
00132
00140 base_local_planner::Trajectory findPath(tf::Stamped<tf::Pose> global_pose, tf::Stamped<tf::Pose> global_vel,
00141 tf::Stamped<tf::Pose> user_vel);
00142
00143 private:
00160 base_local_planner::Trajectory createTrajectories(double x, double y, double theta, double vx, double vy, double vtheta,
00161 double acc_x, double acc_y, double acc_theta, double dx, double dy, double dtheta);
00162
00183 void generateTrajectory(double x, double y, double theta, double vx, double vy,
00184 double vtheta, double vx_samp, double vy_samp, double vtheta_samp, double acc_x, double acc_y,
00185 double acc_theta, double impossible_cost, double dx, double dy, double dtheta,
00186 base_local_planner::Trajectory& traj);
00187
00195 double footprintCost(double x_i, double y_i, double theta_i);
00196
00205 std::vector<base_local_planner::Position2DInt> getFootprintCells(double x_i, double y_i, double theta_i, bool fill);
00206
00215 void getLineCells(int x0, int x1, int y0, int y1, std::vector<base_local_planner::Position2DInt>& pts);
00216
00221 void getFillCells(std::vector<base_local_planner::Position2DInt>& footprint);
00222
00223 base_local_planner::MapGrid map_;
00224 const costmap_2d::Costmap2D& costmap_;
00225 base_local_planner::WorldModel& world_model_;
00226
00227 std::vector<geometry_msgs::Point> footprint_spec_;
00228 double inscribed_radius_, circumscribed_radius_;
00229
00230 double sim_time_;
00231 double sim_granularity_;
00232
00233 int vx_samples_;
00234 int vy_samples_;
00235 int vtheta_samples_;
00236
00237 double userdist_scale_, occdist_scale_;
00238 double acc_lim_x_, acc_lim_y_, acc_lim_theta_;
00239
00240 base_local_planner::Trajectory traj_one, traj_two;
00241
00242 double max_vel_x_, min_vel_x_, max_vel_y_, min_vel_y_, max_vel_th_, min_vel_th_;
00243
00244 bool holonomic_robot_;
00245
00246 bool dwa_;
00247
00248
00258 inline double computeNewXPosition(double xi, double vx, double vy, double theta, double dt){
00259 return xi + (vx * cos(theta) + vy * cos(M_PI_2 + theta)) * dt;
00260 }
00261
00271 inline double computeNewYPosition(double yi, double vx, double vy, double theta, double dt){
00272 return yi + (vx * sin(theta) + vy * sin(M_PI_2 + theta)) * dt;
00273 }
00274
00282 inline double computeNewThetaPosition(double thetai, double vth, double dt){
00283 return thetai + vth * dt;
00284 }
00285
00286
00295 inline double computeNewVelocity(double vg, double vi, double a_max, double dt){
00296 if(vg >= 0)
00297 return std::min(vg, vi + a_max * dt);
00298 return std::max(vg, vi - a_max * dt);
00299 }
00300
00301 double lineCost(int x0, int x1, int y0, int y1);
00302 double pointCost(int x, int y);
00303
00304 };
00305 };
00306
00307 #endif