@@ -432,11 +432,18 @@ Lateral MpcLateralController::getInitialControlCommand() const
432
432
433
433
bool MpcLateralController::isStoppedState () const
434
434
{
435
+ const double current_vel = m_current_kinematic_state.twist .twist .linear .x ;
435
436
// If the nearest index is not found, return false
436
- if (m_current_trajectory.points .empty ()) {
437
+ if (
438
+ m_current_trajectory.points .empty () || std::fabs (current_vel) > m_stop_state_entry_ego_speed) {
437
439
return false ;
438
440
}
439
441
442
+ const auto latest_published_cmd = m_ctrl_cmd_prev; // use prev_cmd as a latest published command
443
+ if (m_keep_steer_control_until_converged && !isSteerConverged (latest_published_cmd)) {
444
+ return false ; // not stopState: keep control
445
+ }
446
+
440
447
// Note: This function used to take into account the distance to the stop line
441
448
// for the stop state judgement. However, it has been removed since the steering
442
449
// control was turned off when approaching/exceeding the stop line on a curve or
@@ -445,21 +452,23 @@ bool MpcLateralController::isStoppedState() const
445
452
m_current_trajectory.points , m_current_kinematic_state.pose .pose , m_ego_nearest_dist_threshold,
446
453
m_ego_nearest_yaw_threshold);
447
454
448
- const double current_vel = m_current_kinematic_state.twist .twist .linear .x ;
449
- const double target_vel = m_current_trajectory.points .at (nearest).longitudinal_velocity_mps ;
450
-
451
- const auto latest_published_cmd = m_ctrl_cmd_prev; // use prev_cmd as a latest published command
452
- if (m_keep_steer_control_until_converged && !isSteerConverged (latest_published_cmd)) {
453
- return false ; // not stopState: keep control
454
- }
455
+ // It is possible that stop is executed earlier than stop point, and velocity controller
456
+ // will not start when the distance from ego to stop point is less than 0.5 meter.
457
+ // So we use a distance margin to ensure we can detect stopped state.
458
+ static constexpr double distance_margin = 1.0 ;
459
+ const double target_vel = std::invoke ([&]() -> double {
460
+ auto min_vel = m_current_trajectory.points .at (nearest).longitudinal_velocity_mps ;
461
+ auto covered_distance = 0.0 ;
462
+ for (auto i = nearest + 1 ; i < m_current_trajectory.points .size (); ++i) {
463
+ min_vel = std::min (min_vel, m_current_trajectory.points .at (i).longitudinal_velocity_mps );
464
+ covered_distance += autoware::universe_utils::calcDistance2d (
465
+ m_current_trajectory.points .at (i - 1 ).pose , m_current_trajectory.points .at (i).pose );
466
+ if (covered_distance > distance_margin) break ;
467
+ }
468
+ return min_vel;
469
+ });
455
470
456
- if (
457
- std::fabs (current_vel) < m_stop_state_entry_ego_speed &&
458
- std::fabs (target_vel) < m_stop_state_entry_target_speed) {
459
- return true ;
460
- } else {
461
- return false ;
462
- }
471
+ return std::fabs (target_vel) < m_stop_state_entry_target_speed;
463
472
}
464
473
465
474
Lateral MpcLateralController::createCtrlCmdMsg (const Lateral & ctrl_cmd)
0 commit comments