$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 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 //for creating a local cost grid 00046 #include <base_local_planner/map_cell.h> 00047 #include <base_local_planner/map_grid.h> 00048 00049 //for obstacle data access 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 //we'll take in a path as a vector of poses 00056 #include <geometry_msgs/PoseStamped.h> 00057 #include <geometry_msgs/Point.h> 00058 #include <base_local_planner/Position2DInt.h> 00059 00060 //for computing path distance 00061 #include <queue> 00062 00063 //for some datatypes 00064 #include <tf/transform_datatypes.h> 00065 00066 namespace safe_teleop { 00071 class SafeTrajectoryPlanner{ 00072 friend class SafeTrajectoryPlannerTest; //Need this for gtest to work 00073 public: 00104 SafeTrajectoryPlanner(base_local_planner::WorldModel& world_model, 00105 const costmap_2d::Costmap2D& costmap, 00106 std::vector<geometry_msgs::Point> footprint_spec, 00107 double inscribed_radius, double circumscribed_radius, 00108 double acc_lim_x = 1.0, double acc_lim_y = 1.0, double acc_lim_theta = 1.0, 00109 double sim_time = 1.0, double sim_granularity = 0.025, 00110 int vx_samples = 10, int vy_samples = 10, int vtheta_samples = 10, 00111 double userdist_scale = 0.8, double occdist_scale = 0.2, 00112 double max_vel_x = 0.5, double min_vel_x = 0.1, 00113 double max_vel_y = 0.2, double min_vel_y = -0.2, 00114 double max_vel_th = 1.0, double min_vel_th = -1.0, 00115 bool holonomic_robot = true, bool dwa = false); 00116 00120 ~SafeTrajectoryPlanner(); 00121 00129 base_local_planner::Trajectory findBestPath(tf::Stamped<tf::Pose> global_pose, tf::Stamped<tf::Pose> global_vel, 00130 tf::Stamped<tf::Pose> user_vel, tf::Stamped<tf::Pose>& drive_velocities); 00131 00139 base_local_planner::Trajectory findPath(tf::Stamped<tf::Pose> global_pose, tf::Stamped<tf::Pose> global_vel, 00140 tf::Stamped<tf::Pose> user_vel); 00141 00142 private: 00159 base_local_planner::Trajectory createTrajectories(double x, double y, double theta, double vx, double vy, double vtheta, 00160 double acc_x, double acc_y, double acc_theta, double dx, double dy, double dtheta); 00161 00182 void generateTrajectory(double x, double y, double theta, double vx, double vy, 00183 double vtheta, double vx_samp, double vy_samp, double vtheta_samp, double acc_x, double acc_y, 00184 double acc_theta, double impossible_cost, double dx, double dy, double dtheta, 00185 base_local_planner::Trajectory& traj); 00186 00194 double footprintCost(double x_i, double y_i, double theta_i); 00195 00204 std::vector<base_local_planner::Position2DInt> getFootprintCells(double x_i, double y_i, double theta_i, bool fill); 00205 00214 void getLineCells(int x0, int x1, int y0, int y1, std::vector<base_local_planner::Position2DInt>& pts); 00215 00220 void getFillCells(std::vector<base_local_planner::Position2DInt>& footprint); 00221 00222 base_local_planner::MapGrid map_; 00223 const costmap_2d::Costmap2D& costmap_; 00224 base_local_planner::WorldModel& world_model_; 00225 00226 std::vector<geometry_msgs::Point> footprint_spec_; 00227 double inscribed_radius_, circumscribed_radius_; 00228 00229 double sim_time_; 00230 double sim_granularity_; 00231 00232 int vx_samples_; 00233 int vy_samples_; 00234 int vtheta_samples_; 00235 00236 double userdist_scale_, occdist_scale_; 00237 double acc_lim_x_, acc_lim_y_, acc_lim_theta_; 00238 00239 base_local_planner::Trajectory traj_one, traj_two; 00240 00241 double max_vel_x_, min_vel_x_, max_vel_y_, min_vel_y_, max_vel_th_, min_vel_th_; 00242 00243 bool holonomic_robot_; 00244 00245 bool dwa_; 00246 00247 00257 inline double computeNewXPosition(double xi, double vx, double vy, double theta, double dt){ 00258 return xi + (vx * cos(theta) + vy * cos(M_PI_2 + theta)) * dt; 00259 } 00260 00270 inline double computeNewYPosition(double yi, double vx, double vy, double theta, double dt){ 00271 return yi + (vx * sin(theta) + vy * sin(M_PI_2 + theta)) * dt; 00272 } 00273 00281 inline double computeNewThetaPosition(double thetai, double vth, double dt){ 00282 return thetai + vth * dt; 00283 } 00284 00285 //compute velocity based on acceleration 00294 inline double computeNewVelocity(double vg, double vi, double a_max, double dt){ 00295 if(vg >= 0) 00296 return std::min(vg, vi + a_max * dt); 00297 return std::max(vg, vi - a_max * dt); 00298 } 00299 00300 double lineCost(int x0, int x1, int y0, int y1); 00301 double pointCost(int x, int y); 00302 // double headingDiff(int cell_x, int cell_y, double x, double y, double heading); 00303 }; 00304 }; 00305 00306 #endif