Skip to content

Commit cf552f6

Browse files
committed
dry steering
Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
1 parent b17e42e commit cf552f6

File tree

3 files changed

+38
-27
lines changed

3 files changed

+38
-27
lines changed

control/autoware_mpc_lateral_controller/src/mpc.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -766,7 +766,7 @@ VectorXd MPC::calcSteerRateLimitOnTrajectory(
766766
};
767767

768768
// when the vehicle is stopped, no steering rate limit.
769-
constexpr double steer_rate_lim = 5.0;
769+
constexpr double steer_rate_lim = 100.0;
770770
const bool is_vehicle_stopped = std::fabs(current_velocity) < 0.01;
771771
if (is_vehicle_stopped) {
772772
return steer_rate_lim * VectorXd::Ones(m_param.prediction_horizon);

control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/pid_longitudinal_controller.hpp

+2
Original file line numberDiff line numberDiff line change
@@ -234,6 +234,8 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro
234234
// debug values
235235
DebugValues m_debug_values;
236236

237+
std::optional<bool> m_prev_keep_stopped_condition{std::nullopt};
238+
237239
std::shared_ptr<rclcpp::Time> m_last_running_time{std::make_shared<rclcpp::Time>(clock_->now())};
238240

239241
// Diagnostic

control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp

+35-26
Original file line numberDiff line numberDiff line change
@@ -599,21 +599,6 @@ void PidLongitudinalController::updateControlState(const ControlData & control_d
599599
// NOTE: the same velocity threshold as autoware::motion_utils::searchZeroVelocity
600600
static constexpr double vel_epsilon = 1e-3;
601601

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\nconverged";
614-
m_pub_stop_reason_marker->publish(marker);
615-
}
616-
617602
const bool stopping_condition = stop_dist < p.stopping_state_stop_dist;
618603

619604
const bool is_stopped = std::abs(current_vel) < p.stopped_state_entry_vel &&
@@ -672,15 +657,18 @@ void PidLongitudinalController::updateControlState(const ControlData & control_d
672657
m_under_control_starting_time =
673658
is_under_control ? std::make_shared<rclcpp::Time>(clock_->now()) : nullptr;
674659
}
660+
661+
if (m_control_state != ControlState::STOPPED) {
662+
m_prev_keep_stopped_condition = std::nullopt;
663+
}
664+
675665
// transit state
676666
// in DRIVE state
677667
if (m_control_state == ControlState::DRIVE) {
678668
if (emergency_condition) {
679669
return changeState(ControlState::EMERGENCY);
680670
}
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) {
684672
return changeState(ControlState::STOPPED);
685673
}
686674

@@ -723,19 +711,40 @@ void PidLongitudinalController::updateControlState(const ControlData & control_d
723711

724712
// in STOPPED state
725713
if (m_control_state == ControlState::STOPPED) {
726-
// -- debug print --
714+
// debug print
727715
if (has_nonzero_target_vel && !departure_condition_from_stopped) {
728716
debug_msg_once("target speed > 0, but departure condition is not met. Keep STOPPED.");
729717
}
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-
// ---------------
734718

735-
if (keep_stopped_condition) {
736-
return changeState(ControlState::STOPPED);
737-
}
738719
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\nconverged";
742+
m_pub_stop_reason_marker->publish(marker);
743+
744+
// keep STOPPED
745+
return;
746+
}
747+
739748
m_pid_vel.reset();
740749
m_lpf_vel_error->reset(0.0);
741750
// prevent the car from taking a long time to start to move

0 commit comments

Comments
 (0)