Go to the documentation of this file.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
00040 #include <vector>
00041 #include <Eigen/Core>
00042
00043
00044 #include <dwa_local_planner/DWAPlannerConfig.h>
00045
00046
00047 #include <base_local_planner/map_grid_visualizer.h>
00048 #include <pcl_ros/publisher.h>
00049
00050
00051 #include <costmap_2d/costmap_2d.h>
00052
00053 #include <base_local_planner/trajectory.h>
00054 #include <base_local_planner/local_planner_limits.h>
00055 #include <base_local_planner/local_planner_util.h>
00056 #include <base_local_planner/simple_trajectory_generator.h>
00057
00058 #include <base_local_planner/oscillation_cost_function.h>
00059 #include <base_local_planner/map_grid_cost_function.h>
00060 #include <base_local_planner/obstacle_cost_function.h>
00061 #include <base_local_planner/simple_scored_sampling_planner.h>
00062
00063 #include <nav_msgs/Path.h>
00064
00065 namespace dwa_local_planner {
00070 class DWAPlanner {
00071 public:
00078 DWAPlanner(std::string name, base_local_planner::LocalPlannerUtil *planner_util);
00079
00083 ~DWAPlanner() {if(traj_cloud_) delete traj_cloud_;}
00084
00088 void reconfigure(DWAPlannerConfig &cfg);
00089
00097 bool checkTrajectory(
00098 const Eigen::Vector3f pos,
00099 const Eigen::Vector3f vel,
00100 const Eigen::Vector3f vel_samples);
00101
00109 base_local_planner::Trajectory findBestPath(
00110 tf::Stamped<tf::Pose> global_pose,
00111 tf::Stamped<tf::Pose> global_vel,
00112 tf::Stamped<tf::Pose>& drive_velocities,
00113 std::vector<geometry_msgs::Point> footprint_spec);
00114
00119 void updatePlanAndLocalCosts(tf::Stamped<tf::Pose> global_pose,
00120 const std::vector<geometry_msgs::PoseStamped>& new_plan);
00121
00126 double getSimPeriod() { return sim_period_; }
00127
00138 bool getCellCosts(int cx, int cy, float &path_cost, float &goal_cost, float &occ_cost, float &total_cost);
00139
00143 bool setPlan(const std::vector<geometry_msgs::PoseStamped>& orig_global_plan);
00144
00145 private:
00146
00147 base_local_planner::LocalPlannerUtil *planner_util_;
00148
00149 double stop_time_buffer_;
00150 double pdist_scale_, gdist_scale_, occdist_scale_;
00151 Eigen::Vector3f vsamples_;
00152
00153 double sim_period_;
00154 base_local_planner::Trajectory result_traj_;
00155
00156 double forward_point_distance_;
00157
00158 std::vector<geometry_msgs::PoseStamped> global_plan_;
00159
00160 boost::mutex configuration_mutex_;
00161 pcl::PointCloud<base_local_planner::MapGridCostPoint>* traj_cloud_;
00162 pcl_ros::Publisher<base_local_planner::MapGridCostPoint> traj_cloud_pub_;
00163 bool publish_cost_grid_pc_;
00164 bool publish_traj_pc_;
00165
00166 double cheat_factor_;
00167
00168 base_local_planner::MapGridVisualizer map_viz_;
00169
00170
00171 base_local_planner::SimpleTrajectoryGenerator generator_;
00172 base_local_planner::OscillationCostFunction oscillation_costs_;
00173 base_local_planner::ObstacleCostFunction obstacle_costs_;
00174 base_local_planner::MapGridCostFunction path_costs_;
00175 base_local_planner::MapGridCostFunction goal_costs_;
00176 base_local_planner::MapGridCostFunction goal_front_costs_;
00177 base_local_planner::MapGridCostFunction alignment_costs_;
00178
00179 base_local_planner::SimpleScoredSamplingPlanner scored_sampling_planner_;
00180 };
00181 };
00182 #endif