35 #ifndef DWB_CRITICS_OSCILLATION_H_ 36 #define DWB_CRITICS_OSCILLATION_H_ 83 bool prepare(
const geometry_msgs::Pose2D& pose,
const nav_2d_msgs::Twist2D& vel,
84 const geometry_msgs::Pose2D& goal,
const nav_2d_msgs::Path2D& global_plan)
override;
86 void reset()
override;
87 void debrief(
const nav_2d_msgs::Twist2D& cmd_vel)
override;
105 bool update(
double velocity);
154 #endif // DWB_CRITICS_OSCILLATION_H_
bool hasSignFlipped()
Check whether we are currently tracking a flipped sign.
bool update(double velocity)
update internal flags based on the commanded velocity
void debrief(const nav_2d_msgs::Twist2D &cmd_vel) override
double oscillation_reset_dist_
Checks to see whether the sign of the commanded velocity flips frequently.
double oscillation_reset_dist_sq_
double oscillation_reset_angle_
bool isOscillating(double velocity)
Check to see whether the proposed velocity would be considered oscillating.
ros::Time prev_reset_time_
double oscillation_reset_time_
bool setOscillationFlags(const nav_2d_msgs::Twist2D &cmd_vel)
Given a command that has been selected, track each component's sign for oscillations.
CommandTrend theta_trend_
geometry_msgs::Pose2D prev_stationary_pose_
geometry_msgs::Pose2D pose_
bool resetAvailable()
Return true if the robot has travelled far enough or waited long enough.
Helper class for performing the same logic on the x,y and theta dimensions.
double scoreTrajectory(const dwb_msgs::Trajectory2D &traj) override
bool prepare(const geometry_msgs::Pose2D &pose, const nav_2d_msgs::Twist2D &vel, const geometry_msgs::Pose2D &goal, const nav_2d_msgs::Path2D &global_plan) override