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

feat(pid_longitudinal_controller)!: add acceleration feedback block #8325

Merged
merged 8 commits into from
Aug 27, 2024
Merged
Show file tree
Hide file tree
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 @@ -61,6 +61,10 @@
emergency_acc: -5.0 # denotes acceleration
emergency_jerk: -3.0

# acceleration feedback
lpf_acc_error_gain: 0.98
acc_feedback_gain: 0.0

# acceleration limit
max_acc: 3.0
min_acc: -5.0
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,10 @@ class DebugValues
STOP_DIST = 28,
FF_SCALE = 29,
ACC_CMD_FF = 30,
ERROR_ACC = 31,
ERROR_ACC_FILTERED = 32,
ACC_CMD_ACC_FB_APPLIED = 33,

SIZE // this is the number of enum elements
};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -61,6 +61,8 @@
m_x = ret;
return ret;
}

void setGain(const double g) { m_gain = g; }

Check warning on line 65 in control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/lowpass_filter.hpp

View check run for this annotation

Codecov / codecov/patch

control/autoware_pid_longitudinal_controller/include/autoware/pid_longitudinal_controller/lowpass_filter.hpp#L65

Added line #L65 was not covered by tests
};
} // namespace autoware::motion::control::pid_longitudinal_controller
#endif // AUTOWARE__PID_LONGITUDINAL_CONTROLLER__LOWPASS_FILTER_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -196,6 +196,10 @@ class PidLongitudinalController : public trajectory_follower::LongitudinalContro
};
EmergencyStateParams m_emergency_state_params;

// acc feedback
double m_acc_feedback_gain;
std::shared_ptr<LowpassFilter1d> m_lpf_acc_error{nullptr};

// acceleration limit
double m_max_acc;
double m_min_acc;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -251,6 +251,16 @@
"description": "target jerk in an EMERGENCY state [m/s^3]",
"default": "-3.0"
},
"lpf_acc_error_gain": {
"type": "number",
"description": "gain of low-pass filter for acceleration",
"default": "0.98"
},
"acc_feedback_gain": {
"type": "number",
"description": "acceleration feedback gain",
"default": "0.0"
},
"max_acc": {
"type": "number",
"description": "max value of output acceleration [m/s^2]",
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -164,6 +164,13 @@
p.jerk = node.declare_parameter<double>("emergency_jerk"); // [m/s^3]
}

// parameters for acc feedback
{
const double lpf_acc_error_gain{node.declare_parameter<double>("lpf_acc_error_gain")};
m_lpf_acc_error = std::make_shared<LowpassFilter1d>(0.0, lpf_acc_error_gain);
m_acc_feedback_gain = node.declare_parameter<double>("acc_feedback_gain");
}

// parameters for acceleration limit
m_max_acc = node.declare_parameter<double>("max_acc"); // [m/s^2]
m_min_acc = node.declare_parameter<double>("min_acc"); // [m/s^2]
Expand Down Expand Up @@ -291,6 +298,10 @@
update_param("kd", kd);
m_pid_vel.setGains(kp, ki, kd);

double lpf_vel_error_gain{node_parameters_->get_parameter("lpf_vel_error_gain").as_double()};
update_param("lpf_vel_error_gain", lpf_vel_error_gain);
m_lpf_vel_error->setGain(lpf_vel_error_gain);

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

View check run for this annotation

Codecov / codecov/patch

control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp#L303

Added line #L303 was not covered by tests

double max_pid{node_parameters_->get_parameter("max_out").as_double()};
double min_pid{node_parameters_->get_parameter("min_out").as_double()};
double max_p{node_parameters_->get_parameter("max_p_effort").as_double()};
Expand Down Expand Up @@ -365,6 +376,12 @@
update_param("emergency_jerk", p.jerk);
}

// acceleration feedback
update_param("acc_feedback_gain", m_acc_feedback_gain);
double lpf_acc_error_gain{node_parameters_->get_parameter("lpf_acc_error_gain").as_double()};
update_param("lpf_acc_error_gain", lpf_acc_error_gain);
m_lpf_acc_error->setGain(lpf_acc_error_gain);

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

View check run for this annotation

Codecov / codecov/patch

control/autoware_pid_longitudinal_controller/src/pid_longitudinal_controller.cpp#L383

Added line #L383 was not covered by tests

Check warning on line 384 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: Large Method

PidLongitudinalController::paramCallback increases from 111 to 118 lines of code, threshold = 70. Large functions with many lines of code are generally harder to understand and lower the code health. Avoid adding more lines to this function.
// acceleration limit
update_param("min_acc", m_min_acc);

Expand Down Expand Up @@ -753,6 +770,7 @@

m_pid_vel.reset();
m_lpf_vel_error->reset(0.0);
m_lpf_acc_error->reset(0.0);

Check notice on line 773 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 138 to 139. 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.
return changeState(ControlState::DRIVE);
}

Expand Down Expand Up @@ -844,8 +862,22 @@
// store acceleration without slope compensation
m_prev_raw_ctrl_cmd = raw_ctrl_cmd;

// calc acc feedback
const double acc_err = control_data.current_motion.acc - raw_ctrl_cmd.acc;
m_debug_values.setValues(DebugValues::TYPE::ERROR_ACC, acc_err);
m_lpf_acc_error->filter(acc_err);
m_debug_values.setValues(DebugValues::TYPE::ERROR_ACC_FILTERED, m_lpf_acc_error->getValue());

const double acc_cmd = raw_ctrl_cmd.acc - m_lpf_acc_error->getValue() * m_acc_feedback_gain;
m_debug_values.setValues(DebugValues::TYPE::ACC_CMD_ACC_FB_APPLIED, acc_cmd);
RCLCPP_DEBUG(
logger_,
"[acc feedback]: raw_ctrl_cmd.acc: %1.3f, control_data.current_motion.acc: %1.3f, acc_cmd: "
"%1.3f",
raw_ctrl_cmd.acc, control_data.current_motion.acc, acc_cmd);

ctrl_cmd_as_pedal_pos.acc =
applySlopeCompensation(raw_ctrl_cmd.acc, control_data.slope_angle, control_data.shift);
applySlopeCompensation(acc_cmd, control_data.slope_angle, control_data.shift);

Check warning on line 880 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: Large Method

PidLongitudinalController::calcCtrlCmd has 80 lines, threshold = 70. Large functions with many lines of code are generally harder to understand and lower the code health. Avoid adding more lines to this function.
m_debug_values.setValues(DebugValues::TYPE::ACC_CMD_SLOPE_APPLIED, ctrl_cmd_as_pedal_pos.acc);
ctrl_cmd_as_pedal_pos.vel = raw_ctrl_cmd.vel;
}
Expand Down
Loading
Loading