Skip to content

Commit 30ac90d

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

File tree

1 file changed

+5
-1
lines changed

1 file changed

+5
-1
lines changed

control/pid_longitudinal_controller/src/pid_longitudinal_controller.cpp

+5-1
Original file line numberDiff line numberDiff line change
@@ -1039,6 +1039,8 @@ PidLongitudinalController::StateAfterDelay PidLongitudinalController::predictedS
10391039
double PidLongitudinalController::applyVelocityFeedback(const ControlData & control_data)
10401040
{
10411041
// NOTE: Acceleration command is always positive even if the ego drives backward.
1042+
const double nearest_target_vel =
1043+
control_data.interpolated_traj.points.at(control_data.nearest_idx).longitudinal_velocity_mps;
10421044
const double vel_sign = (control_data.shift == Shift::Forward)
10431045
? 1.0
10441046
: (control_data.shift == Shift::Reverse ? -1.0 : 0.0);
@@ -1073,7 +1075,9 @@ double PidLongitudinalController::applyVelocityFeedback(const ControlData & cont
10731075
constexpr double ff_scale_max = 2.0; // for safety
10741076
constexpr double ff_scale_min = 0.5; // for safety
10751077
const double ff_scale = std::clamp(
1076-
std::abs(current_vel) / std::max(std::abs(target_motion.vel), 0.1), ff_scale_min, ff_scale_max);
1078+
1.0 + (abs(nearest_target_vel - current_vel) / std::max(abs(current_vel), 0.1)), ff_scale_min,
1079+
ff_scale_max);
1080+
10771081
const double ff_acc =
10781082
control_data.interpolated_traj.points.at(control_data.target_idx).acceleration_mps2 * ff_scale;
10791083

0 commit comments

Comments
 (0)