Skip to content

Commit fb43521

Browse files
feat(control_validator)!: add overrun check (#10236)
Signed-off-by: yuki-takagi-66 <yuki.takagi@tier4.jp>
1 parent c31c0ee commit fb43521

File tree

5 files changed

+62
-8
lines changed

5 files changed

+62
-8
lines changed

control/autoware_control_validator/README.md

+7-6
Original file line numberDiff line numberDiff line change
@@ -57,9 +57,10 @@ The following parameters can be set for the `control_validator`:
5757

5858
The input trajectory is detected as invalid if the index exceeds the following thresholds.
5959

60-
| Name | Type | Description | Default value |
61-
| :---------------------------------- | :----- | :---------------------------------------------------------------------------------------------------------- | :------------ |
62-
| `thresholds.max_distance_deviation` | double | invalid threshold of the max distance deviation between the predicted path and the reference trajectory [m] | 1.0 |
63-
| `thresholds.rolling_back_velocity` | double | threshold velocity to valid the vehicle velocity [m/s] | 0.5 |
64-
| `thresholds.over_velocity_offset` | double | threshold velocity offset to valid the vehicle velocity [m/s] | 2.0 |
65-
| `thresholds.over_velocity_ratio` | double | threshold ratio to valid the vehicle velocity [*] | 0.2 |
60+
| Name | Type | Description | Default value |
61+
| :----------------------------------- | :----- | :---------------------------------------------------------------------------------------------------------- | :------------ |
62+
| `thresholds.max_distance_deviation` | double | invalid threshold of the max distance deviation between the predicted path and the reference trajectory [m] | 1.0 |
63+
| `thresholds.rolling_back_velocity` | double | threshold velocity to valid the vehicle velocity [m/s] | 0.5 |
64+
| `thresholds.over_velocity_offset` | double | threshold velocity offset to valid the vehicle velocity [m/s] | 2.0 |
65+
| `thresholds.over_velocity_ratio` | double | threshold ratio to valid the vehicle velocity [*] | 0.2 |
66+
| `thresholds.overrun_stop_point_dist` | double | threshold distance to overrun stop point [m] | 0.8 |

control/autoware_control_validator/config/control_validator.param.yaml

+1
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,7 @@
1212
rolling_back_velocity: 0.5
1313
over_velocity_offset: 2.0
1414
over_velocity_ratio: 0.2
15+
overrun_stop_point_dist: 0.8
1516
nominal_latency: 0.01
1617

1718
vel_lpf_gain: 0.9 # Time constant 0.33

control/autoware_control_validator/include/autoware/control_validator/control_validator.hpp

+9
Original file line numberDiff line numberDiff line change
@@ -53,6 +53,7 @@ struct ValidationParams
5353
double rolling_back_velocity;
5454
double over_velocity_ratio;
5555
double over_velocity_offset;
56+
double overrun_stop_point_dist;
5657
double nominal_latency_threshold;
5758
};
5859

@@ -95,6 +96,14 @@ class ControlValidator : public rclcpp::Node
9596
void calc_velocity_deviation_status(
9697
const Trajectory & reference_trajectory, const Odometry & kinematics);
9798

