Skip to content

Commit

Permalink
fix(autoware_mpc_lateral_controller): relax the steering rate constra…
Browse files Browse the repository at this point in the history
…int at zero speed (#7581)

* constraint for zero velocity updated

Signed-off-by: Zhe Shen <[email protected]>

* correct the comment

Signed-off-by: Zhe Shen <[email protected]>

---------

Signed-off-by: Zhe Shen <[email protected]>
  • Loading branch information
HansOersted authored Jun 21, 2024
1 parent e90d356 commit eb00776
Showing 1 changed file with 2 additions and 1 deletion.
3 changes: 2 additions & 1 deletion control/autoware_mpc_lateral_controller/src/mpc.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -766,9 +766,10 @@ VectorXd MPC::calcSteerRateLimitOnTrajectory(
};

// when the vehicle is stopped, no steering rate limit.
constexpr double steer_rate_lim = 5.0;
const bool is_vehicle_stopped = std::fabs(current_velocity) < 0.01;
if (is_vehicle_stopped) {
return VectorXd::Zero(m_param.prediction_horizon);
return steer_rate_lim * VectorXd::Ones(m_param.prediction_horizon);
}

// calculate steering rate limit
Expand Down

0 comments on commit eb00776

Please sign in to comment.