From 4bfbd7ced822e3bb52fe7f6f446fad65bcb215f4 Mon Sep 17 00:00:00 2001 From: Jason Shuler Date: Wed, 3 Aug 2022 18:52:12 -0400 Subject: [PATCH] GM: parse low and manumatic gears (#24764) * Switch to ECMPRDNL2 for GM gear * Removing manumatic gear # * formatting * update refs * update refs * line Co-authored-by: Shane Smiskol --- selfdrive/car/gm/carstate.py | 17 +++++++++++------ selfdrive/car/gm/interface.py | 5 ++++- selfdrive/test/process_replay/ref_commit | 2 +- 3 files changed, 16 insertions(+), 8 deletions(-) diff --git a/selfdrive/car/gm/carstate.py b/selfdrive/car/gm/carstate.py index c28abc6036..b174d0327e 100644 --- a/selfdrive/car/gm/carstate.py +++ b/selfdrive/car/gm/carstate.py @@ -12,7 +12,7 @@ class CarState(CarStateBase): def __init__(self, CP): super().__init__(CP) can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) - self.shifter_values = can_define.dv["ECMPRDNL"]["PRNDL"] + self.shifter_values = can_define.dv["ECMPRDNL2"]["PRNDL2"] self.lka_steering_cmd_counter = 0 def update(self, pt_cp, loopback_cp): @@ -30,7 +30,11 @@ class CarState(CarStateBase): ret.vEgoRaw = mean([ret.wheelSpeeds.fl, ret.wheelSpeeds.fr, ret.wheelSpeeds.rl, ret.wheelSpeeds.rr]) ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) ret.standstill = ret.vEgoRaw < 0.01 - ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(pt_cp.vl["ECMPRDNL"]["PRNDL"], None)) + + if pt_cp.vl["ECMPRDNL2"]["ManualMode"] == 1: + ret.gearShifter = self.parse_gear_shifter("T") + else: + ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(pt_cp.vl["ECMPRDNL2"]["PRNDL2"], None)) # Brake pedal's potentiometer returns near-zero reading even when pedal is not pressed. ret.brake = pt_cp.vl["EBCMBrakePedalPosition"]["BrakePedalPosition"] / 0xd0 @@ -97,7 +101,8 @@ class CarState(CarStateBase): ("FRWheelSpd", "EBCMWheelSpdFront"), ("RLWheelSpd", "EBCMWheelSpdRear"), ("RRWheelSpd", "EBCMWheelSpdRear"), - ("PRNDL", "ECMPRDNL"), + ("PRNDL2", "ECMPRDNL2"), + ("ManualMode", "ECMPRDNL2"), ("LKADriverAppldTrq", "PSCMStatus"), ("LKATorqueDelivered", "PSCMStatus"), ("LKATorqueDeliveredStatus", "PSCMStatus"), @@ -108,7 +113,7 @@ class CarState(CarStateBase): checks = [ ("BCMTurnSignals", 1), - ("ECMPRDNL", 10), + ("ECMPRDNL2", 10), ("PSCMStatus", 10), ("ESPStatus", 10), ("BCMDoorBeltStatus", 10), @@ -135,9 +140,9 @@ class CarState(CarStateBase): ] checks = [ - ("ASCMLKASteeringCmd", 10), # 10 Hz is the stock inactive rate (every 100ms). + ("ASCMLKASteeringCmd", 10), # 10 Hz is the stock inactive rate (every 100ms). # While active 50 Hz (every 20 ms) is normal - # EPS will tolerate around 200ms when active before faulting + # EPS will tolerate around 200ms when active before faulting ] return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, CanBus.LOOPBACK) diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py index bdb42f97e2..ab6581201b 100755 --- a/selfdrive/car/gm/interface.py +++ b/selfdrive/car/gm/interface.py @@ -9,6 +9,7 @@ from selfdrive.car.interfaces import CarInterfaceBase ButtonType = car.CarState.ButtonEvent.Type EventName = car.CarEvent.EventName +GearShifter = car.CarState.GearShifter TransmissionType = car.CarParams.TransmissionType NetworkLocation = car.CarParams.NetworkLocation BUTTONS_DICT = {CruiseButtons.RES_ACCEL: ButtonType.accelCruise, CruiseButtons.DECEL_SET: ButtonType.decelCruise, @@ -165,7 +166,9 @@ class CarInterface(CarInterfaceBase): ret.buttonEvents = [be] - events = self.create_common_events(ret, pcm_enable=self.CP.pcmCruise) + events = self.create_common_events(ret, extra_gears=[GearShifter.sport, GearShifter.low, + GearShifter.eco, GearShifter.manumatic], + pcm_enable=self.CP.pcmCruise) if ret.vEgo < self.CP.minEnableSpeed: events.add(EventName.belowEngageSpeed) diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit index d1c0ef985e..0cf6711727 100644 --- a/selfdrive/test/process_replay/ref_commit +++ b/selfdrive/test/process_replay/ref_commit @@ -1 +1 @@ -6d9bd0e80ccdf39827bded1883adbc922224bdf1 +82d3f0a3bfe07a76983e7e4603a0553d077ba15b \ No newline at end of file