99+
/**
100+
* @brief Calculate whether the vehicle has overrun a stop point in the trajectory.
101+
* @param reference_trajectory Reference trajectory
102+
* @param kinematics Current vehicle odometry including pose and twist
103+
*/
104+
void calc_stop_point_overrun_status(
105+
const Trajectory & reference_trajectory, const Odometry & kinematics);
106+
98107
private:
99108
/**
100109
* @brief Setup diagnostic updater

control/autoware_control_validator/msg/ControlValidatorStatus.msg

+3
Original file line numberDiff line numberDiff line change
@@ -4,12 +4,15 @@ builtin_interfaces/Time stamp
44
bool is_valid_max_distance_deviation
55
bool is_rolling_back
66
bool is_over_velocity
7+
bool has_overrun_stop_point
78
bool is_valid_latency
89

910
# values
1011
float64 max_distance_deviation
1112
float64 target_vel
1213
float64 vehicle_vel
14+
float64 dist_to_stop
15+
float64 nearest_trajectory_vel
1316
float64 latency
1417

1518
int64 invalid_count

control/autoware_control_validator/src/control_validator.cpp

+42-2
Original file line numberDiff line numberDiff line change
@@ -16,10 +16,12 @@
1616

1717
#include "autoware/control_validator/utils.hpp"
1818
#include "autoware/motion_utils/trajectory/interpolation.hpp"
19+
#include "autoware/motion_utils/trajectory/trajectory.hpp"
1920
#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp"
2021

2122
#include <nav_msgs/msg/odometry.hpp>
2223

24+
#include <algorithm>
2325
#include <cstdint>
2426
#include <memory>
2527
#include <string>
@@ -72,6 +74,7 @@ void ControlValidator::setup_parameters()
7274
p.rolling_back_velocity = declare_parameter<double>(t + "rolling_back_velocity");
7375
p.over_velocity_offset = declare_parameter<double>(t + "over_velocity_offset");
7476
p.over_velocity_ratio = declare_parameter<double>(t + "over_velocity_ratio");
77+
p.overrun_stop_point_dist = declare_parameter<double>(t + "overrun_stop_point_dist");
7578
p.nominal_latency_threshold = declare_parameter<double>(t + "nominal_latency");
7679
}
7780
const auto lpf_gain = declare_parameter<double>("vel_lpf_gain");
@@ -129,6 +132,11 @@ void ControlValidator::setup_diag()
129132
stat, !validation_status_.is_over_velocity,
130133
"The vehicle is over-speeding against the target.");
131134
});
135+
d.add(ns + "overrun_stop_point", [&](auto & stat) {
136+
set_status(
137+
stat, !validation_status_.has_overrun_stop_point,
138+
"The vehicle has overrun the front stop point on the trajectory.");
139+
});
132140
d.add(ns + "latency", [&](auto & stat) {
133141
set_status(
134142
stat, validation_status_.is_valid_latency, "The latency is larger than expected value.");
@@ -219,12 +227,14 @@ void ControlValidator::validate(
219227
}
220228

221229
validation_status_.stamp = get_clock()->now();
230+
validation_status_.vehicle_vel = vehicle_vel_.filter(kinematics.twist.twist.linear.x);
222231

223232
std::tie(
224233
validation_status_.max_distance_deviation, validation_status_.is_valid_max_distance_deviation) =
225234
calc_lateral_deviation_status(predicted_trajectory, *current_reference_trajectory_);
226235

227236
calc_velocity_deviation_status(*current_reference_trajectory_, kinematics);
237+
calc_stop_point_overrun_status(*current_reference_trajectory_, kinematics);
228238

229239
validation_status_.invalid_count =
230240
is_all_valid(validation_status_) ? 0 : validation_status_.invalid_count + 1;
@@ -245,7 +255,6 @@ void ControlValidator::calc_velocity_deviation_status(
245255
{
246256
auto & status = validation_status_;
247257
const auto & params = validation_params_;
248-
status.vehicle_vel = vehicle_vel_.filter(kinematics.twist.twist.linear.x);
249258
status.target_vel = target_vel_.filter(
250259
autoware::motion_utils::calcInterpolatedPoint(reference_trajectory, kinematics.pose.pose)
251260
.longitudinal_velocity_mps);
@@ -268,10 +277,41 @@ void ControlValidator::calc_velocity_deviation_status(
268277
}
269278
}
270279

280+
void ControlValidator::calc_stop_point_overrun_status(
281+
const Trajectory & reference_trajectory, const Odometry & kinematics)
282+
{
283+
auto & status = validation_status_;
284+
const auto & params = validation_params_;
285+
286+
status.dist_to_stop = [](const Trajectory & traj, const geometry_msgs::msg::Pose & pose) {
287+
const auto stop_idx_opt = autoware::motion_utils::searchZeroVelocityIndex(traj.points);
288+
289+
const size_t end_idx = stop_idx_opt ? *stop_idx_opt : traj.points.size() - 1;
290+
const size_t seg_idx =
291+
autoware::motion_utils::findFirstNearestSegmentIndexWithSoftConstraints(traj.points, pose);
292+
const double signed_length_on_traj = autoware::motion_utils::calcSignedArcLength(
293+
traj.points, pose.position, seg_idx, traj.points.at(end_idx).pose.position,
294+
std::min(end_idx, traj.points.size() - 2));
295+
296+
if (std::isnan(signed_length_on_traj)) {
297+
return 0.0;
298+
}
299+
return signed_length_on_traj;
300+
}(reference_trajectory, kinematics.pose.pose);
301+
302+
status.nearest_trajectory_vel =
303+
autoware::motion_utils::calcInterpolatedPoint(reference_trajectory, kinematics.pose.pose)
304+
.longitudinal_velocity_mps;
305+
306+
// NOTE: the same velocity threshold as autoware::motion_utils::searchZeroVelocity
307+
status.has_overrun_stop_point = status.dist_to_stop < -params.overrun_stop_point_dist &&
308+
status.nearest_trajectory_vel < 1e-3 && status.vehicle_vel > 1e-3;
309+
}
310+
271311
bool ControlValidator::is_all_valid(const ControlValidatorStatus & s)
272312
{
273313
return s.is_valid_max_distance_deviation && !s.is_rolling_back && !s.is_over_velocity &&
274-
s.is_valid_latency;
314+
!s.has_overrun_stop_point;
275315
}
276316

277317
void ControlValidator::display_status()

0 commit comments

Comments
 (0)