Skip to content

Commit

Permalink
Long control: Double delay is super complicated (commaai#32694)
Browse files Browse the repository at this point in the history
* Double delay is super complicated

* No more upper bound

* DEAD

* Update ref
  • Loading branch information
haraschax authored Jun 11, 2024
1 parent 3e33207 commit 9654151
Show file tree
Hide file tree
Showing 8 changed files with 11 additions and 19 deletions.
4 changes: 2 additions & 2 deletions cereal/car.capnp
Original file line number Diff line number Diff line change
Expand Up @@ -490,8 +490,7 @@ struct CarParams {
startingState @70 :Bool; # Does this car make use of special starting state

steerActuatorDelay @36 :Float32; # Steering wheel actuator delay in seconds
longitudinalActuatorDelayLowerBound @61 :Float32; # Gas/Brake actuator delay in seconds, lower bound
longitudinalActuatorDelayUpperBound @58 :Float32; # Gas/Brake actuator delay in seconds, upper bound
longitudinalActuatorDelay @58 :Float32; # Gas/Brake actuator delay in seconds
openpilotLongitudinalControl @37 :Bool; # is openpilot doing the longitudinal control?
carVin @38 :Text; # VIN number queried during fingerprinting
dashcamOnly @41: Bool;
Expand Down Expand Up @@ -703,4 +702,5 @@ struct CarParams {
brakeMaxVDEPRECATED @16 :List(Float32);
directAccelControlDEPRECATED @30 :Bool;
maxSteeringAngleDegDEPRECATED @54 :Float32;
longitudinalActuatorDelayLowerBoundDEPRECATEDDEPRECATED @61 :Float32;
}
2 changes: 1 addition & 1 deletion selfdrive/car/gm/interface.py
Original file line number Diff line number Diff line change
Expand Up @@ -148,7 +148,7 @@ def _get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs):

ret.steerLimitTimer = 0.4
ret.radarTimeStep = 0.0667 # GM radar runs at 15Hz instead of standard 20Hz
ret.longitudinalActuatorDelayUpperBound = 0.5 # large delay to initially start braking
ret.longitudinalActuatorDelay = 0.5 # large delay to initially start braking

if candidate == CAR.CHEVROLET_VOLT:
ret.lateralTuning.pid.kpBP = [0., 40.]
Expand Down
2 changes: 1 addition & 1 deletion selfdrive/car/honda/interface.py
Original file line number Diff line number Diff line change
Expand Up @@ -74,7 +74,7 @@ def _get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs):
if candidate in HONDA_BOSCH:
ret.longitudinalTuning.kpV = [0.25]
ret.longitudinalTuning.kiV = [0.05]
ret.longitudinalActuatorDelayUpperBound = 0.5 # s
ret.longitudinalActuatorDelay = 0.5 # s
if candidate in HONDA_BOSCH_RADARLESS:
ret.stopAccel = CarControllerParams.BOSCH_ACCEL_MIN # stock uses -4.0 m/s^2 once stopped but limited by safety model
else:
Expand Down
3 changes: 1 addition & 2 deletions selfdrive/car/hyundai/interface.py
Original file line number Diff line number Diff line change
Expand Up @@ -94,8 +94,7 @@ def _get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs):
ret.startingState = True
ret.vEgoStarting = 0.1
ret.startAccel = 1.0
ret.longitudinalActuatorDelayLowerBound = 0.5
ret.longitudinalActuatorDelayUpperBound = 0.5
ret.longitudinalActuatorDelay = 0.5

# *** feature detection ***
if candidate in CANFD_CAR:
Expand Down
3 changes: 1 addition & 2 deletions selfdrive/car/interfaces.py
Original file line number Diff line number Diff line change
Expand Up @@ -210,8 +210,7 @@ def get_std_params(candidate):
ret.longitudinalTuning.kiBP = [0.]
ret.longitudinalTuning.kiV = [1.]
# TODO estimate car specific lag, use .15s for now
ret.longitudinalActuatorDelayLowerBound = 0.15
ret.longitudinalActuatorDelayUpperBound = 0.15
ret.longitudinalActuatorDelay = 0.15
ret.steerLimitTimer = 1.0
return ret

Expand Down
2 changes: 1 addition & 1 deletion selfdrive/car/tesla/interface.py
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ def _get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs):
ret.longitudinalTuning.kpV = [0]
ret.longitudinalTuning.kiBP = [0]
ret.longitudinalTuning.kiV = [0]
ret.longitudinalActuatorDelayUpperBound = 0.5 # s
ret.longitudinalActuatorDelay = 0.5 # s
ret.radarTimeStep = (1.0 / 8) # 8Hz

# Check if we have messages on an auxiliary panda, and that 0x2bf (DAS_control) is present on the AP powertrain bus
Expand Down
12 changes: 3 additions & 9 deletions selfdrive/controls/lib/longcontrol.py
Original file line number Diff line number Diff line change
Expand Up @@ -73,16 +73,10 @@ def update(self, active, CS, long_plan, accel_limits, t_since_plan):
v_target_now = interp(t_since_plan, CONTROL_N_T_IDX, speeds)
a_target_now = interp(t_since_plan, CONTROL_N_T_IDX, long_plan.accels)

v_target_lower = interp(self.CP.longitudinalActuatorDelayLowerBound + t_since_plan, CONTROL_N_T_IDX, speeds)
a_target_lower = 2 * (v_target_lower - v_target_now) / self.CP.longitudinalActuatorDelayLowerBound - a_target_now
v_target = interp(self.CP.longitudinalActuatorDelay + t_since_plan, CONTROL_N_T_IDX, speeds)
a_target = 2 * (v_target - v_target_now) / self.CP.longitudinalActuatorDelay - a_target_now

v_target_upper = interp(self.CP.longitudinalActuatorDelayUpperBound + t_since_plan, CONTROL_N_T_IDX, speeds)
a_target_upper = 2 * (v_target_upper - v_target_now) / self.CP.longitudinalActuatorDelayUpperBound - a_target_now

v_target = min(v_target_lower, v_target_upper)
a_target = min(a_target_lower, a_target_upper)

v_target_1sec = interp(self.CP.longitudinalActuatorDelayUpperBound + t_since_plan + 1.0, CONTROL_N_T_IDX, speeds)
v_target_1sec = interp(self.CP.longitudinalActuatorDelay + t_since_plan + 1.0, CONTROL_N_T_IDX, speeds)
else:
v_target = 0.0
v_target_now = 0.0
Expand Down
2 changes: 1 addition & 1 deletion selfdrive/test/process_replay/ref_commit
Original file line number Diff line number Diff line change
@@ -1 +1 @@
e536df5586a71b22baa789dc584d7eab67f1fbbb
0ba779ec9f624872b1d038acb15095b726ff8983

0 comments on commit 9654151

Please sign in to comment.