Go to the documentation of this file.
56 positive_only_ =
false;
57 negative_only_ =
false;
62 bool flag_set =
false;
65 if (sign_ == Sign::POSITIVE)
67 negative_only_ =
true;
70 sign_ = Sign::NEGATIVE;
72 else if (velocity > 0.0)
74 if (sign_ == Sign::NEGATIVE)
76 positive_only_ =
true;
79 sign_ = Sign::POSITIVE;
86 return (positive_only_ && velocity < 0.0) || (negative_only_ && velocity > 0.0);
91 return positive_only_ || negative_only_;
108 std::string resolved_name;
119 ROS_WARN_NAMED(
"OscillationCritic",
"Parameter min_trans_vel is deprecated. "
120 "Please use the name min_speed_xy or x_only_threshold instead.");
132 const nav_2d_msgs::Twist2D& vel,
133 const geometry_msgs::Pose2D& goal,
134 const nav_2d_msgs::Path2D& global_plan)
165 double sq_dist = x_diff * x_diff + y_diff * y_diff;
199 bool flag_set =
false;
param_t searchAndGetParam(const ros::NodeHandle &nh, const std::string ¶m_name, const param_t &default_value)
double scoreTrajectory(const dwb_msgs::Trajectory2D &traj) override
double oscillation_reset_dist_
bool getParam(const std::string &key, bool &b) const
ros::Time prev_reset_time_
bool update(double velocity)
update internal flags based on the commanded velocity
Checks to see whether the sign of the commanded velocity flips frequently.
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
geometry_msgs::Pose2D pose_
bool searchParam(const std::string &key, std::string &result) const
bool hasParam(const std::string &key) const
bool hasSignFlipped()
Check whether we are currently tracking a flipped sign.
bool setOscillationFlags(const nav_2d_msgs::Twist2D &cmd_vel)
Given a command that has been selected, track each component's sign for oscillations.
geometry_msgs::Pose2D prev_stationary_pose_
double oscillation_reset_dist_sq_
ros::NodeHandle critic_nh_
bool isOscillating(double velocity)
Check to see whether the proposed velocity would be considered oscillating.
#define ROS_WARN_NAMED(name,...)
double oscillation_reset_time_
CommandTrend theta_trend_
double oscillation_reset_angle_
bool resetAvailable()
Return true if the robot has travelled far enough or waited long enough.
void debrief(const nav_2d_msgs::Twist2D &cmd_vel) 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
dwb_critics
Author(s): David V. Lu!!
autogenerated on Sun May 18 2025 02:47:34