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 namespace dwa_local_planner {
00068 class DWAPlanner {
00069 public:
00076 DWAPlanner(std::string name, base_local_planner::LocalPlannerUtil *planner_util);
00077
00081 ~DWAPlanner() {}
00082
00086 void reconfigure(DWAPlannerConfig &cfg);
00087
00095 bool checkTrajectory(
00096 const Eigen::Vector3f pos,
00097 const Eigen::Vector3f vel,
00098 const Eigen::Vector3f vel_samples);
00099
00107 base_local_planner::Trajectory findBestPath(
00108 tf::Stamped<tf::Pose> global_pose,
00109 tf::Stamped<tf::Pose> global_vel,
00110 tf::Stamped<tf::Pose>& drive_velocities,
00111 std::vector<geometry_msgs::Point> footprint_spec);
00112
00117 void updatePlanAndLocalCosts(tf::Stamped<tf::Pose> global_pose,
00118 const std::vector<geometry_msgs::PoseStamped>& new_plan);
00119
00124 double getSimPeriod() { return sim_period_; }
00125
00136 bool getCellCosts(int cx, int cy, float &path_cost, float &goal_cost, float &occ_cost, float &total_cost);
00137
00141 bool setPlan(const std::vector<geometry_msgs::PoseStamped>& orig_global_plan);
00142
00143 private:
00144
00145 base_local_planner::LocalPlannerUtil *planner_util_;
00146
00147 double stop_time_buffer_;
00148 double pdist_scale_, gdist_scale_, occdist_scale_;
00149 Eigen::Vector3f vsamples_;
00150
00151 double sim_period_;
00152 base_local_planner::Trajectory result_traj_;
00153
00154 double forward_point_distance_;
00155
00156 std::vector<geometry_msgs::PoseStamped> global_plan_;
00157
00158 boost::mutex configuration_mutex_;
00159 pcl::PointCloud<base_local_planner::MapGridCostPoint> traj_cloud_;
00160 pcl_ros::Publisher<base_local_planner::MapGridCostPoint> traj_cloud_pub_;
00161 bool publish_cost_grid_pc_;
00162
00163 base_local_planner::MapGridVisualizer map_viz_;
00164
00165
00166 base_local_planner::SimpleTrajectoryGenerator generator_;
00167 base_local_planner::OscillationCostFunction oscillation_costs_;
00168 base_local_planner::ObstacleCostFunction obstacle_costs_;
00169 base_local_planner::MapGridCostFunction path_costs_;
00170 base_local_planner::MapGridCostFunction goal_costs_;
00171 base_local_planner::MapGridCostFunction goal_front_costs_;
00172 base_local_planner::MapGridCostFunction alignment_costs_;
00173
00174 base_local_planner::SimpleScoredSamplingPlanner scored_sampling_planner_;
00175 };
00176 };
00177 #endif