Skip to content

Commit d681da0

Browse files
add test
Signed-off-by: yuki-takagi-66 <yuki.takagi@tier4.jp>
1 parent 059181c commit d681da0

File tree

3 files changed

+66
-11
lines changed

3 files changed

+66
-11
lines changed

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

+4
Original file line numberDiff line numberDiff line change
@@ -39,6 +39,8 @@
3939
#include <tuple>
4040
#include <utility>
4141

42+
class AccelerationValidatorTest;
43+
4244
namespace autoware::control_validator
4345
{
4446
using autoware_control_msgs::msg::Control;
@@ -67,6 +69,7 @@ struct ValidationParams
6769
class AccelerationValidator
6870
{
6971
public:
72+
friend class ::AccelerationValidatorTest;
7073
explicit AccelerationValidator(rclcpp::Node & node)
7174
{
7275
e_offset =
@@ -83,6 +86,7 @@ class AccelerationValidator
8386
const AccelWithCovarianceStamped & loc_acc);
8487

8588
private:
89+
bool is_in_error_range() const;
8690
double e_offset;
8791
double e_scale;
8892
autoware::signal_processing::LowpassFilter1d desired_acc_lpf{0.0};

control/autoware_control_validator/src/control_validator.cpp

+11-8
Original file line numberDiff line numberDiff line change
@@ -44,14 +44,17 @@ void AccelerationValidator::validate(
4444

4545
res.desired_acc = desired_acc_lpf.getValue().value();
4646
res.measured_acc = measured_acc_lpf.getValue().value();
47-
res.is_valid_acc = [this]() {
48-
const double des = desired_acc_lpf.getValue().value();
49-
const double mes = measured_acc_lpf.getValue().value();
50-
const int8_t des_sign = std::signbit(des) ? 1 : -1;
51-
52-
return mes <= des * (1 + des_sign * e_scale) + e_offset &&
53-
mes >= des * (1 - des_sign * e_scale) + e_offset;
54-
}();
47+
res.is_valid_acc = is_in_error_range();
48+
}
49+
50+
bool AccelerationValidator::is_in_error_range() const
51+
{
52+
const double des = desired_acc_lpf.getValue().value();
53+
const double mes = measured_acc_lpf.getValue().value();
54+
const int8_t des_sign = std::signbit(des) ? 1 : -1;
55+
56+
return mes <= des * (1 + des_sign * e_scale) + e_offset &&
57+
mes >= des * (1 - des_sign * e_scale) - e_offset;
5558
}
5659

5760
ControlValidator::ControlValidator(const rclcpp::NodeOptions & options)

control/autoware_control_validator/test/test_control_validator.cpp

+51-3
Original file line numberDiff line numberDiff line change
@@ -72,7 +72,7 @@ TrajectoryPoint make_trajectory_point(double x, double y)
7272
return point;
7373
}
7474

75-
class ControlValidatorTest
75+
class TrajectoryDeviationTest
7676
: public ::testing::TestWithParam<std::tuple<Trajectory, Trajectory, double, bool>>
7777
{
7878
protected:
@@ -96,7 +96,7 @@ class ControlValidatorTest
9696
std::shared_ptr<autoware::control_validator::ControlValidator> node;
9797
};
9898

99-
TEST_P(ControlValidatorTest, test_calc_lateral_deviation_status)
99+
TEST_P(TrajectoryDeviationTest, test_calc_lateral_deviation_status)
100100
{
101101
auto [reference_trajectory, predicted_trajectory, expected_deviation, expected_condition] =
102102
GetParam();
@@ -108,7 +108,7 @@ TEST_P(ControlValidatorTest, test_calc_lateral_deviation_status)
108108
}
109109

110110
INSTANTIATE_TEST_SUITE_P(
111-
ControlValidatorTests, ControlValidatorTest,
111+
TrajectoryDeviationTests, TrajectoryDeviationTest,
112112
::testing::Values(
113113

114114
std::make_tuple(
@@ -169,3 +169,51 @@ INSTANTIATE_TEST_SUITE_P(
169169
1.0, true))
170170

171171
);
172+
173+
class AccelerationValidatorTest : public ::testing::TestWithParam<std::tuple<bool, double, double>>
174+
{
175+
public:
176+
bool is_in_error_range() { return acceleration_validator_->is_in_error_range(); }
177+
void set_desired(double x) { acceleration_validator_->desired_acc_lpf.reset(x); }
178+
void set_measured(double x) { acceleration_validator_->measured_acc_lpf.reset(x); }
179+
180+
protected:
181+
void SetUp() override
182+
{
183+
rclcpp::init(0, nullptr);
184+
rclcpp::NodeOptions options;
185+
options.arguments(
186+
{"--ros-args", "--params-file",
187+
ament_index_cpp::get_package_share_directory("autoware_control_validator") +
188+
"/config/control_validator.param.yaml",
189+
"--params-file",
190+
ament_index_cpp::get_package_share_directory("autoware_test_utils") +
191+
"/config/test_vehicle_info.param.yaml"});
192+
193+
node_ = std::make_shared<autoware::control_validator::ControlValidator>(options);
194+
acceleration_validator_ =
195+
std::make_shared<autoware::control_validator::AccelerationValidator>(*node_);
196+
}
197+
void TearDown() override { rclcpp::shutdown(); }
198+
199+
std::shared_ptr<rclcpp::Node> node_;
200+
std::shared_ptr<autoware::control_validator::AccelerationValidator> acceleration_validator_;
201+
};
202+
203+
TEST_P(AccelerationValidatorTest, test_is_in_error_range)
204+
{
205+
auto [expected, des, mes] = GetParam();
206+
set_desired(des);
207+
set_measured(mes);
208+
209+
ASSERT_EQ(expected, is_in_error_range());
210+
};
211+
212+
INSTANTIATE_TEST_SUITE_P(
213+
AccelerationValidatorTests, AccelerationValidatorTest,
214+
::testing::Values(
215+
std::make_tuple(true, 0.0, 0.0), std::make_tuple(false, 0.0, 5.0),
216+
std::make_tuple(false, 0.0, -5.0), std::make_tuple(true, 1.0, 1.0),
217+
std::make_tuple(false, 1.0, 5.0), std::make_tuple(false, 1.0, -5.0),
218+
std::make_tuple(true, -1.0, -1.0), std::make_tuple(false, -1.0, -5.0),
219+
std::make_tuple(false, -1.0, 5.0)));

0 commit comments

Comments
 (0)