Skip to content

Commit 13f73fe

Browse files
committed
feat(pid_longitudinal_controller): improve FF gain constant calculation
Signed-off-by: Berkay Karaman <brkay54@gmail.com>
1 parent c5325a8 commit 13f73fe

File tree

1 file changed

+5
-2
lines changed

1 file changed

+5
-2
lines changed

control/pid_longitudinal_controller/src/pid_longitudinal_controller.cpp

+5-2
Original file line numberDiff line numberDiff line change
@@ -981,7 +981,8 @@ double PidLongitudinalController::applyVelocityFeedback(const ControlData & cont
981981
const double current_vel = control_data.current_motion.vel;
982982
const double target_vel =
983983
control_data.interpolated_traj.points.at(control_data.target_idx).longitudinal_velocity_mps;
984-
984+
const double nearest_target_vel =
985+
control_data.interpolated_traj.points.at(control_data.nearest_idx).longitudinal_velocity_mps;
985986
const double vel_after_delay = control_data.state_after_delay.vel;
986987
const bool is_under_control =
987988
m_current_operation_mode.is_autoware_control_enabled &&
@@ -1010,7 +1011,9 @@ double PidLongitudinalController::applyVelocityFeedback(const ControlData & cont
10101011
constexpr double ff_scale_max = 2.0; // for safety
10111012
constexpr double ff_scale_min = 0.5; // for safety
10121013
const double ff_scale = std::clamp(
1013-
std::abs(current_vel) / std::max(std::abs(target_vel), 0.1), ff_scale_min, ff_scale_max);
1014+
1.0 + (abs(nearest_target_vel - current_vel) / std::max(abs(current_vel), 0.1)), ff_scale_min,
1015+
ff_scale_max);
1016+
10141017
const double ff_acc =
10151018
control_data.interpolated_traj.points.at(control_data.target_idx).acceleration_mps2 * ff_scale;
10161019

0 commit comments

Comments
 (0)