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 #ifndef DWB_LOCAL_PLANNER_DWB_LOCAL_PLANNER_H
00036 #define DWB_LOCAL_PLANNER_DWB_LOCAL_PLANNER_H
00037
00038 #include <dwb_local_planner/trajectory_generator.h>
00039 #include <dwb_local_planner/goal_checker.h>
00040 #include <dwb_local_planner/trajectory_critic.h>
00041 #include <dwb_local_planner/publisher.h>
00042 #include <nav_core2/local_planner.h>
00043 #include <pluginlib/class_loader.h>
00044 #include <string>
00045 #include <vector>
00046
00047 namespace dwb_local_planner
00048 {
00049
00054 class DWBLocalPlanner: public nav_core2::LocalPlanner
00055 {
00056 public:
00060 DWBLocalPlanner();
00061
00062 virtual ~DWBLocalPlanner() {}
00063
00070 void initialize(const ros::NodeHandle& parent, const std::string& name,
00071 TFListenerPtr tf, nav_core2::Costmap::Ptr costmap) override;
00072
00077 void setGoalPose(const nav_2d_msgs::Pose2DStamped& goal_pose) override;
00078
00083 void setPlan(const nav_2d_msgs::Path2D& path) override;
00084
00097 nav_2d_msgs::Twist2DStamped computeVelocityCommands(const nav_2d_msgs::Pose2DStamped& pose,
00098 const nav_2d_msgs::Twist2D& velocity) override;
00099
00110 bool isGoalReached(const nav_2d_msgs::Pose2DStamped& pose, const nav_2d_msgs::Twist2D& velocity) override;
00111
00123 virtual dwb_msgs::TrajectoryScore scoreTrajectory(const dwb_msgs::Trajectory2D& traj, double best_score = -1);
00124
00137 virtual nav_2d_msgs::Twist2DStamped computeVelocityCommands(const nav_2d_msgs::Pose2DStamped& pose,
00138 const nav_2d_msgs::Twist2D& velocity,
00139 std::shared_ptr<dwb_msgs::LocalPlanEvaluation>& results);
00140
00141
00142 protected:
00148 virtual void prepare(const nav_2d_msgs::Pose2DStamped& pose, const nav_2d_msgs::Twist2D& velocity);
00149
00153 virtual dwb_msgs::TrajectoryScore coreScoringAlgorithm(const geometry_msgs::Pose2D& pose,
00154 const nav_2d_msgs::Twist2D velocity,
00155 std::shared_ptr<dwb_msgs::LocalPlanEvaluation>& results);
00156
00167 virtual nav_2d_msgs::Path2D transformGlobalPlan(const nav_2d_msgs::Pose2DStamped& pose);
00168
00172 geometry_msgs::Pose2D transformPoseToLocal(const nav_2d_msgs::Pose2DStamped& pose);
00173
00174 nav_2d_msgs::Path2D global_plan_;
00175 nav_2d_msgs::Pose2DStamped goal_pose_;
00176 bool prune_plan_;
00177 double prune_distance_;
00178 bool debug_trajectory_details_;
00179 bool short_circuit_trajectory_evaluation_;
00180
00181
00182 pluginlib::ClassLoader<TrajectoryGenerator> traj_gen_loader_;
00183 TrajectoryGenerator::Ptr traj_generator_;
00184 pluginlib::ClassLoader<GoalChecker> goal_checker_loader_;
00185 GoalChecker::Ptr goal_checker_;
00186 pluginlib::ClassLoader<TrajectoryCritic> critic_loader_;
00187 std::vector<TrajectoryCritic::Ptr> critics_;
00188
00195 std::string resolveCriticClassName(std::string base_name);
00196
00201 virtual void loadCritics(const std::string name);
00202
00203 std::vector<std::string> default_critic_namespaces_;
00204
00205 nav_core2::Costmap::Ptr costmap_;
00206 bool update_costmap_before_planning_;
00207 TFListenerPtr tf_;
00208 DWBPublisher pub_;
00209
00210 ros::NodeHandle planner_nh_;
00211 };
00212
00213 }
00214
00215 #endif // DWB_LOCAL_PLANNER_DWB_LOCAL_PLANNER_H