@@ -72,7 +72,7 @@ TrajectoryPoint make_trajectory_point(double x, double y)
72
72
return point;
73
73
}
74
74
75
- class ControlValidatorTest
75
+ class TrajectoryDeviationTest
76
76
: public ::testing::TestWithParam<std::tuple<Trajectory, Trajectory, double , bool >>
77
77
{
78
78
protected:
@@ -96,7 +96,7 @@ class ControlValidatorTest
96
96
std::shared_ptr<autoware::control_validator::ControlValidator> node;
97
97
};
98
98
99
- TEST_P (ControlValidatorTest , test_calc_lateral_deviation_status)
99
+ TEST_P (TrajectoryDeviationTest , test_calc_lateral_deviation_status)
100
100
{
101
101
auto [reference_trajectory, predicted_trajectory, expected_deviation, expected_condition] =
102
102
GetParam ();
@@ -108,7 +108,7 @@ TEST_P(ControlValidatorTest, test_calc_lateral_deviation_status)
108
108
}
109
109
110
110
INSTANTIATE_TEST_SUITE_P (
111
- ControlValidatorTests, ControlValidatorTest ,
111
+ TrajectoryDeviationTests, TrajectoryDeviationTest ,
112
112
::testing::Values (
113
113
114
114
std::make_tuple (
@@ -169,3 +169,51 @@ INSTANTIATE_TEST_SUITE_P(
169
169
1.0, true))
170
170
171
171
);
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