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 DWA_LOCAL_PLANNER_DWA_PLANNER_H_
00038 #define DWA_LOCAL_PLANNER_DWA_PLANNER_H_
00039 #include <queue>
00040 #include <vector>
00041 #include <Eigen/Core>
00042 #include <costmap_2d/costmap_2d.h>
00043 #include <costmap_2d/costmap_2d_ros.h>
00044 #include <tf/transform_listener.h>
00045 #include <base_local_planner/trajectory.h>
00046 #include <base_local_planner/map_grid.h>
00047 #include <base_local_planner/costmap_model.h>
00048 #include <nav_msgs/Odometry.h>
00049 #include <nav_msgs/Path.h>
00050 #include <ros/ros.h>
00051 #include <dwa_local_planner/velocity_iterator.h>
00052
00053 #include <dynamic_reconfigure/server.h>
00054 #include <dwa_local_planner/DWAPlannerConfig.h>
00055
00056 #include <base_local_planner/map_grid_visualizer.h>
00057
00058 namespace dwa_local_planner {
00063 class DWAPlanner {
00064 public:
00070 DWAPlanner(std::string name, costmap_2d::Costmap2DROS* costmap_ros);
00071
00075 ~DWAPlanner() {delete world_model_;}
00076
00084 Eigen::Vector3f computeNewPositions(const Eigen::Vector3f& pos, const Eigen::Vector3f& vel, double dt);
00085
00086
00096 void generateTrajectory(Eigen::Vector3f pos, const Eigen::Vector3f& vel, base_local_planner::Trajectory& traj, bool two_point_scoring);
00097
00106 base_local_planner::Trajectory computeTrajectories(const Eigen::Vector3f& pos, const Eigen::Vector3f& vel);
00107
00114 bool checkTrajectory(const Eigen::Vector3f& pos, const Eigen::Vector3f& vel);
00115
00123 base_local_planner::Trajectory findBestPath(tf::Stamped<tf::Pose> global_pose, tf::Stamped<tf::Pose> global_vel,
00124 tf::Stamped<tf::Pose>& drive_velocities);
00125
00130 void updatePlan(const std::vector<geometry_msgs::PoseStamped>& new_plan);
00131
00136 Eigen::Vector3f getAccLimits() { return acc_lim_; }
00137
00142 double getSimPeriod() { return sim_period_; }
00143
00154 bool getCellCosts(int cx, int cy, float &path_cost, float &goal_cost, float &occ_cost, float &total_cost);
00155
00156 private:
00160 void reconfigureCB(DWAPlannerConfig &config, uint32_t level);
00161
00168 double footprintCost(const Eigen::Vector3f& pos, double scale);
00169
00175 void selectBestTrajectory(base_local_planner::Trajectory* &best, base_local_planner::Trajectory* &comp);
00176
00180 void resetOscillationFlags();
00181
00190 void resetOscillationFlagsIfPossible(const Eigen::Vector3f& pos, const Eigen::Vector3f& prev);
00191
00198 bool setOscillationFlags(base_local_planner::Trajectory* t);
00199
00203 inline double squareDist(const geometry_msgs::PoseStamped& p1, const geometry_msgs::PoseStamped& p2){
00204 return (p1.pose.position.x - p2.pose.position.x) * (p1.pose.position.x - p2.pose.position.x)
00205 + (p1.pose.position.y - p2.pose.position.y) * (p1.pose.position.y - p2.pose.position.y);
00206 }
00207
00213 inline Eigen::Vector3f getMaxSpeedToStopInTime(double time){
00214 return acc_lim_ * std::max(time, 0.0);
00215 }
00216
00220 bool oscillationCheck(const Eigen::Vector3f& vel);
00221
00222 base_local_planner::MapGrid map_, front_map_;
00223 costmap_2d::Costmap2DROS* costmap_ros_;
00224 costmap_2d::Costmap2D costmap_;
00225 double stop_time_buffer_;
00226 double pdist_scale_, gdist_scale_, occdist_scale_, heading_scale_;
00227 Eigen::Vector3f acc_lim_, vsamples_, prev_stationary_pos_;
00228 std::vector<geometry_msgs::Point> footprint_spec_;
00229 base_local_planner::CostmapModel* world_model_;
00230 double sim_time_, sim_granularity_;
00231 double max_vel_x_, min_vel_x_;
00232 double max_vel_y_, min_vel_y_, min_vel_trans_, max_vel_trans_;
00233 double max_vel_th_, min_vel_th_, min_rot_vel_;
00234 double sim_period_;
00235 base_local_planner::Trajectory traj_one_, traj_two_;
00236 bool strafe_pos_only_, strafe_neg_only_, strafing_pos_, strafing_neg_;
00237 bool rot_pos_only_, rot_neg_only_, rotating_pos_, rotating_neg_;
00238 bool forward_pos_only_, forward_neg_only_, forward_pos_, forward_neg_;
00239 double oscillation_reset_dist_;
00240 double heading_lookahead_, forward_point_distance_;
00241 double scaling_speed_, max_scaling_factor_;
00242 std::vector<geometry_msgs::PoseStamped> global_plan_;
00243
00244 dynamic_reconfigure::Server<DWAPlannerConfig> dsrv_;
00245 dwa_local_planner::DWAPlannerConfig default_config_;
00246 bool setup_;
00247 boost::mutex configuration_mutex_;
00248 bool penalize_negative_x_;
00249 base_local_planner::MapGridVisualizer map_viz_;
00250 };
00251 };
00252 #endif