Skip to content

Commit db952af

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

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
@@ -1037,6 +1037,8 @@ PidLongitudinalController::StateAfterDelay PidLongitudinalController::predictedS
10371037
double PidLongitudinalController::applyVelocityFeedback(const ControlData & control_data)
10381038
{
10391039
// NOTE: Acceleration command is always positive even if the ego drives backward.
1040+
const double nearest_target_vel =
1041+
control_data.interpolated_traj.points.at(control_data.nearest_idx).longitudinal_velocity_mps;
10401042
const double vel_sign = (control_data.shift == Shift::Forward)
10411043
? 1.0
10421044
: (control_data.shift == Shift::Reverse ? -1.0 : 0.0);
@@ -1071,7 +1073,9 @@ double PidLongitudinalController::applyVelocityFeedback(const ControlData & cont
10711073
constexpr double ff_scale_max = 2.0; // for safety
10721074
constexpr double ff_scale_min = 0.5; // for safety
10731075
const double ff_scale = std::clamp(
1074-
std::abs(current_vel) / std::max(std::abs(target_motion.vel), 0.1), ff_scale_min, ff_scale_max);
1076+
1.0 + (abs(nearest_target_vel - current_vel) / std::max(abs(current_vel), 0.1)), ff_scale_min,
1077+
ff_scale_max);
1078+
10751079
const double ff_acc =
10761080
control_data.interpolated_traj.points.at(control_data.target_idx).acceleration_mps2 * ff_scale;
10771081

0 commit comments

Comments
 (0)