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_TRAJECTORY_CRITIC_H
00036 #define DWB_LOCAL_PLANNER_TRAJECTORY_CRITIC_H
00037
00038 #include <ros/ros.h>
00039 #include <nav_core2/common.h>
00040 #include <nav_core2/costmap.h>
00041 #include <geometry_msgs/Pose2D.h>
00042 #include <nav_2d_msgs/Twist2D.h>
00043 #include <nav_2d_msgs/Path2D.h>
00044 #include <dwb_msgs/Trajectory2D.h>
00045 #include <sensor_msgs/PointCloud.h>
00046 #include <string>
00047 #include <vector>
00048
00049 namespace dwb_local_planner
00050 {
00075 class TrajectoryCritic
00076 {
00077 public:
00078 using Ptr = std::shared_ptr<dwb_local_planner::TrajectoryCritic>;
00079
00080 virtual ~TrajectoryCritic() {}
00081
00092 void initialize(const ros::NodeHandle& planner_nh, std::string name, nav_core2::Costmap::Ptr costmap)
00093 {
00094 name_ = name;
00095 costmap_ = costmap;
00096 planner_nh_ = planner_nh;
00097 critic_nh_ = ros::NodeHandle(planner_nh_, name_);
00098 critic_nh_.param("scale", scale_, 1.0);
00099 onInit();
00100 }
00101
00102 virtual void onInit() {}
00103
00110 virtual void reset() {}
00111
00122 virtual bool prepare(const geometry_msgs::Pose2D& pose, const nav_2d_msgs::Twist2D& vel,
00123 const geometry_msgs::Pose2D& goal,
00124 const nav_2d_msgs::Path2D& global_plan)
00125 {
00126 return true;
00127 }
00128
00135 virtual double scoreTrajectory(const dwb_msgs::Trajectory2D& traj) = 0;
00136
00140 virtual void debrief(const nav_2d_msgs::Twist2D& cmd_vel) {}
00141
00158 virtual void addCriticVisualization(sensor_msgs::PointCloud& pc) {}
00159
00160 std::string getName()
00161 {
00162 return name_;
00163 }
00164
00165 virtual double getScale() const { return scale_; }
00166 void setScale(const double scale) { scale_ = scale; }
00167 protected:
00168 std::string name_;
00169 nav_core2::Costmap::Ptr costmap_;
00170 double scale_;
00171 ros::NodeHandle critic_nh_, planner_nh_;
00172 };
00173
00174 }
00175
00176 #endif // DWB_LOCAL_PLANNER_TRAJECTORY_CRITIC_H