We read every piece of feedback, and take your input very seriously.
To see all available qualifiers, see our documentation.
1 parent c66a3ae commit fdc56f7Copy full SHA for fdc56f7
control/autoware_control_validator/src/control_validator.cpp
@@ -45,13 +45,13 @@ void AccelerationValidator::validate(
45
res.desired_acc = desired_acc_lpf.getValue().value();
46
res.measured_acc = measured_acc_lpf.getValue().value();
47
48
+ res.is_valid_acc = true;
49
const int8_t des_sign = std::signbit(res.desired_acc) ? 1 : -1;
50
if (
- res.measured_acc > res.desired_acc * (1 + des_sign * e_scale) + e_offset &&
51
+ res.measured_acc > res.desired_acc * (1 + des_sign * e_scale) + e_offset ||
52
res.measured_acc < res.desired_acc * (1 - des_sign * e_scale) - e_offset) {
53
res.is_valid_acc = false;
54
}
- res.is_valid_acc = true;
55
56
57
ControlValidator::ControlValidator(const rclcpp::NodeOptions & options)
0 commit comments