Skip to content

Commit f97253a

Browse files
yuki-takagi-66esteve
authored andcommitted
fix(control_validator): fix param names and doc (autowarefoundation#8104)
* fix Signed-off-by: Yuki Takagi <yuki.takagi@tier4.jp>
1 parent 03c6649 commit f97253a

File tree

2 files changed

+7
-6
lines changed

2 files changed

+7
-6
lines changed

control/autoware_control_validator/README.md

+5-4
Original file line numberDiff line numberDiff line change
@@ -8,10 +8,11 @@ The `control_validator` is a module that checks the validity of the output of th
88

99
The following features are supported for the validation and can have thresholds set by parameters.
1010
The listed features below does not always correspond to the latest implementation.
11-
| Description | Arguments | Diagnostic equation | Implemented function name |
12-
| ---------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------- | :--------------------------------: | ------------------------------- |
13-
| Inverse velocity: Measured velocity has a different sign from the target velocity. | measured velocity $v$, target velocity $\hat{v}$, and threshold velocity parameter $k$ | $v\hat{v}<0,~\|v\|>k $ | `checkValidVelocityDeviation()` |
14-
| Overspeed: Measured speed exceeds target speed significantly. | measured velocity $v$, target velocity $\hat{v}$, and threshold ratio parameter $r$ | $\| v \| > (1 + r) \| \hat{v} \| $ | `checkValidVelocityDeviation()` |
11+
12+
| Description | Arguments | Diagnostic equation | Implemented function name |
13+
| ---------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------- | :-----------------------------------------------: | ------------------------------- |
14+
| Inverse velocity: Measured velocity has a different sign from the target velocity. | measured velocity $v$, target velocity $\hat{v}$, and threshold velocity parameter $k$ | $v \hat{v} < 0, \quad \lvert v \rvert > k$ | `checkValidVelocityDeviation()` |
15+
| Overspeed: Measured speed exceeds target speed significantly. | measured velocity $v$, target velocity $\hat{v}$, and threshold ratio parameter $r$ | $\lvert v \rvert > (1 + r) \lvert \hat{v} \rvert$ | `checkValidVelocityDeviation()` |
1516

1617
- **Deviation check between reference trajectory and predicted trajectory** : invalid when the largest deviation between the predicted trajectory and reference trajectory is greater than the given threshold.
1718

control/autoware_control_validator/src/control_validator.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -53,8 +53,8 @@ void ControlValidator::setupParameters()
5353
auto & p = validation_params_;
5454
const std::string t = "thresholds.";
5555
p.max_distance_deviation_threshold = declare_parameter<double>(t + "max_distance_deviation");
56-
p.max_reverse_velocity_threshold = declare_parameter<double>(t + "reverse_velocity");
57-
p.max_over_velocity_ratio_threshold = declare_parameter<double>(t + "over_velocity_ratio");
56+
p.max_reverse_velocity_threshold = declare_parameter<double>(t + "max_reverse_velocity");
57+
p.max_over_velocity_ratio_threshold = declare_parameter<double>(t + "max_over_velocity_ratio");
5858
}
5959

6060
try {

0 commit comments

Comments
 (0)