Fix pre-enable engagement on GM (#348)

In 2017 Volts, PCM fault occurs for a few seconds if ACC gas
is commanded while user presses gas pedal. PID winds up,
and when PCM fault clears, car gets a "max gas" jolt.

In 2018 Volts, PCM fault doesn't time out, which means pre-enable
doesn't work at all, and car would slowly decelerate, while openpilot
thinks it's engaged.
old-commit-hash: 9653f9d6a6
commatwo_master
Vasily Tarasov 7 years ago committed by rbiasini
parent e07d32c790
commit d63ae5c7d0
  1. 6
      selfdrive/car/gm/interface.py

@ -325,7 +325,11 @@ class CarInterface(object):
"chimeRepeated": (CM.LOW_CHIME, -1),
"chimeContinuous": (CM.LOW_CHIME, -1)}[str(c.hudControl.audibleAlert)]
self.CC.update(self.sendcan, c.enabled, self.CS, self.frame, \
# For Openpilot, "enabled" includes pre-enable.
# In GM, PCM faults out if ACC command overlaps user gas.
enabled = c.enabled and not self.CS.user_gas_pressed
self.CC.update(self.sendcan, enabled, self.CS, self.frame, \
c.actuators,
hud_v_cruise, c.hudControl.lanesVisible, \
c.hudControl.leadVisible, \

Loading…
Cancel
Save