35 #ifndef DWB_CRITICS__OSCILLATION_HPP_
36 #define DWB_CRITICS__OSCILLATION_HPP_
41 #include "dwb_core/trajectory_critic.hpp"
43 using namespace std::chrono_literals;
86 : oscillation_reset_time_(0s) {}
87 void onInit()
override;
89 const geometry_msgs::msg::Pose & pose,
const nav_2d_msgs::msg::Twist2D & vel,
90 const geometry_msgs::msg::Pose & goal,
const nav_msgs::msg::Path & global_plan)
override;
91 double scoreTrajectory(
const dwb_msgs::msg::Trajectory2D & traj)
override;
92 void reset()
override;
93 void debrief(
const nav_2d_msgs::msg::Twist2D & cmd_vel)
override;
111 bool update(
double velocity);
118 bool isOscillating(
double velocity);
124 bool hasSignFlipped();
129 enum class Sign { ZERO, POSITIVE, NEGATIVE };
132 bool positive_only_, negative_only_;
140 bool setOscillationFlags(
const nav_2d_msgs::msg::Twist2D & cmd_vel);
145 bool resetAvailable();
147 CommandTrend x_trend_, y_trend_, theta_trend_;
148 double oscillation_reset_dist_, oscillation_reset_angle_, x_only_threshold_;
149 rclcpp::Duration oscillation_reset_time_;
152 double oscillation_reset_dist_sq_;
155 geometry_msgs::msg::Pose pose_, prev_stationary_pose_;
157 rclcpp::Time prev_reset_time_;
158 rclcpp::Clock::SharedPtr clock_;
Evaluates a Trajectory2D to produce a score.
Checks to see whether the sign of the commanded velocity flips frequently.