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_CRITICS_OSCILLATION_H_
00036 #define DWB_CRITICS_OSCILLATION_H_
00037 
00038 #include <dwb_local_planner/trajectory_critic.h>
00039 #include <vector>
00040 #include <string>
00041 
00042 namespace dwb_critics
00043 {
00044 
00079 class OscillationCritic: public dwb_local_planner::TrajectoryCritic
00080 {
00081 public:
00082   void onInit() override;
00083   bool prepare(const geometry_msgs::Pose2D& pose, const nav_2d_msgs::Twist2D& vel,
00084                const geometry_msgs::Pose2D& goal, const nav_2d_msgs::Path2D& global_plan) override;
00085   double scoreTrajectory(const dwb_msgs::Trajectory2D& traj) override;
00086   void reset() override;
00087   void debrief(const nav_2d_msgs::Twist2D& cmd_vel) override;
00088 
00089 protected:
00094   class CommandTrend
00095   {
00096   public:
00097     CommandTrend();
00098     void reset();
00099 
00105     bool update(double velocity);
00106 
00112     bool isOscillating(double velocity);
00113 
00118     bool hasSignFlipped();
00119 
00120   protected:
00121     
00122     enum class Sign { ZERO, POSITIVE, NEGATIVE };
00123 
00124     Sign sign_;
00125     bool positive_only_, negative_only_;
00126   };
00127 
00133   bool setOscillationFlags(const nav_2d_msgs::Twist2D& cmd_vel);
00134 
00138   bool resetAvailable();
00139 
00140   CommandTrend x_trend_, y_trend_, theta_trend_;
00141   double oscillation_reset_dist_, oscillation_reset_angle_, x_only_threshold_;
00142   double oscillation_reset_time_;
00143 
00144   
00145   double oscillation_reset_dist_sq_;
00146 
00147   
00148   geometry_msgs::Pose2D pose_, prev_stationary_pose_;
00149   
00150   ros::Time prev_reset_time_;
00151 };
00152 
00153 }  
00154 #endif  // DWB_CRITICS_OSCILLATION_H_