Skip to content

Commit ddbe1e8

Browse files
authored
Merge pull request #1772 from tier4/fix/lateral-controller-unstable-steering-command_v0.29.0-1
fix(mpc_lateral_controller): prevent unstable steering command while stopped v0.29.0 1
2 parents d46ec36 + d5e08bb commit ddbe1e8

File tree

1 file changed

+24
-15
lines changed

1 file changed

+24
-15
lines changed

control/autoware_mpc_lateral_controller/src/mpc_lateral_controller.cpp

+24-15
Original file line numberDiff line numberDiff line change
@@ -399,11 +399,18 @@ Lateral MpcLateralController::getInitialControlCommand() const
399399

400400
bool MpcLateralController::isStoppedState() const
401401
{
402+
const double current_vel = m_current_kinematic_state.twist.twist.linear.x;
402403
// If the nearest index is not found, return false
403-
if (m_current_trajectory.points.empty()) {
404+
if (
405+
m_current_trajectory.points.empty() || std::fabs(current_vel) > m_stop_state_entry_ego_speed) {
404406
return false;
405407
}
406408

409+
const auto latest_published_cmd = m_ctrl_cmd_prev; // use prev_cmd as a latest published command
410+
if (m_keep_steer_control_until_converged && !isSteerConverged(latest_published_cmd)) {
411+
return false; // not stopState: keep control
412+
}
413+
407414
// Note: This function used to take into account the distance to the stop line
408415
// for the stop state judgement. However, it has been removed since the steering
409416
// control was turned off when approaching/exceeding the stop line on a curve or
@@ -412,21 +419,23 @@ bool MpcLateralController::isStoppedState() const
412419
m_current_trajectory.points, m_current_kinematic_state.pose.pose, m_ego_nearest_dist_threshold,
413420
m_ego_nearest_yaw_threshold);
414421

415-
const double current_vel = m_current_kinematic_state.twist.twist.linear.x;
416-
const double target_vel = m_current_trajectory.points.at(nearest).longitudinal_velocity_mps;
417-
418-
const auto latest_published_cmd = m_ctrl_cmd_prev; // use prev_cmd as a latest published command
419-
if (m_keep_steer_control_until_converged && !isSteerConverged(latest_published_cmd)) {
420-
return false; // not stopState: keep control
421-
}
422+
// It is possible that stop is executed earlier than stop point, and velocity controller
423+
// will not start when the distance from ego to stop point is less than 0.5 meter.
424+
// So we use a distance margin to ensure we can detect stopped state.
425+
static constexpr double distance_margin = 1.0;
426+
const double target_vel = std::invoke([&]() -> double {
427+
auto min_vel = m_current_trajectory.points.at(nearest).longitudinal_velocity_mps;
428+
auto covered_distance = 0.0;
429+
for (auto i = nearest + 1; i < m_current_trajectory.points.size(); ++i) {
430+
min_vel = std::min(min_vel, m_current_trajectory.points.at(i).longitudinal_velocity_mps);
431+
covered_distance += autoware::universe_utils::calcDistance2d(
432+
m_current_trajectory.points.at(i - 1).pose, m_current_trajectory.points.at(i).pose);
433+
if (covered_distance > distance_margin) break;
434+
}
435+
return min_vel;
436+
});
422437

423-
if (
424-
std::fabs(current_vel) < m_stop_state_entry_ego_speed &&
425-
std::fabs(target_vel) < m_stop_state_entry_target_speed) {
426-
return true;
427-
} else {
428-
return false;
429-
}
438+
return std::fabs(target_vel) < m_stop_state_entry_target_speed;
430439
}
431440

432441
Lateral MpcLateralController::createCtrlCmdMsg(const Lateral & ctrl_cmd)

0 commit comments

Comments
 (0)