Skip to content

Commit

Permalink
dry steering
Browse files Browse the repository at this point in the history
Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
  • Loading branch information
takayuki5168 committed Jul 8, 2024
1 parent b17e42e commit cf552f6
Show file tree
Hide file tree
Showing 3 changed files with 38 additions and 27 deletions.
2 changes: 1 addition & 1 deletion control/autoware_mpc_lateral_controller/src/mpc.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -766,7 +766,7 @@ VectorXd MPC::calcSteerRateLimitOnTrajectory(
};

// when the vehicle is stopped, no steering rate limit.
constexpr double steer_rate_lim = 5.0;
constexpr double steer_rate_lim = 100.0;
const bool is_vehicle_stopped = std::fabs(current_velocity) < 0.01;
if (is_vehicle_stopped) {
return steer_rate_lim * VectorXd::Ones(m_param.prediction_horizon);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -234,6 +234,8 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro
// debug values
DebugValues m_debug_values;

std::optional<bool> m_prev_keep_stopped_condition{std::nullopt};

std::shared_ptr<rclcpp::Time> m_last_running_time{std::make_shared<rclcpp::Time>(clock_->now())};

// Diagnostic
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -599,21 +599,6 @@ void PidLongitudinalController::updateControlState(const ControlData & control_d
// NOTE: the same velocity threshold as autoware::motion_utils::searchZeroVelocity
static constexpr double vel_epsilon = 1e-3;

// Let vehicle start after the steering is converged for control accuracy
const bool keep_stopped_condition = std::fabs(current_vel) < vel_epsilon &&
m_enable_keep_stopped_until_steer_convergence &&
!lateral_sync_data_.is_steer_converged;
if (keep_stopped_condition) {
auto marker = createDefaultMarker(
"map", clock_->now(), "stop_reason", 0, Marker::TEXT_VIEW_FACING,
createMarkerScale(0.0, 0.0, 1.0), createMarkerColor(1.0, 1.0, 1.0, 0.999));
marker.pose = autoware::universe_utils::calcOffsetPose(
m_current_kinematic_state.pose.pose, m_wheel_base + m_front_overhang,
m_vehicle_width / 2 + 2.0, 1.5);
marker.text = "steering not\nconverged";
m_pub_stop_reason_marker->publish(marker);
}

const bool stopping_condition = stop_dist < p.stopping_state_stop_dist;

const bool is_stopped = std::abs(current_vel) < p.stopped_state_entry_vel &&
Expand Down Expand Up @@ -672,15 +657,18 @@ void PidLongitudinalController::updateControlState(const ControlData & control_d
m_under_control_starting_time =
is_under_control ? std::make_shared<rclcpp::Time>(clock_->now()) : nullptr;
}

if (m_control_state != ControlState::STOPPED) {
m_prev_keep_stopped_condition = std::nullopt;
}

// transit state
// in DRIVE state
if (m_control_state == ControlState::DRIVE) {
if (emergency_condition) {
return changeState(ControlState::EMERGENCY);
}
if (!is_under_control && stopped_condition && keep_stopped_condition) {
// NOTE: When the ego is stopped on manual driving, since the driving state may transit to
// autonomous, keep_stopped_condition should be checked.
if (!is_under_control && stopped_condition) {

Check notice on line 671 in control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ No longer an issue: Complex Conditional

PidLongitudinalController::updateControlState no longer has a complex conditional
return changeState(ControlState::STOPPED);
}

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

// in STOPPED state
if (m_control_state == ControlState::STOPPED) {
// -- debug print --
// debug print
if (has_nonzero_target_vel && !departure_condition_from_stopped) {
debug_msg_once("target speed > 0, but departure condition is not met. Keep STOPPED.");
}
if (has_nonzero_target_vel && keep_stopped_condition) {
debug_msg_once("target speed > 0, but keep stop condition is met. Keep STOPPED.");
}
// ---------------

if (keep_stopped_condition) {
return changeState(ControlState::STOPPED);
}
if (departure_condition_from_stopped) {
// Let vehicle start after the steering is converged for dry steering
const bool current_keep_stopped_condition = std::fabs(current_vel) < vel_epsilon &&
m_enable_keep_stopped_until_steer_convergence &&
!lateral_sync_data_.is_steer_converged;
const bool keep_stopped_condition =
!m_prev_keep_stopped_condition ||
(current_keep_stopped_condition || *m_prev_keep_stopped_condition);
m_prev_keep_stopped_condition = current_keep_stopped_condition;
if (keep_stopped_condition) {
// debug print
if (has_nonzero_target_vel) {
debug_msg_once("target speed > 0, but keep stop condition is met. Keep STOPPED.");
}

// publish debug marker
auto marker = createDefaultMarker(
"map", clock_->now(), "stop_reason", 0, Marker::TEXT_VIEW_FACING,
createMarkerScale(0.0, 0.0, 1.0), createMarkerColor(1.0, 1.0, 1.0, 0.999));
marker.pose = autoware::universe_utils::calcOffsetPose(
m_current_kinematic_state.pose.pose, m_wheel_base + m_front_overhang,
m_vehicle_width / 2 + 2.0, 1.5);
marker.text = "steering not\nconverged";
m_pub_stop_reason_marker->publish(marker);

// keep STOPPED
return;
}

Check warning on line 747 in control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

PidLongitudinalController::updateControlState already has high cyclomatic complexity, and now it increases in Lines of Code from 137 to 142. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.

Check warning on line 747 in control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Bumpy Road Ahead

PidLongitudinalController::updateControlState increases from 9 to 10 logical blocks with deeply nested code, threshold is one single block per function. The Bumpy Road code smell is a function that contains multiple chunks of nested conditional logic. The deeper the nesting and the more bumps, the lower the code health.

Check warning on line 747 in control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Deep, Nested Complexity

PidLongitudinalController::updateControlState has a nested complexity depth of 4, threshold = 4. This function contains deeply nested logic such as if statements and/or loops. The deeper the nesting, the lower the code health.
m_pid_vel.reset();
m_lpf_vel_error->reset(0.0);
// prevent the car from taking a long time to start to move
Expand Down

0 comments on commit cf552f6

Please sign in to comment.