Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix(mpc_lateral_controller): prevent unstable steering command while stopped #1709

Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -399,11 +399,18 @@ Lateral MpcLateralController::getInitialControlCommand() const

bool MpcLateralController::isStoppedState() const
{
const double current_vel = m_current_kinematic_state.twist.twist.linear.x;
// If the nearest index is not found, return false
if (m_current_trajectory.points.empty()) {
if (
m_current_trajectory.points.empty() || std::fabs(current_vel) > m_stop_state_entry_ego_speed) {
return false;
}

const auto latest_published_cmd = m_ctrl_cmd_prev; // use prev_cmd as a latest published command
if (m_keep_steer_control_until_converged && !isSteerConverged(latest_published_cmd)) {
return false; // not stopState: keep control
}

// Note: This function used to take into account the distance to the stop line
// for the stop state judgement. However, it has been removed since the steering
// control was turned off when approaching/exceeding the stop line on a curve or
Expand All @@ -412,21 +419,23 @@ bool MpcLateralController::isStoppedState() const
m_current_trajectory.points, m_current_kinematic_state.pose.pose, m_ego_nearest_dist_threshold,
m_ego_nearest_yaw_threshold);

const double current_vel = m_current_kinematic_state.twist.twist.linear.x;
const double target_vel = m_current_trajectory.points.at(nearest).longitudinal_velocity_mps;

const auto latest_published_cmd = m_ctrl_cmd_prev; // use prev_cmd as a latest published command
if (m_keep_steer_control_until_converged && !isSteerConverged(latest_published_cmd)) {
return false; // not stopState: keep control
}
// It is possible that stop is executed earlier than stop point, and velocity controller
// will not start when the distance from ego to stop point is less than 0.5 meter.
// So we use a distance margin to ensure we can detect stopped state.
static constexpr double distance_margin = 1.0;
const double target_vel = std::invoke([&]() -> double {
auto min_vel = m_current_trajectory.points.at(nearest).longitudinal_velocity_mps;
auto covered_distance = 0.0;
for (auto i = nearest + 1; i < m_current_trajectory.points.size(); ++i) {
min_vel = std::min(min_vel, m_current_trajectory.points.at(i).longitudinal_velocity_mps);
covered_distance += autoware::universe_utils::calcDistance2d(
m_current_trajectory.points.at(i - 1).pose, m_current_trajectory.points.at(i).pose);
if (covered_distance > distance_margin) break;
}
return min_vel;
});

if (
std::fabs(current_vel) < m_stop_state_entry_ego_speed &&
std::fabs(target_vel) < m_stop_state_entry_target_speed) {
return true;
} else {
return false;
}
return std::fabs(target_vel) < m_stop_state_entry_target_speed;
}

Lateral MpcLateralController::createCtrlCmdMsg(const Lateral & ctrl_cmd)
Expand Down
Loading