@@ -96,8 +96,6 @@ class MPCTest : public ::testing::Test
96
96
double error_deriv_lpf_cutoff_hz = 5.0 ;
97
97
98
98
// Test Parameters
99
- double admissible_position_error = 5.0 ;
100
- double admissible_yaw_error_rad = M_PI_2;
101
99
double steer_lim = 0.610865 ; // 35 degrees
102
100
double steer_rate_lim = 2.61799 ; // 150 degrees
103
101
double ctrl_period = 0.03 ;
@@ -162,8 +160,6 @@ class MPCTest : public ::testing::Test
162
160
void initializeMPC (mpc_lateral_controller::MPC & mpc)
163
161
{
164
162
mpc.m_param = param;
165
- mpc.m_admissible_position_error = admissible_position_error;
166
- mpc.m_admissible_yaw_error_rad = admissible_yaw_error_rad;
167
163
mpc.m_steer_lim = steer_lim;
168
164
mpc.m_steer_rate_lim_map_by_curvature .emplace_back (0.0 , steer_rate_lim);
169
165
mpc.m_steer_rate_lim_map_by_velocity .emplace_back (0.0 , steer_rate_lim);
@@ -480,37 +476,4 @@ TEST_F(MPCTest, MultiSolveWithBuffer)
480
476
EXPECT_EQ (ctrl_cmd_horizon.controls .front ().steering_tire_angle , 0 .0f );
481
477
EXPECT_EQ (ctrl_cmd_horizon.controls .front ().steering_tire_rotation_rate , 0 .0f );
482
478
}
483
-
484
- TEST_F (MPCTest, FailureCases)
485
- {
486
- auto node = rclcpp::Node (" mpc_test_node" , rclcpp::NodeOptions{});
487
- auto mpc = std::make_unique<MPC>(node);
488
- std::shared_ptr<VehicleModelInterface> vehicle_model_ptr =
489
- std::make_shared<KinematicsBicycleModel>(wheelbase, steer_limit, steer_tau);
490
- mpc->setVehicleModel (vehicle_model_ptr);
491
- std::shared_ptr<QPSolverInterface> qpsolver_ptr = std::make_shared<QPSolverEigenLeastSquareLLT>();
492
- mpc->setQPSolver (qpsolver_ptr);
493
-
494
- // Init parameters and reference trajectory
495
- initializeMPC (*mpc);
496
-
497
- // Calculate MPC with a pose too far from the trajectory
498
- Pose pose_far;
499
- pose_far.position .x = pose_zero.position .x - admissible_position_error - 1.0 ;
500
- pose_far.position .y = pose_zero.position .y - admissible_position_error - 1.0 ;
501
- Lateral ctrl_cmd;
502
- Trajectory pred_traj;
503
- Float32MultiArrayStamped diag;
504
- LateralHorizon ctrl_cmd_horizon;
505
- const auto odom = makeOdometry (pose_far, default_velocity);
506
- EXPECT_FALSE (
507
- mpc->calculateMPC (neutral_steer, odom, ctrl_cmd, pred_traj, diag, ctrl_cmd_horizon).result );
508
-
509
- // Calculate MPC with a fast velocity to make the prediction go further than the reference path
510
- EXPECT_FALSE (mpc
511
- ->calculateMPC (
512
- neutral_steer, makeOdometry (pose_far, default_velocity + 10.0 ), ctrl_cmd,
513
- pred_traj, diag, ctrl_cmd_horizon)
514
- .result );
515
- }
516
479
} // namespace autoware::motion::control::mpc_lateral_controller
0 commit comments