@@ -115,7 +115,7 @@ TEST(TestLongitudinalControllerUtils, getPitchByTraj)
115
115
{
116
116
using autoware_auto_planning_msgs::msg::Trajectory;
117
117
using autoware_auto_planning_msgs::msg::TrajectoryPoint;
118
- const double wheel_base = 0.9 ;
118
+ const double wheel_base = 1.0 ;
119
119
/* *
120
120
* Trajectory:
121
121
* 1 X
@@ -130,32 +130,30 @@ TEST(TestLongitudinalControllerUtils, getPitchByTraj)
130
130
point.pose .position .z = 0.0 ;
131
131
traj.points .push_back (point);
132
132
// non stopping trajectory: stop distance = trajectory length
133
- point.pose .position .x = 1.0 ;
133
+ point.pose .position .x = 0.6 ;
134
134
point.pose .position .y = 0.0 ;
135
- point.pose .position .z = 1.0 ;
135
+ point.pose .position .z = 0.8 ;
136
136
traj.points .push_back (point);
137
- point.pose .position .x = 2.0 ;
137
+ point.pose .position .x = 1.2 ;
138
138
point.pose .position .y = 0.0 ;
139
139
point.pose .position .z = 0.0 ;
140
140
traj.points .push_back (point);
141
- point.pose .position .x = 3.0 ;
141
+ point.pose .position .x = 1.8 ;
142
142
point.pose .position .y = 0.0 ;
143
- point.pose .position .z = 0.5 ;
143
+ point.pose .position .z = 0.8 ;
144
144
traj.points .push_back (point);
145
145
size_t closest_idx = 0 ;
146
146
EXPECT_DOUBLE_EQ (
147
- std::abs ( longitudinal_utils::getPitchByTraj (traj, closest_idx, wheel_base)), M_PI_4 );
147
+ longitudinal_utils::getPitchByTraj (traj, closest_idx, wheel_base), std::atan2 (- 0.8 , 0.6 ) );
148
148
closest_idx = 1 ;
149
149
EXPECT_DOUBLE_EQ (
150
- std::abs ( longitudinal_utils::getPitchByTraj (traj, closest_idx, wheel_base)), M_PI_4 );
150
+ longitudinal_utils::getPitchByTraj (traj, closest_idx, wheel_base), std::atan2 ( 0.8 , 0.6 ) );
151
151
closest_idx = 2 ;
152
152
EXPECT_DOUBLE_EQ (
153
- std::abs (longitudinal_utils::getPitchByTraj (traj, closest_idx, wheel_base)),
154
- std::atan2 (0.5 , 1 ));
153
+ longitudinal_utils::getPitchByTraj (traj, closest_idx, wheel_base), std::atan2 (-0.8 , 0.6 ));
155
154
closest_idx = 3 ;
156
155
EXPECT_DOUBLE_EQ (
157
- std::abs (longitudinal_utils::getPitchByTraj (traj, closest_idx, wheel_base)),
158
- std::atan2 (0.5 , 1 ));
156
+ longitudinal_utils::getPitchByTraj (traj, closest_idx, wheel_base), std::atan2 (-0.8 , 0.6 ));
159
157
}
160
158
161
159
TEST (TestLongitudinalControllerUtils, calcPoseAfterTimeDelay)
@@ -353,95 +351,113 @@ TEST(TestLongitudinalControllerUtils, lerpTrajectoryPoint)
353
351
TrajectoryPoint p;
354
352
p.pose .position .x = 0.0 ;
355
353
p.pose .position .y = 0.0 ;
354
+ p.pose .position .z = 0.0 ;
356
355
p.longitudinal_velocity_mps = 10.0 ;
357
356
p.acceleration_mps2 = 10.0 ;
358
357
points.push_back (p);
359
358
p.pose .position .x = 1.0 ;
360
359
p.pose .position .y = 0.0 ;
360
+ p.pose .position .z = 0.0 ;
361
361
p.longitudinal_velocity_mps = 20.0 ;
362
362
p.acceleration_mps2 = 20.0 ;
363
363
points.push_back (p);
364
364
p.pose .position .x = 1.0 ;
365
365
p.pose .position .y = 1.0 ;
366
+ p.pose .position .z = 1.0 ;
366
367
p.longitudinal_velocity_mps = 30.0 ;
367
368
p.acceleration_mps2 = 30.0 ;
368
369
points.push_back (p);
369
370
p.pose .position .x = 2.0 ;
370
371
p.pose .position .y = 1.0 ;
372
+ p.pose .position .z = 2.0 ;
371
373
p.longitudinal_velocity_mps = 40.0 ;
372
374
p.acceleration_mps2 = 40.0 ;
373
375
points.push_back (p);
374
- TrajectoryPoint result;
375
376
Pose pose;
376
377
double max_dist = 3.0 ;
377
378
double max_yaw = 0.7 ;
378
379
// Points on the trajectory gives back the original trajectory points values
379
380
pose.position .x = 0.0 ;
380
381
pose.position .y = 0.0 ;
381
- result = longitudinal_utils::lerpTrajectoryPoint (points, pose, max_dist, max_yaw);
382
- EXPECT_NEAR (result.pose .position .x , pose.position .x , abs_err);
383
- EXPECT_NEAR (result.pose .position .y , pose.position .y , abs_err);
384
- EXPECT_NEAR (result.longitudinal_velocity_mps , 10.0 , abs_err);
385
- EXPECT_NEAR (result.acceleration_mps2 , 10.0 , abs_err);
382
+ pose.position .z = 0.0 ;
383
+
384
+ auto result = longitudinal_utils::lerpTrajectoryPoint (points, pose, max_dist, max_yaw);
385
+ EXPECT_NEAR (result.first .pose .position .x , pose.position .x , abs_err);
386
+ EXPECT_NEAR (result.first .pose .position .y , pose.position .y , abs_err);
387
+ EXPECT_NEAR (result.first .pose .position .z , pose.position .z , abs_err);
388
+ EXPECT_NEAR (result.first .longitudinal_velocity_mps , 10.0 , abs_err);
389
+ EXPECT_NEAR (result.first .acceleration_mps2 , 10.0 , abs_err);
386
390
387
391
pose.position .x = 1.0 ;
388
392
pose.position .y = 0.0 ;
393
+ pose.position .z = 0.0 ;
389
394
result = longitudinal_utils::lerpTrajectoryPoint (points, pose, max_dist, max_yaw);
390
- EXPECT_NEAR (result.pose .position .x , pose.position .x , abs_err);
391
- EXPECT_NEAR (result.pose .position .y , pose.position .y , abs_err);
392
- EXPECT_NEAR (result.longitudinal_velocity_mps , 20.0 , abs_err);
393
- EXPECT_NEAR (result.acceleration_mps2 , 20.0 , abs_err);
395
+ EXPECT_NEAR (result.first .pose .position .x , pose.position .x , abs_err);
396
+ EXPECT_NEAR (result.first .pose .position .y , pose.position .y , abs_err);
397
+ EXPECT_NEAR (result.first .pose .position .z , pose.position .z , abs_err);
398
+ EXPECT_NEAR (result.first .longitudinal_velocity_mps , 20.0 , abs_err);
399
+ EXPECT_NEAR (result.first .acceleration_mps2 , 20.0 , abs_err);
394
400
395
401
pose.position .x = 1.0 ;
396
402
pose.position .y = 1.0 ;
403
+ pose.position .z = 1.0 ;
397
404
result = longitudinal_utils::lerpTrajectoryPoint (points, pose, max_dist, max_yaw);
398
- EXPECT_NEAR (result.pose .position .x , pose.position .x , abs_err);
399
- EXPECT_NEAR (result.pose .position .y , pose.position .y , abs_err);
400
- EXPECT_NEAR (result.longitudinal_velocity_mps , 30.0 , abs_err);
401
- EXPECT_NEAR (result.acceleration_mps2 , 30.0 , abs_err);
405
+ EXPECT_NEAR (result.first .pose .position .x , pose.position .x , abs_err);
406
+ EXPECT_NEAR (result.first .pose .position .y , pose.position .y , abs_err);
407
+ EXPECT_NEAR (result.first .pose .position .z , pose.position .z , abs_err);
408
+ EXPECT_NEAR (result.first .longitudinal_velocity_mps , 30.0 , abs_err);
409
+ EXPECT_NEAR (result.first .acceleration_mps2 , 30.0 , abs_err);
402
410
403
411
pose.position .x = 2.0 ;
404
412
pose.position .y = 1.0 ;
413
+ pose.position .z = 2.0 ;
405
414
result = longitudinal_utils::lerpTrajectoryPoint (points, pose, max_dist, max_yaw);
406
- EXPECT_NEAR (result.pose .position .x , pose.position .x , abs_err);
407
- EXPECT_NEAR (result.pose .position .y , pose.position .y , abs_err);
408
- EXPECT_NEAR (result.longitudinal_velocity_mps , 40.0 , abs_err);
409
- EXPECT_NEAR (result.acceleration_mps2 , 40.0 , abs_err);
415
+ EXPECT_NEAR (result.first .pose .position .x , pose.position .x , abs_err);
416
+ EXPECT_NEAR (result.first .pose .position .y , pose.position .y , abs_err);
417
+ EXPECT_NEAR (result.first .pose .position .z , pose.position .z , abs_err);
418
+ EXPECT_NEAR (result.first .longitudinal_velocity_mps , 40.0 , abs_err);
419
+ EXPECT_NEAR (result.first .acceleration_mps2 , 40.0 , abs_err);
410
420
411
421
// Interpolate between trajectory points
412
422
pose.position .x = 0.5 ;
413
423
pose.position .y = 0.0 ;
424
+ pose.position .z = 0.0 ;
414
425
result = longitudinal_utils::lerpTrajectoryPoint (points, pose, max_dist, max_yaw);
415
- EXPECT_NEAR (result.pose .position .x , pose.position .x , abs_err);
416
- EXPECT_NEAR (result.pose .position .y , pose.position .y , abs_err);
417
- EXPECT_NEAR (result.longitudinal_velocity_mps , 15.0 , abs_err);
418
- EXPECT_NEAR (result.acceleration_mps2 , 15.0 , abs_err);
426
+ EXPECT_NEAR (result.first .pose .position .x , pose.position .x , abs_err);
427
+ EXPECT_NEAR (result.first .pose .position .y , pose.position .y , abs_err);
428
+ EXPECT_NEAR (result.first .pose .position .z , pose.position .z , abs_err);
429
+ EXPECT_NEAR (result.first .longitudinal_velocity_mps , 15.0 , abs_err);
430
+ EXPECT_NEAR (result.first .acceleration_mps2 , 15.0 , abs_err);
419
431
pose.position .x = 0.75 ;
420
432
pose.position .y = 0.0 ;
433
+ pose.position .z = 0.0 ;
421
434
result = longitudinal_utils::lerpTrajectoryPoint (points, pose, max_dist, max_yaw);
422
435
423
- EXPECT_NEAR (result.pose .position .x , pose.position .x , abs_err);
424
- EXPECT_NEAR (result.pose .position .y , pose.position .y , abs_err);
425
- EXPECT_NEAR (result.longitudinal_velocity_mps , 17.5 , abs_err);
426
- EXPECT_NEAR (result.acceleration_mps2 , 17.5 , abs_err);
436
+ EXPECT_NEAR (result.first .pose .position .x , pose.position .x , abs_err);
437
+ EXPECT_NEAR (result.first .pose .position .y , pose.position .y , abs_err);
438
+ EXPECT_NEAR (result.first .pose .position .z , pose.position .z , abs_err);
439
+ EXPECT_NEAR (result.first .longitudinal_velocity_mps , 17.5 , abs_err);
440
+ EXPECT_NEAR (result.first .acceleration_mps2 , 17.5 , abs_err);
427
441
428
442
// Interpolate away from the trajectory (interpolated point is projected)
429
443
pose.position .x = 0.5 ;
430
444
pose.position .y = -1.0 ;
431
445
result = longitudinal_utils::lerpTrajectoryPoint (points, pose, max_dist, max_yaw);
432
- EXPECT_NEAR (result.pose .position .x , pose.position .x , abs_err);
433
- EXPECT_NEAR (result.pose .position .y , 0.0 , abs_err);
434
- EXPECT_NEAR (result.longitudinal_velocity_mps , 15.0 , abs_err);
435
- EXPECT_NEAR (result.acceleration_mps2 , 15.0 , abs_err);
446
+ EXPECT_NEAR (result.first .pose .position .x , pose.position .x , abs_err);
447
+ EXPECT_NEAR (result.first .pose .position .y , 0.0 , abs_err);
448
+ EXPECT_NEAR (result.first .pose .position .z , pose.position .z , abs_err);
449
+ EXPECT_NEAR (result.first .longitudinal_velocity_mps , 15.0 , abs_err);
450
+ EXPECT_NEAR (result.first .acceleration_mps2 , 15.0 , abs_err);
436
451
437
452
// Ambiguous projections: possibility with the lowest index is used
438
453
pose.position .x = 0.5 ;
439
454
pose.position .y = 0.5 ;
440
455
result = longitudinal_utils::lerpTrajectoryPoint (points, pose, max_dist, max_yaw);
441
- EXPECT_NEAR (result.pose .position .x , pose.position .x , abs_err);
442
- EXPECT_NEAR (result.pose .position .y , 0.0 , abs_err);
443
- EXPECT_NEAR (result.longitudinal_velocity_mps , 15.0 , abs_err);
444
- EXPECT_NEAR (result.acceleration_mps2 , 15.0 , abs_err);
456
+ EXPECT_NEAR (result.first .pose .position .x , pose.position .x , abs_err);
457
+ EXPECT_NEAR (result.first .pose .position .y , 0.0 , abs_err);
458
+ EXPECT_NEAR (result.first .pose .position .z , pose.position .z , abs_err);
459
+ EXPECT_NEAR (result.first .longitudinal_velocity_mps , 15.0 , abs_err);
460
+ EXPECT_NEAR (result.first .acceleration_mps2 , 15.0 , abs_err);
445
461
}
446
462
447
463
TEST (TestLongitudinalControllerUtils, applyDiffLimitFilter)
0 commit comments