|
27 | 27 |
|
28 | 28 | constexpr double epsilon = 1e-6;
|
29 | 29 |
|
| 30 | +using autoware::behavior_path_planner::utils::path_safety_checker::calcInterpolatedPoseWithVelocity; |
30 | 31 | using autoware::behavior_path_planner::utils::path_safety_checker::CollisionCheckDebug;
|
| 32 | +using autoware::behavior_path_planner::utils::path_safety_checker::PoseWithVelocityStamped; |
| 33 | +using autoware::universe_utils::createPoint; |
| 34 | +using autoware::universe_utils::createQuaternionFromRPY; |
31 | 35 | using autoware::universe_utils::Point2d;
|
32 | 36 | using autoware::universe_utils::Polygon2d;
|
33 | 37 | using autoware_perception_msgs::msg::Shape;
|
34 | 38 | using geometry_msgs::msg::Point;
|
35 | 39 | using geometry_msgs::msg::Pose;
|
36 | 40 | using geometry_msgs::msg::Twist;
|
37 | 41 |
|
| 42 | +geometry_msgs::msg::Pose createPose( |
| 43 | + double x, double y, double z, double roll, double pitch, double yaw) |
| 44 | +{ |
| 45 | + geometry_msgs::msg::Pose p; |
| 46 | + p.position = createPoint(x, y, z); |
| 47 | + p.orientation = createQuaternionFromRPY(roll, pitch, yaw); |
| 48 | + return p; |
| 49 | +} |
| 50 | + |
| 51 | +std::vector<PoseWithVelocityStamped> createTestPath() |
| 52 | +{ |
| 53 | + std::vector<PoseWithVelocityStamped> path; |
| 54 | + path.emplace_back(0.0, createPose(0.0, 0.0, 0.0, 0.0, 0.0, 0.0), 1.0); |
| 55 | + path.emplace_back(1.0, createPose(1.0, 0.0, 0.0, 0.0, 0.0, 0.0), 2.0); |
| 56 | + path.emplace_back(2.0, createPose(2.0, 0.0, 0.0, 0.0, 0.0, 0.0), 3.0); |
| 57 | + return path; |
| 58 | +} |
| 59 | + |
38 | 60 | TEST(BehaviorPathPlanningSafetyUtilsTest, createExtendedEgoPolygon)
|
39 | 61 | {
|
40 | 62 | using autoware::behavior_path_planner::utils::path_safety_checker::createExtendedPolygon;
|
@@ -207,3 +229,74 @@ TEST(BehaviorPathPlanningSafetyUtilsTest, calcRssDistance)
|
207 | 229 | EXPECT_NEAR(calcRssDistance(front_vel, rear_vel, params), 63.75, epsilon);
|
208 | 230 | }
|
209 | 231 | }
|
| 232 | + |
| 233 | +// Basic interpolation test |
| 234 | +TEST(CalcInterpolatedPoseWithVelocityTest, BasicInterpolation) |
| 235 | +{ |
| 236 | + auto path = createTestPath(); |
| 237 | + auto result = calcInterpolatedPoseWithVelocity(path, 0.5); |
| 238 | + |
| 239 | + ASSERT_TRUE(result.has_value()); |
| 240 | + EXPECT_NEAR(result->time, 0.5, 1e-6); |
| 241 | + EXPECT_NEAR(result->pose.position.x, 0.5, 1e-6); |
| 242 | + EXPECT_NEAR(result->velocity, 1.5, 1e-6); |
| 243 | +} |
| 244 | + |
| 245 | +// Boundary conditions test |
| 246 | +TEST(CalcInterpolatedPoseWithVelocityTest, BoundaryConditions) |
| 247 | +{ |
| 248 | + auto path = createTestPath(); |
| 249 | + |
| 250 | + // First point of the path |
| 251 | + auto start_result = calcInterpolatedPoseWithVelocity(path, 0.0); |
| 252 | + ASSERT_TRUE(start_result.has_value()); |
| 253 | + EXPECT_NEAR(start_result->time, 0.0, 1e-6); |
| 254 | + EXPECT_NEAR(start_result->pose.position.x, 0.0, 1e-6); |
| 255 | + EXPECT_NEAR(start_result->velocity, 1.0, 1e-6); |
| 256 | + |
| 257 | + // Last point of the path |
| 258 | + auto end_result = calcInterpolatedPoseWithVelocity(path, 2.0); |
| 259 | + ASSERT_TRUE(end_result.has_value()); |
| 260 | + EXPECT_NEAR(end_result->time, 2.0, 1e-6); |
| 261 | + EXPECT_NEAR(end_result->pose.position.x, 2.0, 1e-6); |
| 262 | + EXPECT_NEAR(end_result->velocity, 3.0, 1e-6); |
| 263 | +} |
| 264 | + |
| 265 | +// Invalid input test |
| 266 | +TEST(CalcInterpolatedPoseWithVelocityTest, InvalidInput) |
| 267 | +{ |
| 268 | + auto path = createTestPath(); |
| 269 | + |
| 270 | + // Empty path |
| 271 | + EXPECT_FALSE(calcInterpolatedPoseWithVelocity({}, 1.0).has_value()); |
| 272 | + |
| 273 | + // Negative relative time |
| 274 | + EXPECT_FALSE(calcInterpolatedPoseWithVelocity(path, -1.0).has_value()); |
| 275 | + |
| 276 | + // Relative time greater than the last time in the path |
| 277 | + EXPECT_FALSE(calcInterpolatedPoseWithVelocity(path, 3.0).has_value()); |
| 278 | +} |
| 279 | + |
| 280 | +// Special cases test |
| 281 | +TEST(CalcInterpolatedPoseWithVelocityTest, DISABLED_SpecialCases) |
| 282 | +{ |
| 283 | + // Case with consecutive points at the same time |
| 284 | + std::vector<PoseWithVelocityStamped> same_time_path; |
| 285 | + same_time_path.emplace_back(0.0, createPose(0.0, 0.0, 0.0, 0.0, 0.0, 0.0), 1.0); |
| 286 | + same_time_path.emplace_back(0.0, createPose(1.0, 0.0, 0.0, 0.0, 0.0, 0.0), 2.0); |
| 287 | + same_time_path.emplace_back(1.0, createPose(2.0, 0.0, 0.0, 0.0, 0.0, 0.0), 3.0); |
| 288 | + |
| 289 | + auto same_time_result = calcInterpolatedPoseWithVelocity(same_time_path, 0.0); |
| 290 | + ASSERT_TRUE(same_time_result.has_value()); |
| 291 | + EXPECT_NEAR(same_time_result->pose.position.x, 0.0, 1e-6); |
| 292 | + EXPECT_NEAR(same_time_result->velocity, 1.0, 1e-6); |
| 293 | + |
| 294 | + // Case with reversed time order |
| 295 | + std::vector<PoseWithVelocityStamped> reverse_time_path; |
| 296 | + reverse_time_path.emplace_back(2.0, createPose(0.0, 0.0, 0.0, 0.0, 0.0, 0.0), 1.0); |
| 297 | + reverse_time_path.emplace_back(1.0, createPose(1.0, 0.0, 0.0, 0.0, 0.0, 0.0), 2.0); |
| 298 | + reverse_time_path.emplace_back(0.0, createPose(2.0, 0.0, 0.0, 0.0, 0.0, 0.0), 3.0); |
| 299 | + |
| 300 | + auto reverse_time_result = calcInterpolatedPoseWithVelocity(reverse_time_path, 1.5); |
| 301 | + ASSERT_FALSE(reverse_time_result.has_value()); |
| 302 | +} |
0 commit comments