@@ -599,21 +599,6 @@ void PidLongitudinalController::updateControlState(const ControlData & control_d
599
599
// NOTE: the same velocity threshold as autoware::motion_utils::searchZeroVelocity
600
600
static constexpr double vel_epsilon = 1e-3 ;
601
601
602
- // Let vehicle start after the steering is converged for control accuracy
603
- const bool keep_stopped_condition = std::fabs (current_vel) < vel_epsilon &&
604
- m_enable_keep_stopped_until_steer_convergence &&
605
- !lateral_sync_data_.is_steer_converged ;
606
- if (keep_stopped_condition) {
607
- auto marker = createDefaultMarker (
608
- " map" , clock_->now (), " stop_reason" , 0 , Marker::TEXT_VIEW_FACING,
609
- createMarkerScale (0.0 , 0.0 , 1.0 ), createMarkerColor (1.0 , 1.0 , 1.0 , 0.999 ));
610
- marker.pose = autoware::universe_utils::calcOffsetPose (
611
- m_current_kinematic_state.pose .pose , m_wheel_base + m_front_overhang,
612
- m_vehicle_width / 2 + 2.0 , 1.5 );
613
- marker.text = " steering not\n converged" ;
614
- m_pub_stop_reason_marker->publish (marker);
615
- }
616
-
617
602
const bool stopping_condition = stop_dist < p.stopping_state_stop_dist ;
618
603
619
604
const bool is_stopped = std::abs (current_vel) < p.stopped_state_entry_vel &&
@@ -672,15 +657,18 @@ void PidLongitudinalController::updateControlState(const ControlData & control_d
672
657
m_under_control_starting_time =
673
658
is_under_control ? std::make_shared<rclcpp::Time>(clock_->now ()) : nullptr ;
674
659
}
660
+
661
+ if (m_control_state != ControlState::STOPPED) {
662
+ m_prev_keep_stopped_condition = std::nullopt;
663
+ }
664
+
675
665
// transit state
676
666
// in DRIVE state
677
667
if (m_control_state == ControlState::DRIVE) {
678
668
if (emergency_condition) {
679
669
return changeState (ControlState::EMERGENCY);
680
670
}
681
- if (!is_under_control && stopped_condition && keep_stopped_condition) {
682
- // NOTE: When the ego is stopped on manual driving, since the driving state may transit to
683
- // autonomous, keep_stopped_condition should be checked.
671
+ if (!is_under_control && stopped_condition) {
684
672
return changeState (ControlState::STOPPED);
685
673
}
686
674
@@ -723,19 +711,40 @@ void PidLongitudinalController::updateControlState(const ControlData & control_d
723
711
724
712
// in STOPPED state
725
713
if (m_control_state == ControlState::STOPPED) {
726
- // -- debug print --
714
+ // debug print
727
715
if (has_nonzero_target_vel && !departure_condition_from_stopped) {
728
716
debug_msg_once (" target speed > 0, but departure condition is not met. Keep STOPPED." );
729
717
}
730
- if (has_nonzero_target_vel && keep_stopped_condition) {
731
- debug_msg_once (" target speed > 0, but keep stop condition is met. Keep STOPPED." );
732
- }
733
- // ---------------
734
718
735
- if (keep_stopped_condition) {
736
- return changeState (ControlState::STOPPED);
737
- }
738
719
if (departure_condition_from_stopped) {
720
+ // Let vehicle start after the steering is converged for dry steering
721
+ const bool current_keep_stopped_condition = std::fabs (current_vel) < vel_epsilon &&
722
+ m_enable_keep_stopped_until_steer_convergence &&
723
+ !lateral_sync_data_.is_steer_converged ;
724
+ const bool keep_stopped_condition =
725
+ !m_prev_keep_stopped_condition ||
726
+ (current_keep_stopped_condition || *m_prev_keep_stopped_condition);
727
+ m_prev_keep_stopped_condition = current_keep_stopped_condition;
728
+ if (keep_stopped_condition) {
729
+ // debug print
730
+ if (has_nonzero_target_vel) {
731
+ debug_msg_once (" target speed > 0, but keep stop condition is met. Keep STOPPED." );
732
+ }
733
+
734
+ // publish debug marker
735
+ auto marker = createDefaultMarker (
736
+ " map" , clock_->now (), " stop_reason" , 0 , Marker::TEXT_VIEW_FACING,
737
+ createMarkerScale (0.0 , 0.0 , 1.0 ), createMarkerColor (1.0 , 1.0 , 1.0 , 0.999 ));
738
+ marker.pose = autoware::universe_utils::calcOffsetPose (
739
+ m_current_kinematic_state.pose .pose , m_wheel_base + m_front_overhang,
740
+ m_vehicle_width / 2 + 2.0 , 1.5 );
741
+ marker.text = " steering not\n converged" ;
742
+ m_pub_stop_reason_marker->publish (marker);
743
+
744
+ // keep STOPPED
745
+ return ;
746
+ }
747
+
739
748
m_pid_vel.reset ();
740
749
m_lpf_vel_error->reset (0.0 );
741
750
// prevent the car from taking a long time to start to move
0 commit comments