35 #include "dwb_critics/oscillation.hpp"
40 #include "nav_2d_utils/parameters.hpp"
41 #include "nav2_util/node_utils.hpp"
42 #include "dwb_core/exceptions.hpp"
43 #include "pluginlib/class_list_macros.hpp"
51 OscillationCritic::CommandTrend::CommandTrend()
56 void OscillationCritic::CommandTrend::reset()
59 positive_only_ =
false;
60 negative_only_ =
false;
63 bool OscillationCritic::CommandTrend::update(
double velocity)
65 bool flag_set =
false;
67 if (sign_ == Sign::POSITIVE) {
68 negative_only_ =
true;
71 sign_ = Sign::NEGATIVE;
72 }
else if (velocity > 0.0) {
73 if (sign_ == Sign::NEGATIVE) {
74 positive_only_ =
true;
77 sign_ = Sign::POSITIVE;
82 bool OscillationCritic::CommandTrend::isOscillating(
double velocity)
84 return (positive_only_ && velocity < 0.0) || (negative_only_ && velocity > 0.0);
87 bool OscillationCritic::CommandTrend::hasSignFlipped()
89 return positive_only_ || negative_only_;
94 auto node = node_.lock();
96 throw std::runtime_error{
"Failed to lock node"};
99 clock_ = node->get_clock();
101 oscillation_reset_dist_ = nav_2d_utils::searchAndGetParam(
103 dwb_plugin_name_ +
"." + name_ +
".oscillation_reset_dist", 0.05);
104 oscillation_reset_dist_sq_ = oscillation_reset_dist_ * oscillation_reset_dist_;
105 oscillation_reset_angle_ = nav_2d_utils::searchAndGetParam(
107 dwb_plugin_name_ +
"." + name_ +
".oscillation_reset_angle", 0.2);
108 oscillation_reset_time_ = rclcpp::Duration::from_seconds(
109 nav_2d_utils::searchAndGetParam(
111 dwb_plugin_name_ +
"." + name_ +
".oscillation_reset_time", -1.0));
113 nav2_util::declare_parameter_if_not_declared(
115 dwb_plugin_name_ +
"." + name_ +
".x_only_threshold", rclcpp::ParameterValue(0.05));
124 node->get_parameter(dwb_plugin_name_ +
"." + name_ +
".x_only_threshold", x_only_threshold_);
151 const geometry_msgs::msg::Pose2D & pose,
152 const nav_2d_msgs::msg::Twist2D &,
153 const geometry_msgs::msg::Pose2D &,
154 const nav_2d_msgs::msg::Path2D &)
162 if (setOscillationFlags(cmd_vel)) {
163 prev_stationary_pose_ = pose_;
164 prev_reset_time_ = clock_->now();
168 if (x_trend_.hasSignFlipped() || y_trend_.hasSignFlipped() || theta_trend_.hasSignFlipped()) {
170 if (resetAvailable()) {
176 bool OscillationCritic::resetAvailable()
178 if (oscillation_reset_dist_ >= 0.0) {
179 double x_diff = pose_.x - prev_stationary_pose_.x;
180 double y_diff = pose_.y - prev_stationary_pose_.y;
181 double sq_dist = x_diff * x_diff + y_diff * y_diff;
182 if (sq_dist > oscillation_reset_dist_sq_) {
186 if (oscillation_reset_angle_ >= 0.0) {
187 double th_diff = pose_.theta - prev_stationary_pose_.theta;
188 if (fabs(th_diff) > oscillation_reset_angle_) {
192 if (oscillation_reset_time_ >= rclcpp::Duration::from_seconds(0.0)) {
193 auto t_diff = (clock_->now() - prev_reset_time_);
194 if (t_diff > oscillation_reset_time_) {
205 theta_trend_.reset();
208 bool OscillationCritic::setOscillationFlags(
const nav_2d_msgs::msg::Twist2D & cmd_vel)
210 bool flag_set =
false;
212 flag_set |= x_trend_.update(cmd_vel.x);
215 if (x_only_threshold_ < 0.0 || fabs(cmd_vel.x) <= x_only_threshold_) {
216 flag_set |= y_trend_.update(cmd_vel.y);
217 flag_set |= theta_trend_.update(cmd_vel.theta);
224 if (x_trend_.isOscillating(traj.velocity.x) ||
225 y_trend_.isOscillating(traj.velocity.y) ||
226 theta_trend_.isOscillating(traj.velocity.theta))
229 IllegalTrajectoryException(name_,
"Trajectory is oscillating.");
Evaluates a Trajectory2D to produce a score.
Checks to see whether the sign of the commanded velocity flips frequently.
void debrief(const nav_2d_msgs::msg::Twist2D &cmd_vel) override
debrief informs the critic what the chosen cmd_vel was (if it cares)
bool prepare(const geometry_msgs::msg::Pose2D &pose, const nav_2d_msgs::msg::Twist2D &vel, const geometry_msgs::msg::Pose2D &goal, const nav_2d_msgs::msg::Path2D &global_plan) override
Prior to evaluating any trajectories, look at contextual information constant across all trajectories...
double scoreTrajectory(const dwb_msgs::msg::Trajectory2D &traj) override
Return a raw score for the given trajectory.
void reset() override
Reset the state of the critic.