-
Notifications
You must be signed in to change notification settings - Fork 682
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
test(lane_departure_checker): add tests for calcTrajectoryDeviation()…
…, calcMaxSearchLengthForBoundaries() (#9029) * move calcTrajectoryDeviation() to separate files Signed-off-by: mitukou1109 <[email protected]> * move calcMaxSearchLengthForBoundaries() to separate files Signed-off-by: mitukou1109 <[email protected]> * add tests for calcTrajectoryDeviation() Signed-off-by: mitukou1109 <[email protected]> * add tests for calcMaxSearchLengthForBoundaries() Signed-off-by: mitukou1109 <[email protected]> --------- Signed-off-by: mitukou1109 <[email protected]> Co-authored-by: Kyoichi Sugahara <[email protected]>
- Loading branch information
1 parent
959e57b
commit 2a50825
Showing
6 changed files
with
250 additions
and
31 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
105 changes: 105 additions & 0 deletions
105
control/autoware_lane_departure_checker/test/test_calc_max_search_length_for_boundaries.cpp
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,105 @@ | ||
// Copyright 2024 TIER IV, Inc. | ||
// | ||
// Licensed under the Apache License, Version 2.0 (the "License"); | ||
// you may not use this file except in compliance with the License. | ||
// You may obtain a copy of the License at | ||
// | ||
// http://www.apache.org/licenses/LICENSE-2.0 | ||
// | ||
// Unless required by applicable law or agreed to in writing, software | ||
// distributed under the License is distributed on an "AS IS" BASIS, | ||
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. | ||
// See the License for the specific language governing permissions and | ||
// limitations under the License. | ||
|
||
#include "autoware/lane_departure_checker/utils.hpp" | ||
|
||
#include <Eigen/Core> | ||
|
||
#include <gtest/gtest.h> | ||
|
||
using autoware_planning_msgs::msg::Trajectory; | ||
using autoware_planning_msgs::msg::TrajectoryPoint; | ||
|
||
namespace | ||
{ | ||
Trajectory create_trajectory(const std::vector<Eigen::Vector2d> & points) | ||
{ | ||
Trajectory trajectory; | ||
for (const auto & point : points) { | ||
TrajectoryPoint p; | ||
p.pose.position.x = point.x(); | ||
p.pose.position.y = point.y(); | ||
trajectory.points.push_back(p); | ||
} | ||
return trajectory; | ||
} | ||
|
||
// reference: | ||
// https://github.com/autowarefoundation/sample_vehicle_launch/blob/main/sample_vehicle_description/config/vehicle_info.param.yaml | ||
constexpr double wheel_radius_m = 0.383; | ||
constexpr double wheel_width_m = 0.235; | ||
constexpr double wheel_base_m = 2.79; | ||
constexpr double wheel_tread_m = 1.64; | ||
constexpr double front_overhang_m = 1.0; | ||
constexpr double rear_overhang_m = 1.1; | ||
constexpr double left_overhang_m = 0.128; | ||
constexpr double right_overhang_m = 0.128; | ||
constexpr double vehicle_height_m = 2.5; | ||
constexpr double max_steer_angle_rad = 0.70; | ||
} // namespace | ||
|
||
struct CalcMaxSearchLengthForBoundariesParam | ||
{ | ||
std::string description; | ||
std::vector<Eigen::Vector2d> trajectory_points; | ||
double expected_max_search_length; | ||
}; | ||
|
||
std::ostream & operator<<(std::ostream & os, const CalcMaxSearchLengthForBoundariesParam & p) | ||
{ | ||
return os << p.description; | ||
} | ||
|
||
class CalcMaxSearchLengthForBoundariesTest | ||
: public ::testing::TestWithParam<CalcMaxSearchLengthForBoundariesParam> | ||
{ | ||
protected: | ||
void SetUp() override | ||
{ | ||
vehicle_info = autoware::vehicle_info_utils::createVehicleInfo( | ||
wheel_radius_m, wheel_width_m, wheel_base_m, wheel_tread_m, front_overhang_m, rear_overhang_m, | ||
left_overhang_m, right_overhang_m, vehicle_height_m, max_steer_angle_rad); | ||
} | ||
|
||
autoware::vehicle_info_utils::VehicleInfo vehicle_info; | ||
}; | ||
|
||
TEST_P(CalcMaxSearchLengthForBoundariesTest, test_calc_max_search_length_for_boundaries) | ||
{ | ||
const auto p = GetParam(); | ||
const auto trajectory = create_trajectory(p.trajectory_points); | ||
|
||
const auto max_search_length = | ||
autoware::lane_departure_checker::utils::calcMaxSearchLengthForBoundaries( | ||
trajectory, vehicle_info); | ||
|
||
EXPECT_DOUBLE_EQ(max_search_length, p.expected_max_search_length); | ||
} | ||
|
||
INSTANTIATE_TEST_SUITE_P( | ||
LaneDepartureCheckerTest, CalcMaxSearchLengthForBoundariesTest, | ||
::testing::Values( | ||
CalcMaxSearchLengthForBoundariesParam{ | ||
"EmptyTrajectory", | ||
{}, | ||
std::hypot(front_overhang_m + wheel_base_m, wheel_tread_m / 2.0 + left_overhang_m)}, | ||
CalcMaxSearchLengthForBoundariesParam{ | ||
"SinglePointTrajectory", | ||
{{0.0, 0.0}}, | ||
std::hypot(front_overhang_m + wheel_base_m, wheel_tread_m / 2.0 + left_overhang_m)}, | ||
CalcMaxSearchLengthForBoundariesParam{ | ||
"MultiPointTrajectory", | ||
{{0.0, 0.0}, {1.0, 0.0}}, | ||
1.0 + std::hypot(front_overhang_m + wheel_base_m, wheel_tread_m / 2.0 + left_overhang_m)}), | ||
::testing::PrintToStringParamName()); |
98 changes: 98 additions & 0 deletions
98
control/autoware_lane_departure_checker/test/test_calc_trajectory_deviation.cpp
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,98 @@ | ||
// Copyright 2024 TIER IV, Inc. | ||
// | ||
// Licensed under the Apache License, Version 2.0 (the "License"); | ||
// you may not use this file except in compliance with the License. | ||
// You may obtain a copy of the License at | ||
// | ||
// http://www.apache.org/licenses/LICENSE-2.0 | ||
// | ||
// Unless required by applicable law or agreed to in writing, software | ||
// distributed under the License is distributed on an "AS IS" BASIS, | ||
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. | ||
// See the License for the specific language governing permissions and | ||
// limitations under the License. | ||
|
||
#include "autoware/lane_departure_checker/utils.hpp" | ||
|
||
#include <Eigen/Core> | ||
|
||
#include <gtest/gtest.h> | ||
|
||
using autoware::universe_utils::PoseDeviation; | ||
using autoware_planning_msgs::msg::Trajectory; | ||
using autoware_planning_msgs::msg::TrajectoryPoint; | ||
|
||
namespace | ||
{ | ||
Trajectory create_trajectory(const std::vector<Eigen::Vector2d> & points) | ||
{ | ||
Trajectory trajectory; | ||
for (const auto & point : points) { | ||
TrajectoryPoint p; | ||
p.pose.position.x = point.x(); | ||
p.pose.position.y = point.y(); | ||
trajectory.points.push_back(p); | ||
} | ||
return trajectory; | ||
} | ||
|
||
geometry_msgs::msg::Pose create_pose(const Eigen::Vector3d & x_y_yaw) | ||
{ | ||
geometry_msgs::msg::Pose pose; | ||
pose.position.x = x_y_yaw[0]; | ||
pose.position.y = x_y_yaw[1]; | ||
pose.orientation.z = std::sin(x_y_yaw[2] / 2); | ||
pose.orientation.w = std::cos(x_y_yaw[2] / 2); | ||
return pose; | ||
} | ||
|
||
constexpr double ego_nearest_dist_threshold = 3.0; | ||
constexpr double ego_nearest_yaw_threshold = 1.046; | ||
} // namespace | ||
|
||
struct CalcTrajectoryDeviationTestParam | ||
{ | ||
std::string description; | ||
std::vector<Eigen::Vector2d> trajectory_points; | ||
Eigen::Vector3d x_y_yaw; | ||
bool exception_expected; | ||
PoseDeviation expected_deviation; | ||
}; | ||
|
||
std::ostream & operator<<(std::ostream & os, const CalcTrajectoryDeviationTestParam & p) | ||
{ | ||
return os << p.description; | ||
} | ||
|
||
class CalcTrajectoryDeviationTest | ||
: public ::testing::TestWithParam<CalcTrajectoryDeviationTestParam> | ||
{ | ||
}; | ||
|
||
TEST_P(CalcTrajectoryDeviationTest, test_calc_trajectory_deviation) | ||
{ | ||
const auto p = GetParam(); | ||
const auto trajectory = create_trajectory(p.trajectory_points); | ||
const auto pose = create_pose(p.x_y_yaw); | ||
if (p.exception_expected) { | ||
EXPECT_ANY_THROW({ | ||
autoware::lane_departure_checker::utils::calcTrajectoryDeviation( | ||
trajectory, pose, ego_nearest_dist_threshold, ego_nearest_yaw_threshold); | ||
}); | ||
} else { | ||
const auto deviation = autoware::lane_departure_checker::utils::calcTrajectoryDeviation( | ||
trajectory, pose, ego_nearest_dist_threshold, ego_nearest_yaw_threshold); | ||
|
||
EXPECT_DOUBLE_EQ(deviation.lateral, p.expected_deviation.lateral); | ||
EXPECT_DOUBLE_EQ(deviation.longitudinal, p.expected_deviation.longitudinal); | ||
EXPECT_DOUBLE_EQ(deviation.yaw, p.expected_deviation.yaw); | ||
} | ||
} | ||
|
||
INSTANTIATE_TEST_SUITE_P( | ||
LaneDepartureCheckerTest, CalcTrajectoryDeviationTest, | ||
::testing::Values( | ||
CalcTrajectoryDeviationTestParam{"EmptyTrajectory", {}, {}, true, {}}, | ||
CalcTrajectoryDeviationTestParam{ | ||
"SinglePointTrajectory", {{0.0, 0.0}}, {0.0, 0.0, 0.0}, false, {0.0, 0.0, 0.0}}), | ||
::testing::PrintToStringParamName()); |