Skip to content

Commit eef298b

Browse files
authored
feat(mpc_lateral_controller): remove trans/rot deviation validation since the control_validator has the same feature (#9684)
Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
1 parent f87d732 commit eef298b

File tree

6 files changed

+7
-63
lines changed

6 files changed

+7
-63
lines changed

control/autoware_mpc_lateral_controller/README.md

+5-7
Original file line numberDiff line numberDiff line change
@@ -95,13 +95,11 @@ AutonomouStuff Lexus RX 450h for under 40 km/h driving.
9595

9696
#### System
9797

98-
| Name | Type | Description | Default value |
99-
| :------------------------ | :------ | :-------------------------------------------------------------------------- | :------------ |
100-
| traj_resample_dist | double | distance of waypoints in resampling [m] | 0.1 |
101-
| use_steer_prediction | boolean | flag for using steer prediction (do not use steer measurement) | false |
102-
| admissible_position_error | double | stop vehicle when following position error is larger than this value [m] | 5.0 |
103-
| admissible_yaw_error_rad | double | stop vehicle when following yaw angle error is larger than this value [rad] | 1.57 |
104-
| use_delayed_initial_state | boolean | flag to use x0_delayed as initial state for predicted trajectory | true |
98+
| Name | Type | Description | Default value |
99+
| :------------------------ | :------ | :--------------------------------------------------------------- | :------------ |
100+
| traj_resample_dist | double | distance of waypoints in resampling [m] | 0.1 |
101+
| use_steer_prediction | boolean | flag for using steer prediction (do not use steer measurement) | false |
102+
| use_delayed_initial_state | boolean | flag to use x0_delayed as initial state for predicted trajectory | true |
105103

106104
#### Path Smoothing
107105

control/autoware_mpc_lateral_controller/include/autoware/mpc_lateral_controller/mpc.hpp

+2-4
Original file line numberDiff line numberDiff line change
@@ -421,10 +421,8 @@ class MPC
421421
double m_raw_steer_cmd_prev = 0.0; // Previous MPC raw output.
422422

423423
/* Parameters for control */
424-
double m_admissible_position_error; // Threshold for lateral error to trigger stop command [m].
425-
double m_admissible_yaw_error_rad; // Threshold for yaw error to trigger stop command [rad].
426-
double m_steer_lim; // Steering command limit [rad].
427-
double m_ctrl_period; // Control frequency [s].
424+
double m_steer_lim; // Steering command limit [rad].
425+
double m_ctrl_period; // Control frequency [s].
428426

429427
//!< @brief steering rate limit list depending on curvature [/m], [rad/s]
430428
std::vector<std::pair<double, double>> m_steer_rate_lim_map_by_curvature{};

control/autoware_mpc_lateral_controller/param/lateral_controller_defaults.param.yaml

-2
Original file line numberDiff line numberDiff line change
@@ -3,8 +3,6 @@
33
# -- system --
44
traj_resample_dist: 0.1 # path resampling interval [m]
55
use_steer_prediction: false # flag for using steer prediction (do not use steer measurement)
6-
admissible_position_error: 5.0 # stop mpc calculation when error is larger than the following value
7-
admissible_yaw_error_rad: 1.57 # stop mpc calculation when error is larger than the following value
86
use_delayed_initial_state: true # flag to use x0_delayed as initial state for predicted trajectory
97

108
# -- path smoothing --

control/autoware_mpc_lateral_controller/src/mpc.cpp

-11
Original file line numberDiff line numberDiff line change
@@ -307,17 +307,6 @@ std::pair<ResultWithReason, MPCData> MPC::getData(
307307
// get predicted steer
308308
data.predicted_steer = m_steering_predictor->calcSteerPrediction();
309309

310-
// check error limit
311-
const double dist_err = calcDistance2d(current_pose, data.nearest_pose);
312-
if (dist_err > m_admissible_position_error) {
313-
return {ResultWithReason{false, "too large position error"}, MPCData{}};
314-
}
315-
316-
// check yaw error limit
317-
if (std::fabs(data.yaw_err) > m_admissible_yaw_error_rad) {
318-
return {ResultWithReason{false, "too large yaw error"}, MPCData{}};
319-
}
320-
321310
// check trajectory time length
322311
const double max_prediction_time =
323312
m_param.min_prediction_length / static_cast<double>(m_param.prediction_horizon - 1);

control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp

-2
Original file line numberDiff line numberDiff line change
@@ -57,8 +57,6 @@ MpcLateralController::MpcLateralController(
5757
p_filt.traj_resample_dist = dp_double("traj_resample_dist");
5858
p_filt.extend_trajectory_for_end_yaw_control = dp_bool("extend_trajectory_for_end_yaw_control");
5959

60-
m_mpc->m_admissible_position_error = dp_double("admissible_position_error");
61-
m_mpc->m_admissible_yaw_error_rad = dp_double("admissible_yaw_error_rad");
6260
m_mpc->m_use_steer_prediction = dp_bool("use_steer_prediction");
6361
m_mpc->m_param.steer_tau = dp_double("vehicle_model_steer_tau");
6462

control/autoware_mpc_lateral_controller/test/test_mpc.cpp

-37
Original file line numberDiff line numberDiff line change
@@ -96,8 +96,6 @@ class MPCTest : public ::testing::Test
9696
double error_deriv_lpf_cutoff_hz = 5.0;
9797

9898
// Test Parameters
99-
double admissible_position_error = 5.0;
100-
double admissible_yaw_error_rad = M_PI_2;
10199
double steer_lim = 0.610865; // 35 degrees
102100
double steer_rate_lim = 2.61799; // 150 degrees
103101
double ctrl_period = 0.03;
@@ -162,8 +160,6 @@ class MPCTest : public ::testing::Test
162160
void initializeMPC(mpc_lateral_controller::MPC & mpc)
163161
{
164162
mpc.m_param = param;
165-
mpc.m_admissible_position_error = admissible_position_error;
166-
mpc.m_admissible_yaw_error_rad = admissible_yaw_error_rad;
167163
mpc.m_steer_lim = steer_lim;
168164
mpc.m_steer_rate_lim_map_by_curvature.emplace_back(0.0, steer_rate_lim);
169165
mpc.m_steer_rate_lim_map_by_velocity.emplace_back(0.0, steer_rate_lim);
@@ -480,37 +476,4 @@ TEST_F(MPCTest, MultiSolveWithBuffer)
480476
EXPECT_EQ(ctrl_cmd_horizon.controls.front().steering_tire_angle, 0.0f);
481477
EXPECT_EQ(ctrl_cmd_horizon.controls.front().steering_tire_rotation_rate, 0.0f);
482478
}
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-
}
516479
} // namespace autoware::motion::control::mpc_lateral_controller

0 commit comments

Comments
 (0)