From 0589ea0dbec5e3d25ed4498257eb162d656780bb Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Fri, 7 Jun 2024 22:10:35 -0700 Subject: [PATCH 01/15] move car interfaces to opendbc --- car/body/__init__.py | 0 car/body/bodycan.py | 7 + car/body/carcontroller.py | 84 + car/body/carstate.py | 40 + car/body/fingerprints.py | 28 + car/body/interface.py | 39 + car/body/radar_interface.py | 4 + car/body/values.py | 40 + car/chrysler/__init__.py | 0 car/chrysler/carcontroller.py | 85 ++ car/chrysler/carstate.py | 156 ++ car/chrysler/chryslercan.py | 71 + car/chrysler/fingerprints.py | 705 +++++++++ car/chrysler/interface.py | 97 ++ car/chrysler/radar_interface.py | 86 ++ car/chrysler/values.py | 156 ++ car/ford/__init__.py | 0 car/ford/carcontroller.py | 120 ++ car/ford/carstate.py | 174 +++ car/ford/fingerprints.py | 166 ++ car/ford/fordcan.py | 340 +++++ car/ford/interface.py | 85 ++ car/ford/radar_interface.py | 143 ++ car/ford/tests/__init__.py | 0 car/ford/tests/print_platform_codes.py | 30 + car/ford/tests/test_ford.py | 143 ++ car/ford/values.py | 279 ++++ car/gm/__init__.py | 0 car/gm/carcontroller.py | 165 ++ car/gm/carstate.py | 180 +++ car/gm/fingerprints.py | 63 + car/gm/gmcan.py | 173 +++ car/gm/interface.py | 239 +++ car/gm/radar_interface.py | 101 ++ car/gm/tests/__init__.py | 0 car/gm/tests/test_gm.py | 20 + car/gm/values.py | 234 +++ car/honda/__init__.py | 0 car/honda/carcontroller.py | 256 ++++ car/honda/carstate.py | 297 ++++ car/honda/fingerprints.py | 895 +++++++++++ car/honda/hondacan.py | 211 +++ car/honda/interface.py | 259 ++++ car/honda/radar_interface.py | 84 + car/honda/tests/__init__.py | 0 car/honda/tests/test_honda.py | 14 + car/honda/values.py | 331 ++++ car/hyundai/__init__.py | 0 car/hyundai/carcontroller.py | 208 +++ car/hyundai/carstate.py | 368 +++++ car/hyundai/fingerprints.py | 1160 ++++++++++++++ car/hyundai/hyundaican.py | 213 +++ car/hyundai/hyundaicanfd.py | 223 +++ car/hyundai/interface.py | 180 +++ car/hyundai/radar_interface.py | 79 + car/hyundai/tests/__init__.py | 0 car/hyundai/tests/print_platform_codes.py | 22 + car/hyundai/tests/test_hyundai.py | 218 +++ car/hyundai/values.py | 751 +++++++++ car/mazda/__init__.py | 0 car/mazda/carcontroller.py | 66 + car/mazda/carstate.py | 153 ++ car/mazda/fingerprints.py | 265 ++++ car/mazda/interface.py | 50 + car/mazda/mazdacan.py | 128 ++ car/mazda/radar_interface.py | 5 + car/mazda/values.py | 104 ++ car/mock/__init__.py | 0 car/mock/carcontroller.py | 5 + car/mock/carstate.py | 4 + car/mock/interface.py | 32 + car/mock/radar_interface.py | 4 + car/mock/values.py | 9 + car/nissan/__init__.py | 0 car/nissan/carcontroller.py | 82 + car/nissan/carstate.py | 197 +++ car/nissan/fingerprints.py | 119 ++ car/nissan/interface.py | 44 + car/nissan/nissancan.py | 154 ++ car/nissan/radar_interface.py | 4 + car/nissan/values.py | 107 ++ car/subaru/__init__.py | 0 car/subaru/carcontroller.py | 144 ++ car/subaru/carstate.py | 229 +++ car/subaru/fingerprints.py | 563 +++++++ car/subaru/interface.py | 116 ++ car/subaru/radar_interface.py | 4 + car/subaru/subarucan.py | 321 ++++ car/subaru/tests/test_subaru.py | 16 + car/subaru/values.py | 275 ++++ car/tesla/__init__.py | 0 car/tesla/carcontroller.py | 67 + car/tesla/carstate.py | 139 ++ car/tesla/fingerprints.py | 32 + car/tesla/interface.py | 52 + car/tesla/radar_interface.py | 91 ++ car/tesla/teslacan.py | 94 ++ car/tesla/values.py | 98 ++ car/toyota/__init__.py | 0 car/toyota/carcontroller.py | 179 +++ car/toyota/carstate.py | 247 +++ car/toyota/fingerprints.py | 1681 +++++++++++++++++++++ car/toyota/interface.py | 202 +++ car/toyota/radar_interface.py | 94 ++ car/toyota/tests/__init__.py | 0 car/toyota/tests/print_platform_codes.py | 35 + car/toyota/tests/test_toyota.py | 166 ++ car/toyota/toyotacan.py | 118 ++ car/toyota/values.py | 575 +++++++ car/volkswagen/__init__.py | 0 car/volkswagen/carcontroller.py | 121 ++ car/volkswagen/carstate.py | 398 +++++ car/volkswagen/fingerprints.py | 1201 +++++++++++++++ car/volkswagen/interface.py | 133 ++ car/volkswagen/mqbcan.py | 137 ++ car/volkswagen/pqcan.py | 105 ++ car/volkswagen/radar_interface.py | 4 + car/volkswagen/tests/test_volkswagen.py | 60 + car/volkswagen/values.py | 516 +++++++ 119 files changed, 19767 insertions(+) create mode 100644 car/body/__init__.py create mode 100644 car/body/bodycan.py create mode 100644 car/body/carcontroller.py create mode 100644 car/body/carstate.py create mode 100644 car/body/fingerprints.py create mode 100644 car/body/interface.py create mode 100644 car/body/radar_interface.py create mode 100644 car/body/values.py create mode 100644 car/chrysler/__init__.py create mode 100644 car/chrysler/carcontroller.py create mode 100644 car/chrysler/carstate.py create mode 100644 car/chrysler/chryslercan.py create mode 100644 car/chrysler/fingerprints.py create mode 100755 car/chrysler/interface.py create mode 100755 car/chrysler/radar_interface.py create mode 100644 car/chrysler/values.py create mode 100644 car/ford/__init__.py create mode 100644 car/ford/carcontroller.py create mode 100644 car/ford/carstate.py create mode 100644 car/ford/fingerprints.py create mode 100644 car/ford/fordcan.py create mode 100644 car/ford/interface.py create mode 100644 car/ford/radar_interface.py create mode 100644 car/ford/tests/__init__.py create mode 100755 car/ford/tests/print_platform_codes.py create mode 100644 car/ford/tests/test_ford.py create mode 100644 car/ford/values.py create mode 100644 car/gm/__init__.py create mode 100644 car/gm/carcontroller.py create mode 100644 car/gm/carstate.py create mode 100644 car/gm/fingerprints.py create mode 100644 car/gm/gmcan.py create mode 100755 car/gm/interface.py create mode 100755 car/gm/radar_interface.py create mode 100644 car/gm/tests/__init__.py create mode 100644 car/gm/tests/test_gm.py create mode 100644 car/gm/values.py create mode 100644 car/honda/__init__.py create mode 100644 car/honda/carcontroller.py create mode 100644 car/honda/carstate.py create mode 100644 car/honda/fingerprints.py create mode 100644 car/honda/hondacan.py create mode 100755 car/honda/interface.py create mode 100755 car/honda/radar_interface.py create mode 100644 car/honda/tests/__init__.py create mode 100644 car/honda/tests/test_honda.py create mode 100644 car/honda/values.py create mode 100644 car/hyundai/__init__.py create mode 100644 car/hyundai/carcontroller.py create mode 100644 car/hyundai/carstate.py create mode 100644 car/hyundai/fingerprints.py create mode 100644 car/hyundai/hyundaican.py create mode 100644 car/hyundai/hyundaicanfd.py create mode 100644 car/hyundai/interface.py create mode 100644 car/hyundai/radar_interface.py create mode 100644 car/hyundai/tests/__init__.py create mode 100755 car/hyundai/tests/print_platform_codes.py create mode 100644 car/hyundai/tests/test_hyundai.py create mode 100644 car/hyundai/values.py create mode 100644 car/mazda/__init__.py create mode 100644 car/mazda/carcontroller.py create mode 100644 car/mazda/carstate.py create mode 100644 car/mazda/fingerprints.py create mode 100755 car/mazda/interface.py create mode 100644 car/mazda/mazdacan.py create mode 100755 car/mazda/radar_interface.py create mode 100644 car/mazda/values.py create mode 100644 car/mock/__init__.py create mode 100644 car/mock/carcontroller.py create mode 100644 car/mock/carstate.py create mode 100755 car/mock/interface.py create mode 100644 car/mock/radar_interface.py create mode 100644 car/mock/values.py create mode 100644 car/nissan/__init__.py create mode 100644 car/nissan/carcontroller.py create mode 100644 car/nissan/carstate.py create mode 100644 car/nissan/fingerprints.py create mode 100644 car/nissan/interface.py create mode 100644 car/nissan/nissancan.py create mode 100644 car/nissan/radar_interface.py create mode 100644 car/nissan/values.py create mode 100644 car/subaru/__init__.py create mode 100644 car/subaru/carcontroller.py create mode 100644 car/subaru/carstate.py create mode 100644 car/subaru/fingerprints.py create mode 100644 car/subaru/interface.py create mode 100644 car/subaru/radar_interface.py create mode 100644 car/subaru/subarucan.py create mode 100644 car/subaru/tests/test_subaru.py create mode 100644 car/subaru/values.py create mode 100644 car/tesla/__init__.py create mode 100644 car/tesla/carcontroller.py create mode 100644 car/tesla/carstate.py create mode 100644 car/tesla/fingerprints.py create mode 100755 car/tesla/interface.py create mode 100755 car/tesla/radar_interface.py create mode 100644 car/tesla/teslacan.py create mode 100644 car/tesla/values.py create mode 100644 car/toyota/__init__.py create mode 100644 car/toyota/carcontroller.py create mode 100644 car/toyota/carstate.py create mode 100644 car/toyota/fingerprints.py create mode 100644 car/toyota/interface.py create mode 100755 car/toyota/radar_interface.py create mode 100644 car/toyota/tests/__init__.py create mode 100755 car/toyota/tests/print_platform_codes.py create mode 100644 car/toyota/tests/test_toyota.py create mode 100644 car/toyota/toyotacan.py create mode 100644 car/toyota/values.py create mode 100644 car/volkswagen/__init__.py create mode 100644 car/volkswagen/carcontroller.py create mode 100644 car/volkswagen/carstate.py create mode 100644 car/volkswagen/fingerprints.py create mode 100644 car/volkswagen/interface.py create mode 100644 car/volkswagen/mqbcan.py create mode 100644 car/volkswagen/pqcan.py create mode 100644 car/volkswagen/radar_interface.py create mode 100644 car/volkswagen/tests/test_volkswagen.py create mode 100644 car/volkswagen/values.py diff --git a/car/body/__init__.py b/car/body/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/car/body/bodycan.py b/car/body/bodycan.py new file mode 100644 index 0000000000..580e5025ad --- /dev/null +++ b/car/body/bodycan.py @@ -0,0 +1,7 @@ +def create_control(packer, torque_l, torque_r): + values = { + "TORQUE_L": torque_l, + "TORQUE_R": torque_r, + } + + return packer.make_can_msg("TORQUE_CMD", 0, values) diff --git a/car/body/carcontroller.py b/car/body/carcontroller.py new file mode 100644 index 0000000000..259126c416 --- /dev/null +++ b/car/body/carcontroller.py @@ -0,0 +1,84 @@ +import numpy as np + +from openpilot.common.realtime import DT_CTRL +from opendbc.can.packer import CANPacker +from openpilot.selfdrive.car.body import bodycan +from openpilot.selfdrive.car.body.values import SPEED_FROM_RPM +from openpilot.selfdrive.car.interfaces import CarControllerBase +from openpilot.selfdrive.controls.lib.pid import PIDController + + +MAX_TORQUE = 500 +MAX_TORQUE_RATE = 50 +MAX_ANGLE_ERROR = np.radians(7) +MAX_POS_INTEGRATOR = 0.2 # meters +MAX_TURN_INTEGRATOR = 0.1 # meters + + +class CarController(CarControllerBase): + def __init__(self, dbc_name, CP, VM): + self.frame = 0 + self.packer = CANPacker(dbc_name) + + # PIDs + self.turn_pid = PIDController(110, k_i=11.5, rate=1/DT_CTRL) + self.wheeled_speed_pid = PIDController(110, k_i=11.5, rate=1/DT_CTRL) + + self.torque_r_filtered = 0. + self.torque_l_filtered = 0. + + @staticmethod + def deadband_filter(torque, deadband): + if torque > 0: + torque += deadband + else: + torque -= deadband + return torque + + def update(self, CC, CS, now_nanos): + + torque_l = 0 + torque_r = 0 + + llk_valid = len(CC.orientationNED) > 1 and len(CC.angularVelocity) > 1 + if CC.enabled and llk_valid: + # Read these from the joystick + # TODO: this isn't acceleration, okay? + speed_desired = CC.actuators.accel / 5. + speed_diff_desired = -CC.actuators.steer / 2. + + speed_measured = SPEED_FROM_RPM * (CS.out.wheelSpeeds.fl + CS.out.wheelSpeeds.fr) / 2. + speed_error = speed_desired - speed_measured + + torque = self.wheeled_speed_pid.update(speed_error, freeze_integrator=False) + + speed_diff_measured = SPEED_FROM_RPM * (CS.out.wheelSpeeds.fl - CS.out.wheelSpeeds.fr) + turn_error = speed_diff_measured - speed_diff_desired + freeze_integrator = ((turn_error < 0 and self.turn_pid.error_integral <= -MAX_TURN_INTEGRATOR) or + (turn_error > 0 and self.turn_pid.error_integral >= MAX_TURN_INTEGRATOR)) + torque_diff = self.turn_pid.update(turn_error, freeze_integrator=freeze_integrator) + + # Combine 2 PIDs outputs + torque_r = torque + torque_diff + torque_l = torque - torque_diff + + # Torque rate limits + self.torque_r_filtered = np.clip(self.deadband_filter(torque_r, 10), + self.torque_r_filtered - MAX_TORQUE_RATE, + self.torque_r_filtered + MAX_TORQUE_RATE) + self.torque_l_filtered = np.clip(self.deadband_filter(torque_l, 10), + self.torque_l_filtered - MAX_TORQUE_RATE, + self.torque_l_filtered + MAX_TORQUE_RATE) + torque_r = int(np.clip(self.torque_r_filtered, -MAX_TORQUE, MAX_TORQUE)) + torque_l = int(np.clip(self.torque_l_filtered, -MAX_TORQUE, MAX_TORQUE)) + + can_sends = [] + can_sends.append(bodycan.create_control(self.packer, torque_l, torque_r)) + + new_actuators = CC.actuators.as_builder() + new_actuators.accel = torque_l + new_actuators.steer = torque_r + new_actuators.steerOutputCan = torque_r + + self.frame += 1 + return new_actuators, can_sends diff --git a/car/body/carstate.py b/car/body/carstate.py new file mode 100644 index 0000000000..fca9bcc627 --- /dev/null +++ b/car/body/carstate.py @@ -0,0 +1,40 @@ +from cereal import car +from opendbc.can.parser import CANParser +from openpilot.selfdrive.car.interfaces import CarStateBase +from openpilot.selfdrive.car.body.values import DBC + +STARTUP_TICKS = 100 + +class CarState(CarStateBase): + def update(self, cp): + ret = car.CarState.new_message() + + ret.wheelSpeeds.fl = cp.vl['MOTORS_DATA']['SPEED_L'] + ret.wheelSpeeds.fr = cp.vl['MOTORS_DATA']['SPEED_R'] + + ret.vEgoRaw = ((ret.wheelSpeeds.fl + ret.wheelSpeeds.fr) / 2.) * self.CP.wheelSpeedFactor + + ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) + ret.standstill = False + + ret.steerFaultPermanent = any([cp.vl['VAR_VALUES']['MOTOR_ERR_L'], cp.vl['VAR_VALUES']['MOTOR_ERR_R'], + cp.vl['VAR_VALUES']['FAULT']]) + + ret.charging = cp.vl["BODY_DATA"]["CHARGER_CONNECTED"] == 1 + ret.fuelGauge = cp.vl["BODY_DATA"]["BATT_PERCENTAGE"] / 100 + + # irrelevant for non-car + ret.gearShifter = car.CarState.GearShifter.drive + ret.cruiseState.enabled = True + ret.cruiseState.available = True + + return ret + + @staticmethod + def get_can_parser(CP): + messages = [ + ("MOTORS_DATA", 100), + ("VAR_VALUES", 10), + ("BODY_DATA", 1), + ] + return CANParser(DBC[CP.carFingerprint]["pt"], messages, 0) diff --git a/car/body/fingerprints.py b/car/body/fingerprints.py new file mode 100644 index 0000000000..ab7a5f8d7b --- /dev/null +++ b/car/body/fingerprints.py @@ -0,0 +1,28 @@ +# ruff: noqa: E501 +from cereal import car +from openpilot.selfdrive.car.body.values import CAR + +Ecu = car.CarParams.Ecu + +# debug ecu fw version is the git hash of the firmware + + +FINGERPRINTS = { + CAR.COMMA_BODY: [{ + 513: 8, 516: 8, 514: 3, 515: 4 + }], +} + +FW_VERSIONS = { + CAR.COMMA_BODY: { + (Ecu.engine, 0x720, None): [ + b'0.0.01', + b'0.3.00a', + b'02/27/2022', + ], + (Ecu.debug, 0x721, None): [ + b'166bd860', + b'dc780f85', + ], + }, +} diff --git a/car/body/interface.py b/car/body/interface.py new file mode 100644 index 0000000000..f797a7ecf8 --- /dev/null +++ b/car/body/interface.py @@ -0,0 +1,39 @@ +import math +from cereal import car +from openpilot.common.realtime import DT_CTRL +from openpilot.selfdrive.car import get_safety_config +from openpilot.selfdrive.car.interfaces import CarInterfaceBase +from openpilot.selfdrive.car.body.values import SPEED_FROM_RPM + +class CarInterface(CarInterfaceBase): + @staticmethod + def _get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs): + ret.notCar = True + ret.carName = "body" + ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.body)] + + ret.minSteerSpeed = -math.inf + ret.maxLateralAccel = math.inf # TODO: set to a reasonable value + ret.steerLimitTimer = 1.0 + ret.steerActuatorDelay = 0. + + ret.wheelSpeedFactor = SPEED_FROM_RPM + + ret.radarUnavailable = True + ret.openpilotLongitudinalControl = True + ret.steerControlType = car.CarParams.SteerControlType.angle + + return ret + + def _update(self, c): + ret = self.CS.update(self.cp) + + # wait for everything to init first + if self.frame > int(5. / DT_CTRL): + # body always wants to enable + ret.init('events', 1) + ret.events[0].name = car.CarEvent.EventName.pcmEnable + ret.events[0].enable = True + self.frame += 1 + + return ret diff --git a/car/body/radar_interface.py b/car/body/radar_interface.py new file mode 100644 index 0000000000..e654bd61fd --- /dev/null +++ b/car/body/radar_interface.py @@ -0,0 +1,4 @@ +from openpilot.selfdrive.car.interfaces import RadarInterfaceBase + +class RadarInterface(RadarInterfaceBase): + pass diff --git a/car/body/values.py b/car/body/values.py new file mode 100644 index 0000000000..a1195f7cb5 --- /dev/null +++ b/car/body/values.py @@ -0,0 +1,40 @@ +from cereal import car +from openpilot.selfdrive.car import CarSpecs, PlatformConfig, Platforms, dbc_dict +from openpilot.selfdrive.car.docs_definitions import CarDocs +from openpilot.selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries + +Ecu = car.CarParams.Ecu + +SPEED_FROM_RPM = 0.008587 + + +class CarControllerParams: + ANGLE_DELTA_BP = [0., 5., 15.] + ANGLE_DELTA_V = [5., .8, .15] # windup limit + ANGLE_DELTA_VU = [5., 3.5, 0.4] # unwind limit + LKAS_MAX_TORQUE = 1 # A value of 1 is easy to overpower + STEER_THRESHOLD = 1.0 + + def __init__(self, CP): + pass + + +class CAR(Platforms): + COMMA_BODY = PlatformConfig( + [CarDocs("comma body", package="All")], + CarSpecs(mass=9, wheelbase=0.406, steerRatio=0.5, centerToFrontRatio=0.44), + dbc_dict('comma_body', None), + ) + + +FW_QUERY_CONFIG = FwQueryConfig( + requests=[ + Request( + [StdQueries.TESTER_PRESENT_REQUEST, StdQueries.UDS_VERSION_REQUEST], + [StdQueries.TESTER_PRESENT_RESPONSE, StdQueries.UDS_VERSION_RESPONSE], + bus=0, + ), + ], +) + +DBC = CAR.create_dbc_map() diff --git a/car/chrysler/__init__.py b/car/chrysler/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/car/chrysler/carcontroller.py b/car/chrysler/carcontroller.py new file mode 100644 index 0000000000..85f53f68eb --- /dev/null +++ b/car/chrysler/carcontroller.py @@ -0,0 +1,85 @@ +from opendbc.can.packer import CANPacker +from openpilot.common.realtime import DT_CTRL +from openpilot.selfdrive.car import apply_meas_steer_torque_limits +from openpilot.selfdrive.car.chrysler import chryslercan +from openpilot.selfdrive.car.chrysler.values import RAM_CARS, CarControllerParams, ChryslerFlags +from openpilot.selfdrive.car.interfaces import CarControllerBase + + +class CarController(CarControllerBase): + def __init__(self, dbc_name, CP, VM): + self.CP = CP + self.apply_steer_last = 0 + self.frame = 0 + + self.hud_count = 0 + self.last_lkas_falling_edge = 0 + self.lkas_control_bit_prev = False + self.last_button_frame = 0 + + self.packer = CANPacker(dbc_name) + self.params = CarControllerParams(CP) + + def update(self, CC, CS, now_nanos): + can_sends = [] + + lkas_active = CC.latActive and self.lkas_control_bit_prev + + # cruise buttons + if (self.frame - self.last_button_frame)*DT_CTRL > 0.05: + das_bus = 2 if self.CP.carFingerprint in RAM_CARS else 0 + + # ACC cancellation + if CC.cruiseControl.cancel: + self.last_button_frame = self.frame + can_sends.append(chryslercan.create_cruise_buttons(self.packer, CS.button_counter + 1, das_bus, cancel=True)) + + # ACC resume from standstill + elif CC.cruiseControl.resume: + self.last_button_frame = self.frame + can_sends.append(chryslercan.create_cruise_buttons(self.packer, CS.button_counter + 1, das_bus, resume=True)) + + # HUD alerts + if self.frame % 25 == 0: + if CS.lkas_car_model != -1: + can_sends.append(chryslercan.create_lkas_hud(self.packer, self.CP, lkas_active, CC.hudControl.visualAlert, + self.hud_count, CS.lkas_car_model, CS.auto_high_beam)) + self.hud_count += 1 + + # steering + if self.frame % self.params.STEER_STEP == 0: + + # TODO: can we make this more sane? why is it different for all the cars? + lkas_control_bit = self.lkas_control_bit_prev + if CS.out.vEgo > self.CP.minSteerSpeed: + lkas_control_bit = True + elif self.CP.flags & ChryslerFlags.HIGHER_MIN_STEERING_SPEED: + if CS.out.vEgo < (self.CP.minSteerSpeed - 3.0): + lkas_control_bit = False + elif self.CP.carFingerprint in RAM_CARS: + if CS.out.vEgo < (self.CP.minSteerSpeed - 0.5): + lkas_control_bit = False + + # EPS faults if LKAS re-enables too quickly + lkas_control_bit = lkas_control_bit and (self.frame - self.last_lkas_falling_edge > 200) + + if not lkas_control_bit and self.lkas_control_bit_prev: + self.last_lkas_falling_edge = self.frame + self.lkas_control_bit_prev = lkas_control_bit + + # steer torque + new_steer = int(round(CC.actuators.steer * self.params.STEER_MAX)) + apply_steer = apply_meas_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorqueEps, self.params) + if not lkas_active or not lkas_control_bit: + apply_steer = 0 + self.apply_steer_last = apply_steer + + can_sends.append(chryslercan.create_lkas_command(self.packer, self.CP, int(apply_steer), lkas_control_bit)) + + self.frame += 1 + + new_actuators = CC.actuators.as_builder() + new_actuators.steer = self.apply_steer_last / self.params.STEER_MAX + new_actuators.steerOutputCan = self.apply_steer_last + + return new_actuators, can_sends diff --git a/car/chrysler/carstate.py b/car/chrysler/carstate.py new file mode 100644 index 0000000000..91b922c596 --- /dev/null +++ b/car/chrysler/carstate.py @@ -0,0 +1,156 @@ +from cereal import car +from openpilot.common.conversions import Conversions as CV +from opendbc.can.parser import CANParser +from opendbc.can.can_define import CANDefine +from openpilot.selfdrive.car.interfaces import CarStateBase +from openpilot.selfdrive.car.chrysler.values import DBC, STEER_THRESHOLD, RAM_CARS + + +class CarState(CarStateBase): + def __init__(self, CP): + super().__init__(CP) + self.CP = CP + can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) + + self.auto_high_beam = 0 + self.button_counter = 0 + self.lkas_car_model = -1 + + if CP.carFingerprint in RAM_CARS: + self.shifter_values = can_define.dv["Transmission_Status"]["Gear_State"] + else: + self.shifter_values = can_define.dv["GEAR"]["PRNDL"] + + self.prev_distance_button = 0 + self.distance_button = 0 + + def update(self, cp, cp_cam): + + ret = car.CarState.new_message() + + self.prev_distance_button = self.distance_button + self.distance_button = cp.vl["CRUISE_BUTTONS"]["ACC_Distance_Dec"] + + # lock info + ret.doorOpen = any([cp.vl["BCM_1"]["DOOR_OPEN_FL"], + cp.vl["BCM_1"]["DOOR_OPEN_FR"], + cp.vl["BCM_1"]["DOOR_OPEN_RL"], + cp.vl["BCM_1"]["DOOR_OPEN_RR"]]) + ret.seatbeltUnlatched = cp.vl["ORC_1"]["SEATBELT_DRIVER_UNLATCHED"] == 1 + + # brake pedal + ret.brake = 0 + ret.brakePressed = cp.vl["ESP_1"]['Brake_Pedal_State'] == 1 # Physical brake pedal switch + + # gas pedal + ret.gas = cp.vl["ECM_5"]["Accelerator_Position"] + ret.gasPressed = ret.gas > 1e-5 + + # car speed + if self.CP.carFingerprint in RAM_CARS: + ret.vEgoRaw = cp.vl["ESP_8"]["Vehicle_Speed"] * CV.KPH_TO_MS + ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(cp.vl["Transmission_Status"]["Gear_State"], None)) + else: + ret.vEgoRaw = (cp.vl["SPEED_1"]["SPEED_LEFT"] + cp.vl["SPEED_1"]["SPEED_RIGHT"]) / 2. + ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(cp.vl["GEAR"]["PRNDL"], None)) + ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) + ret.standstill = not ret.vEgoRaw > 0.001 + ret.wheelSpeeds = self.get_wheel_speeds( + cp.vl["ESP_6"]["WHEEL_SPEED_FL"], + cp.vl["ESP_6"]["WHEEL_SPEED_FR"], + cp.vl["ESP_6"]["WHEEL_SPEED_RL"], + cp.vl["ESP_6"]["WHEEL_SPEED_RR"], + unit=1, + ) + + # button presses + ret.leftBlinker, ret.rightBlinker = self.update_blinker_from_stalk(200, cp.vl["STEERING_LEVERS"]["TURN_SIGNALS"] == 1, + cp.vl["STEERING_LEVERS"]["TURN_SIGNALS"] == 2) + ret.genericToggle = cp.vl["STEERING_LEVERS"]["HIGH_BEAM_PRESSED"] == 1 + + # steering wheel + ret.steeringAngleDeg = cp.vl["STEERING"]["STEERING_ANGLE"] + cp.vl["STEERING"]["STEERING_ANGLE_HP"] + ret.steeringRateDeg = cp.vl["STEERING"]["STEERING_RATE"] + ret.steeringTorque = cp.vl["EPS_2"]["COLUMN_TORQUE"] + ret.steeringTorqueEps = cp.vl["EPS_2"]["EPS_TORQUE_MOTOR"] + ret.steeringPressed = abs(ret.steeringTorque) > STEER_THRESHOLD + + # cruise state + cp_cruise = cp_cam if self.CP.carFingerprint in RAM_CARS else cp + + ret.cruiseState.available = cp_cruise.vl["DAS_3"]["ACC_AVAILABLE"] == 1 + ret.cruiseState.enabled = cp_cruise.vl["DAS_3"]["ACC_ACTIVE"] == 1 + ret.cruiseState.speed = cp_cruise.vl["DAS_4"]["ACC_SET_SPEED_KPH"] * CV.KPH_TO_MS + ret.cruiseState.nonAdaptive = cp_cruise.vl["DAS_4"]["ACC_STATE"] in (1, 2) # 1 NormalCCOn and 2 NormalCCSet + ret.cruiseState.standstill = cp_cruise.vl["DAS_3"]["ACC_STANDSTILL"] == 1 + ret.accFaulted = cp_cruise.vl["DAS_3"]["ACC_FAULTED"] != 0 + + if self.CP.carFingerprint in RAM_CARS: + # Auto High Beam isn't Located in this message on chrysler or jeep currently located in 729 message + self.auto_high_beam = cp_cam.vl["DAS_6"]['AUTO_HIGH_BEAM_ON'] + ret.steerFaultTemporary = cp.vl["EPS_3"]["DASM_FAULT"] == 1 + else: + ret.steerFaultTemporary = cp.vl["EPS_2"]["LKAS_TEMPORARY_FAULT"] == 1 + ret.steerFaultPermanent = cp.vl["EPS_2"]["LKAS_STATE"] == 4 + + # blindspot sensors + if self.CP.enableBsm: + ret.leftBlindspot = cp.vl["BSM_1"]["LEFT_STATUS"] == 1 + ret.rightBlindspot = cp.vl["BSM_1"]["RIGHT_STATUS"] == 1 + + self.lkas_car_model = cp_cam.vl["DAS_6"]["CAR_MODEL"] + self.button_counter = cp.vl["CRUISE_BUTTONS"]["COUNTER"] + + return ret + + @staticmethod + def get_cruise_messages(): + messages = [ + ("DAS_3", 50), + ("DAS_4", 50), + ] + return messages + + @staticmethod + def get_can_parser(CP): + messages = [ + # sig_address, frequency + ("ESP_1", 50), + ("EPS_2", 100), + ("ESP_6", 50), + ("STEERING", 100), + ("ECM_5", 50), + ("CRUISE_BUTTONS", 50), + ("STEERING_LEVERS", 10), + ("ORC_1", 2), + ("BCM_1", 1), + ] + + if CP.enableBsm: + messages.append(("BSM_1", 2)) + + if CP.carFingerprint in RAM_CARS: + messages += [ + ("ESP_8", 50), + ("EPS_3", 50), + ("Transmission_Status", 50), + ] + else: + messages += [ + ("GEAR", 50), + ("SPEED_1", 100), + ] + messages += CarState.get_cruise_messages() + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, 0) + + @staticmethod + def get_cam_can_parser(CP): + messages = [ + ("DAS_6", 4), + ] + + if CP.carFingerprint in RAM_CARS: + messages += CarState.get_cruise_messages() + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, 2) diff --git a/car/chrysler/chryslercan.py b/car/chrysler/chryslercan.py new file mode 100644 index 0000000000..96439f35d8 --- /dev/null +++ b/car/chrysler/chryslercan.py @@ -0,0 +1,71 @@ +from cereal import car +from openpilot.selfdrive.car.chrysler.values import RAM_CARS + +GearShifter = car.CarState.GearShifter +VisualAlert = car.CarControl.HUDControl.VisualAlert + +def create_lkas_hud(packer, CP, lkas_active, hud_alert, hud_count, car_model, auto_high_beam): + # LKAS_HUD - Controls what lane-keeping icon is displayed + + # == Color == + # 0 hidden? + # 1 white + # 2 green + # 3 ldw + + # == Lines == + # 03 white Lines + # 04 grey lines + # 09 left lane close + # 0A right lane close + # 0B left Lane very close + # 0C right Lane very close + # 0D left cross cross + # 0E right lane cross + + # == Alerts == + # 7 Normal + # 6 lane departure place hands on wheel + + color = 2 if lkas_active else 1 + lines = 3 if lkas_active else 0 + alerts = 7 if lkas_active else 0 + + if hud_count < (1 * 4): # first 3 seconds, 4Hz + alerts = 1 + + if hud_alert in (VisualAlert.ldw, VisualAlert.steerRequired): + color = 4 + lines = 0 + alerts = 6 + + values = { + "LKAS_ICON_COLOR": color, + "CAR_MODEL": car_model, + "LKAS_LANE_LINES": lines, + "LKAS_ALERTS": alerts, + } + + if CP.carFingerprint in RAM_CARS: + values['AUTO_HIGH_BEAM_ON'] = auto_high_beam + + return packer.make_can_msg("DAS_6", 0, values) + + +def create_lkas_command(packer, CP, apply_steer, lkas_control_bit): + # LKAS_COMMAND Lane-keeping signal to turn the wheel + enabled_val = 2 if CP.carFingerprint in RAM_CARS else 1 + values = { + "STEERING_TORQUE": apply_steer, + "LKAS_CONTROL_BIT": enabled_val if lkas_control_bit else 0, + } + return packer.make_can_msg("LKAS_COMMAND", 0, values) + + +def create_cruise_buttons(packer, frame, bus, cancel=False, resume=False): + values = { + "ACC_Cancel": cancel, + "ACC_Resume": resume, + "COUNTER": frame % 0x10, + } + return packer.make_can_msg("CRUISE_BUTTONS", bus, values) diff --git a/car/chrysler/fingerprints.py b/car/chrysler/fingerprints.py new file mode 100644 index 0000000000..01faa49bf7 --- /dev/null +++ b/car/chrysler/fingerprints.py @@ -0,0 +1,705 @@ +from cereal import car +from openpilot.selfdrive.car.chrysler.values import CAR + +Ecu = car.CarParams.Ecu + +FW_VERSIONS = { + CAR.CHRYSLER_PACIFICA_2017_HYBRID: { + (Ecu.combinationMeter, 0x742, None): [ + b'68239262AH', + b'68239262AI', + b'68239262AJ', + b'68239263AH', + b'68239263AJ', + ], + (Ecu.srs, 0x744, None): [ + b'68238840AH', + ], + (Ecu.fwdRadar, 0x753, None): [ + b'68226356AI', + ], + (Ecu.eps, 0x75a, None): [ + b'68288309AC', + b'68288309AD', + ], + (Ecu.engine, 0x7e0, None): [ + b'68277480AV ', + b'68277480AX ', + b'68277480AZ ', + ], + (Ecu.hybrid, 0x7e2, None): [ + b'05190175BF', + b'05190175BH', + b'05190226AK', + ], + }, + CAR.CHRYSLER_PACIFICA_2018: { + (Ecu.combinationMeter, 0x742, None): [ + b'68227902AF', + b'68227902AG', + b'68227902AH', + b'68227905AG', + b'68360252AC', + ], + (Ecu.srs, 0x744, None): [ + b'68211617AF', + b'68211617AG', + b'68358974AC', + b'68405937AA', + ], + (Ecu.abs, 0x747, None): [ + b'68222747AG', + b'68330876AA', + b'68330876AB', + b'68352227AA', + ], + (Ecu.fwdRadar, 0x753, None): [ + b'04672758AA', + b'68226356AF', + b'68226356AH', + b'68226356AI', + ], + (Ecu.eps, 0x75a, None): [ + b'68288891AE', + b'68378884AA', + b'68525338AA', + b'68525338AB', + ], + (Ecu.engine, 0x7e0, None): [ + b'68267018AO ', + b'68267020AJ ', + b'68303534AG ', + b'68303534AJ ', + b'68340762AD ', + b'68340764AD ', + b'68352652AE ', + b'68352654AE ', + b'68366851AH ', + b'68366853AE ', + b'68372861AF ', + ], + (Ecu.transmission, 0x7e1, None): [ + b'68277370AJ', + b'68277370AM', + b'68277372AD', + b'68277372AE', + b'68277372AN', + b'68277374AA', + b'68277374AB', + b'68277374AD', + b'68277374AN', + b'68367471AC', + b'68380571AB', + ], + }, + CAR.CHRYSLER_PACIFICA_2020: { + (Ecu.combinationMeter, 0x742, None): [ + b'68405327AC', + b'68436233AB', + b'68436233AC', + b'68436234AB', + b'68436250AE', + b'68529067AA', + b'68594993AB', + b'68594994AB', + ], + (Ecu.srs, 0x744, None): [ + b'68405565AB', + b'68405565AC', + b'68444299AC', + b'68480707AC', + b'68480708AC', + b'68526663AB', + ], + (Ecu.abs, 0x747, None): [ + b'68397394AA', + b'68433480AB', + b'68453575AF', + b'68577676AA', + b'68593395AA', + ], + (Ecu.fwdRadar, 0x753, None): [ + b'04672758AA', + b'04672758AB', + b'68417813AF', + b'68540436AA', + b'68540436AC', + b'68540436AD', + b'68598670AB', + b'68598670AC', + ], + (Ecu.eps, 0x75a, None): [ + b'68416742AA', + b'68460393AA', + b'68460393AB', + b'68494461AB', + b'68494461AC', + b'68524936AA', + b'68524936AB', + b'68525338AB', + b'68594337AB', + b'68594340AB', + ], + (Ecu.engine, 0x7e0, None): [ + b'68413871AD ', + b'68413871AE ', + b'68413871AH ', + b'68413871AI ', + b'68413873AH ', + b'68413873AI ', + b'68443120AE ', + b'68443123AC ', + b'68443125AC ', + b'68496647AI ', + b'68496647AJ ', + b'68496650AH ', + b'68496650AI ', + b'68496652AH ', + b'68526752AD ', + b'68526752AE ', + b'68526754AE ', + b'68536264AE ', + b'68700304AB ', + b'68700306AB ', + ], + (Ecu.transmission, 0x7e1, None): [ + b'68414271AC', + b'68414271AD', + b'68414275AC', + b'68414275AD', + b'68443154AB', + b'68443155AC', + b'68443158AB', + b'68501050AD', + b'68501051AD', + b'68501055AD', + b'68527221AB', + b'68527223AB', + b'68586231AD', + b'68586233AD', + ], + }, + CAR.CHRYSLER_PACIFICA_2018_HYBRID: { + (Ecu.combinationMeter, 0x742, None): [ + b'68358439AE', + b'68358439AG', + ], + (Ecu.srs, 0x744, None): [ + b'68358990AC', + b'68405939AA', + ], + (Ecu.fwdRadar, 0x753, None): [ + b'04672758AA', + ], + (Ecu.eps, 0x75a, None): [ + b'68288309AD', + b'68525339AA', + ], + (Ecu.engine, 0x7e0, None): [ + b'68366580AI ', + b'68366580AK ', + b'68366580AM ', + ], + (Ecu.hybrid, 0x7e2, None): [ + b'05190226AI', + b'05190226AK', + b'05190226AM', + ], + }, + CAR.CHRYSLER_PACIFICA_2019_HYBRID: { + (Ecu.combinationMeter, 0x742, None): [ + b'68405292AC', + b'68434956AC', + b'68434956AD', + b'68434960AE', + b'68434960AF', + b'68529064AB', + b'68594990AB', + ], + (Ecu.srs, 0x744, None): [ + b'68405567AB', + b'68405567AC', + b'68453076AD', + b'68480710AC', + b'68526665AB', + ], + (Ecu.fwdRadar, 0x753, None): [ + b'04672758AB', + b'68417813AF', + b'68540436AA', + b'68540436AB', + b'68540436AC', + b'68540436AD', + b'68598670AB', + b'68598670AC', + ], + (Ecu.eps, 0x75a, None): [ + b'68416741AA', + b'68460392AA', + b'68525339AA', + b'68525339AB', + b'68594341AB', + ], + (Ecu.engine, 0x7e0, None): [ + b'68416680AE ', + b'68416680AF ', + b'68416680AG ', + b'68444228AD ', + b'68444228AE ', + b'68444228AF ', + b'68499122AD ', + b'68499122AE ', + b'68499122AF ', + b'68526772AD ', + b'68526772AH ', + b'68599493AC ', + ], + (Ecu.hybrid, 0x7e2, None): [ + b'05185116AF', + b'05185116AJ', + b'05185116AK', + b'05190240AP', + b'05190240AQ', + b'05190240AR', + b'05190265AG', + b'05190265AH', + b'05190289AE', + b'68540977AH', + b'68540977AK', + b'68597647AE', + ], + }, + CAR.JEEP_GRAND_CHEROKEE: { + (Ecu.combinationMeter, 0x742, None): [ + b'68243549AG', + b'68302211AC', + b'68302212AD', + b'68302223AC', + b'68302246AC', + b'68331511AC', + b'68331574AC', + b'68331687AC', + b'68331690AC', + b'68340272AD', + ], + (Ecu.srs, 0x744, None): [ + b'68309533AA', + b'68316742AB', + b'68355363AB', + ], + (Ecu.abs, 0x747, None): [ + b'68252642AG', + b'68306178AD', + b'68336276AB', + ], + (Ecu.fwdRadar, 0x753, None): [ + b'04672627AB', + b'68251506AF', + b'68332015AB', + ], + (Ecu.eps, 0x75a, None): [ + b'68276201AG', + b'68321644AB', + b'68321644AC', + b'68321646AC', + b'68321648AC', + ], + (Ecu.engine, 0x7e0, None): [ + b'05035920AE ', + b'68252272AG ', + b'68284455AI ', + b'68284456AI ', + b'68284477AF ', + b'68325564AH ', + b'68325565AH ', + b'68325565AI ', + b'68325618AD ', + ], + (Ecu.transmission, 0x7e1, None): [ + b'05035517AH', + b'68253222AF', + b'68311218AC', + b'68311223AF', + b'68311223AG', + b'68361911AE', + b'68361911AF', + b'68361911AH', + b'68361916AD', + ], + }, + CAR.JEEP_GRAND_CHEROKEE_2019: { + (Ecu.combinationMeter, 0x742, None): [ + b'68402703AB', + b'68402704AB', + b'68402708AB', + b'68402971AD', + b'68454144AD', + b'68454145AB', + b'68454152AB', + b'68454156AB', + b'68516650AB', + b'68516651AB', + b'68516669AB', + b'68516671AB', + b'68516683AB', + ], + (Ecu.srs, 0x744, None): [ + b'68355363AB', + b'68355364AB', + ], + (Ecu.abs, 0x747, None): [ + b'68408639AC', + b'68408639AD', + b'68499978AB', + ], + (Ecu.fwdRadar, 0x753, None): [ + b'04672788AA', + b'68456722AC', + ], + (Ecu.eps, 0x75a, None): [ + b'68417279AA', + b'68417280AA', + b'68417281AA', + b'68453431AA', + b'68453433AA', + b'68453435AA', + b'68499171AA', + b'68499171AB', + b'68501183AA', + ], + (Ecu.engine, 0x7e0, None): [ + b'05035674AB ', + b'68412635AG ', + b'68412660AD ', + b'68422860AB', + b'68449435AE ', + b'68496223AA ', + b'68504959AD ', + b'68504960AD ', + b'68504993AC ', + ], + (Ecu.transmission, 0x7e1, None): [ + b'05035707AA', + b'68419672AC', + b'68419678AB', + b'68423905AB', + b'68449258AC', + b'68495807AA', + b'68495807AB', + b'68503641AC', + b'68503664AC', + ], + }, + CAR.RAM_1500_5TH_GEN: { + (Ecu.combinationMeter, 0x742, None): [ + b'68294051AG', + b'68294051AI', + b'68294052AG', + b'68294052AH', + b'68294063AG', + b'68294063AH', + b'68294063AI', + b'68434846AC', + b'68434847AC', + b'68434849AC', + b'68434856AC', + b'68434858AC', + b'68434859AC', + b'68434860AC', + b'68453483AC', + b'68453483AD', + b'68453487AD', + b'68453491AC', + b'68453499AD', + b'68453503AC', + b'68453503AD', + b'68453505AC', + b'68453505AD', + b'68453511AC', + b'68453513AC', + b'68453513AD', + b'68453514AD', + b'68505633AB', + b'68510277AG', + b'68510277AH', + b'68510280AG', + b'68510282AG', + b'68510282AH', + b'68510283AG', + b'68527346AE', + b'68527361AD', + b'68527375AD', + b'68527381AE', + b'68527382AE', + b'68527383AD', + b'68527387AE', + b'68527403AC', + b'68527403AD', + b'68546047AF', + b'68631938AA', + b'68631939AA', + b'68631940AA', + b'68631940AB', + b'68631942AA', + b'68631943AB', + ], + (Ecu.srs, 0x744, None): [ + b'68428609AB', + b'68441329AB', + b'68473844AB', + b'68490898AA', + b'68500728AA', + b'68615033AA', + b'68615034AA', + ], + (Ecu.abs, 0x747, None): [ + b'68292406AG', + b'68292406AH', + b'68432418AB', + b'68432418AC', + b'68432418AD', + b'68436004AD', + b'68436004AE', + b'68438454AC', + b'68438454AD', + b'68438456AE', + b'68438456AF', + b'68535469AB', + b'68535470AC', + b'68548900AB', + b'68586307AB', + ], + (Ecu.fwdRadar, 0x753, None): [ + b'04672892AB', + b'04672932AB', + b'04672932AC', + b'22DTRHD_AA', + b'68320950AH', + b'68320950AI', + b'68320950AJ', + b'68320950AL', + b'68320950AM', + b'68454268AB', + b'68475160AE', + b'68475160AF', + b'68475160AG', + ], + (Ecu.eps, 0x75a, None): [ + b'21590101AA', + b'21590101AB', + b'68273275AF', + b'68273275AG', + b'68273275AH', + b'68312176AE', + b'68312176AG', + b'68440789AC', + b'68466110AA', + b'68466110AB', + b'68466113AA', + b'68469901AA', + b'68469907AA', + b'68522583AA', + b'68522583AB', + b'68522584AA', + b'68522585AB', + b'68552788AA', + b'68552789AA', + b'68552790AA', + b'68552791AB', + b'68552794AA', + b'68552794AD', + b'68585106AB', + b'68585107AB', + b'68585108AB', + b'68585109AB', + b'68585112AB', + ], + (Ecu.engine, 0x7e0, None): [ + b'05035699AG ', + b'05035841AC ', + b'05035841AD ', + b'05036026AB ', + b'05036065AE ', + b'05036066AE ', + b'05036193AA ', + b'05149368AA ', + b'05149591AD ', + b'05149591AE ', + b'05149592AE ', + b'05149599AE ', + b'05149600AD ', + b'05149605AE ', + b'05149846AA ', + b'05149848AA ', + b'05149848AC ', + b'05190341AD', + b'68378695AJ ', + b'68378696AJ ', + b'68378701AI ', + b'68378702AI ', + b'68378710AL ', + b'68378742AI ', + b'68378742AK ', + b'68378748AL ', + b'68378758AM ', + b'68448163AJ', + b'68448163AK', + b'68448163AL', + b'68448165AG', + b'68448165AK', + b'68455111AC ', + b'68455119AC ', + b'68455145AC ', + b'68455145AE ', + b'68455146AC ', + b'68467915AC ', + b'68467916AC ', + b'68467936AC ', + b'68500630AD', + b'68500630AE', + b'68500631AE', + b'68502719AC ', + b'68502722AC ', + b'68502733AC ', + b'68502734AF ', + b'68502740AF ', + b'68502741AF ', + b'68502742AC ', + b'68502742AF ', + b'68539650AD', + b'68539650AF', + b'68539651AD', + b'68586101AA ', + b'68586105AB ', + b'68629919AC ', + b'68629922AC ', + b'68629925AC ', + b'68629926AC ', + ], + (Ecu.transmission, 0x7e1, None): [ + b'05035706AD', + b'05035842AB', + b'05036069AA', + b'05036181AA', + b'05149536AC', + b'05149537AC', + b'05149543AC', + b'68360078AL', + b'68360080AL', + b'68360080AM', + b'68360081AM', + b'68360085AJ', + b'68360085AL', + b'68360086AH', + b'68360086AK', + b'68384328AD', + b'68384332AD', + b'68445531AC', + b'68445533AB', + b'68445536AB', + b'68445537AB', + b'68466081AB', + b'68466087AB', + b'68484466AC', + b'68484467AC', + b'68484471AC', + b'68502994AD', + b'68502996AD', + b'68520867AE', + b'68520867AF', + b'68520870AC', + b'68540431AB', + b'68540433AB', + b'68551676AA', + b'68629935AB', + b'68629936AC', + ], + }, + CAR.RAM_HD_5TH_GEN: { + (Ecu.combinationMeter, 0x742, None): [ + b'68361606AH', + b'68437735AC', + b'68492693AD', + b'68525485AB', + b'68525487AB', + b'68525498AB', + b'68528791AF', + b'68628474AB', + ], + (Ecu.srs, 0x744, None): [ + b'68399794AC', + b'68428503AA', + b'68428505AA', + b'68428507AA', + ], + (Ecu.abs, 0x747, None): [ + b'68334977AH', + b'68455481AC', + b'68504022AA', + b'68504022AB', + b'68504022AC', + b'68530686AB', + b'68530686AC', + b'68544596AC', + b'68641704AA', + ], + (Ecu.fwdRadar, 0x753, None): [ + b'04672895AB', + b'04672934AB', + b'56029827AG', + b'56029827AH', + b'68462657AE', + b'68484694AD', + b'68484694AE', + b'68615489AB', + ], + (Ecu.eps, 0x761, None): [ + b'68421036AC', + b'68507906AB', + b'68534023AC', + ], + (Ecu.engine, 0x7e0, None): [ + b'52370131AF', + b'52370231AF', + b'52370231AG', + b'52370491AA', + b'52370931CT', + b'52401032AE', + b'52421132AF', + b'52421332AF', + b'68527616AD ', + b'M2370131MB', + b'M2421132MB', + ], + }, + CAR.DODGE_DURANGO: { + (Ecu.combinationMeter, 0x742, None): [ + b'68454261AD', + b'68471535AE', + ], + (Ecu.srs, 0x744, None): [ + b'68355362AB', + b'68492238AD', + ], + (Ecu.abs, 0x747, None): [ + b'68408639AD', + b'68499978AB', + ], + (Ecu.fwdRadar, 0x753, None): [ + b'68440581AE', + b'68456722AC', + ], + (Ecu.eps, 0x75a, None): [ + b'68453435AA', + b'68498477AA', + ], + (Ecu.engine, 0x7e0, None): [ + b'05035786AE ', + b'68449476AE ', + ], + (Ecu.transmission, 0x7e1, None): [ + b'05035826AC', + b'68449265AC', + ], + }, +} diff --git a/car/chrysler/interface.py b/car/chrysler/interface.py new file mode 100755 index 0000000000..217a1a756c --- /dev/null +++ b/car/chrysler/interface.py @@ -0,0 +1,97 @@ +#!/usr/bin/env python3 +from cereal import car +from panda import Panda +from openpilot.selfdrive.car import create_button_events, get_safety_config +from openpilot.selfdrive.car.chrysler.values import CAR, RAM_HD, RAM_DT, RAM_CARS, ChryslerFlags +from openpilot.selfdrive.car.interfaces import CarInterfaceBase + +ButtonType = car.CarState.ButtonEvent.Type + + +class CarInterface(CarInterfaceBase): + @staticmethod + def _get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs): + ret.carName = "chrysler" + ret.dashcamOnly = candidate in RAM_HD + + # radar parsing needs some work, see https://github.com/commaai/openpilot/issues/26842 + ret.radarUnavailable = True # DBC[candidate]['radar'] is None + ret.steerActuatorDelay = 0.1 + ret.steerLimitTimer = 0.4 + + # safety config + ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.chrysler)] + if candidate in RAM_HD: + ret.safetyConfigs[0].safetyParam |= Panda.FLAG_CHRYSLER_RAM_HD + elif candidate in RAM_DT: + ret.safetyConfigs[0].safetyParam |= Panda.FLAG_CHRYSLER_RAM_DT + + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) + if candidate not in RAM_CARS: + # Newer FW versions standard on the following platforms, or flashed by a dealer onto older platforms have a higher minimum steering speed. + new_eps_platform = candidate in (CAR.CHRYSLER_PACIFICA_2019_HYBRID, CAR.CHRYSLER_PACIFICA_2020, CAR.JEEP_GRAND_CHEROKEE_2019, CAR.DODGE_DURANGO) + new_eps_firmware = any(fw.ecu == 'eps' and fw.fwVersion[:4] >= b"6841" for fw in car_fw) + if new_eps_platform or new_eps_firmware: + ret.flags |= ChryslerFlags.HIGHER_MIN_STEERING_SPEED.value + + # Chrysler + if candidate in (CAR.CHRYSLER_PACIFICA_2017_HYBRID, CAR.CHRYSLER_PACIFICA_2018, CAR.CHRYSLER_PACIFICA_2018_HYBRID, \ + CAR.CHRYSLER_PACIFICA_2019_HYBRID, CAR.CHRYSLER_PACIFICA_2020, CAR.DODGE_DURANGO): + ret.lateralTuning.init('pid') + ret.lateralTuning.pid.kpBP, ret.lateralTuning.pid.kiBP = [[9., 20.], [9., 20.]] + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.15, 0.30], [0.03, 0.05]] + ret.lateralTuning.pid.kf = 0.00006 + + # Jeep + elif candidate in (CAR.JEEP_GRAND_CHEROKEE, CAR.JEEP_GRAND_CHEROKEE_2019): + ret.steerActuatorDelay = 0.2 + + ret.lateralTuning.init('pid') + ret.lateralTuning.pid.kpBP, ret.lateralTuning.pid.kiBP = [[9., 20.], [9., 20.]] + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.15, 0.30], [0.03, 0.05]] + ret.lateralTuning.pid.kf = 0.00006 + + # Ram + elif candidate == CAR.RAM_1500_5TH_GEN: + ret.steerActuatorDelay = 0.2 + ret.wheelbase = 3.88 + # Older EPS FW allow steer to zero + if any(fw.ecu == 'eps' and b"68" < fw.fwVersion[:4] <= b"6831" for fw in car_fw): + ret.minSteerSpeed = 0. + + elif candidate == CAR.RAM_HD_5TH_GEN: + ret.steerActuatorDelay = 0.2 + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning, 1.0, False) + + else: + raise ValueError(f"Unsupported car: {candidate}") + + if ret.flags & ChryslerFlags.HIGHER_MIN_STEERING_SPEED: + # TODO: allow these cars to steer down to 13 m/s if already engaged. + # TODO: Durango 2020 may be able to steer to zero once above 38 kph + ret.minSteerSpeed = 17.5 # m/s 17 on the way up, 13 on the way down once engaged. + + ret.centerToFront = ret.wheelbase * 0.44 + ret.enableBsm = 720 in fingerprint[0] + + return ret + + def _update(self, c): + ret = self.CS.update(self.cp, self.cp_cam) + + ret.buttonEvents = create_button_events(self.CS.distance_button, self.CS.prev_distance_button, {1: ButtonType.gapAdjustCruise}) + + # events + events = self.create_common_events(ret, extra_gears=[car.CarState.GearShifter.low]) + + # Low speed steer alert hysteresis logic + if self.CP.minSteerSpeed > 0. and ret.vEgo < (self.CP.minSteerSpeed + 0.5): + self.low_speed_alert = True + elif ret.vEgo > (self.CP.minSteerSpeed + 1.): + self.low_speed_alert = False + if self.low_speed_alert: + events.add(car.CarEvent.EventName.belowSteerSpeed) + + ret.events = events.to_msg() + + return ret diff --git a/car/chrysler/radar_interface.py b/car/chrysler/radar_interface.py new file mode 100755 index 0000000000..d982958422 --- /dev/null +++ b/car/chrysler/radar_interface.py @@ -0,0 +1,86 @@ +#!/usr/bin/env python3 +from opendbc.can.parser import CANParser +from cereal import car +from openpilot.selfdrive.car.interfaces import RadarInterfaceBase +from openpilot.selfdrive.car.chrysler.values import DBC + +RADAR_MSGS_C = list(range(0x2c2, 0x2d4+2, 2)) # c_ messages 706,...,724 +RADAR_MSGS_D = list(range(0x2a2, 0x2b4+2, 2)) # d_ messages +LAST_MSG = max(RADAR_MSGS_C + RADAR_MSGS_D) +NUMBER_MSGS = len(RADAR_MSGS_C) + len(RADAR_MSGS_D) + +def _create_radar_can_parser(car_fingerprint): + dbc = DBC[car_fingerprint]['radar'] + if dbc is None: + return None + + msg_n = len(RADAR_MSGS_C) + # list of [(signal name, message name or number), (...)] + # [('RADAR_STATE', 1024), + # ('LONG_DIST', 1072), + # ('LONG_DIST', 1073), + # ('LONG_DIST', 1074), + # ('LONG_DIST', 1075), + + messages = list(zip(RADAR_MSGS_C + + RADAR_MSGS_D, + [20] * msg_n + # 20Hz (0.05s) + [20] * msg_n, strict=True)) # 20Hz (0.05s) + + return CANParser(DBC[car_fingerprint]['radar'], messages, 1) + +def _address_to_track(address): + if address in RADAR_MSGS_C: + return (address - RADAR_MSGS_C[0]) // 2 + if address in RADAR_MSGS_D: + return (address - RADAR_MSGS_D[0]) // 2 + raise ValueError("radar received unexpected address %d" % address) + +class RadarInterface(RadarInterfaceBase): + def __init__(self, CP): + super().__init__(CP) + self.CP = CP + self.rcp = _create_radar_can_parser(CP.carFingerprint) + self.updated_messages = set() + self.trigger_msg = LAST_MSG + + def update(self, can_strings): + if self.rcp is None or self.CP.radarUnavailable: + return super().update(None) + + vls = self.rcp.update_strings(can_strings) + self.updated_messages.update(vls) + + if self.trigger_msg not in self.updated_messages: + return None + + ret = car.RadarData.new_message() + errors = [] + if not self.rcp.can_valid: + errors.append("canError") + ret.errors = errors + + for ii in self.updated_messages: # ii should be the message ID as a number + cpt = self.rcp.vl[ii] + trackId = _address_to_track(ii) + + if trackId not in self.pts: + self.pts[trackId] = car.RadarData.RadarPoint.new_message() + self.pts[trackId].trackId = trackId + self.pts[trackId].aRel = float('nan') + self.pts[trackId].yvRel = float('nan') + self.pts[trackId].measured = True + + if 'LONG_DIST' in cpt: # c_* message + self.pts[trackId].dRel = cpt['LONG_DIST'] # from front of car + # our lat_dist is positive to the right in car's frame. + # TODO what does yRel want? + self.pts[trackId].yRel = cpt['LAT_DIST'] # in car frame's y axis, left is positive + else: # d_* message + self.pts[trackId].vRel = cpt['REL_SPEED'] + + # We want a list, not a dictionary. Filter out LONG_DIST==0 because that means it's not valid. + ret.points = [x for x in self.pts.values() if x.dRel != 0] + + self.updated_messages.clear() + return ret diff --git a/car/chrysler/values.py b/car/chrysler/values.py new file mode 100644 index 0000000000..42ea94cf86 --- /dev/null +++ b/car/chrysler/values.py @@ -0,0 +1,156 @@ +from enum import IntFlag +from dataclasses import dataclass, field + +from cereal import car +from panda.python import uds +from openpilot.selfdrive.car import CarSpecs, DbcDict, PlatformConfig, Platforms, dbc_dict +from openpilot.selfdrive.car.docs_definitions import CarHarness, CarDocs, CarParts +from openpilot.selfdrive.car.fw_query_definitions import FwQueryConfig, Request, p16 + +Ecu = car.CarParams.Ecu + + +class ChryslerFlags(IntFlag): + # Detected flags + HIGHER_MIN_STEERING_SPEED = 1 + +@dataclass +class ChryslerCarDocs(CarDocs): + package: str = "Adaptive Cruise Control (ACC)" + car_parts: CarParts = field(default_factory=CarParts.common([CarHarness.fca])) + + +@dataclass +class ChryslerPlatformConfig(PlatformConfig): + dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict('chrysler_pacifica_2017_hybrid_generated', 'chrysler_pacifica_2017_hybrid_private_fusion')) + + +@dataclass(frozen=True) +class ChryslerCarSpecs(CarSpecs): + minSteerSpeed: float = 3.8 # m/s + + +class CAR(Platforms): + # Chrysler + CHRYSLER_PACIFICA_2017_HYBRID = ChryslerPlatformConfig( + [ChryslerCarDocs("Chrysler Pacifica Hybrid 2017")], + ChryslerCarSpecs(mass=2242., wheelbase=3.089, steerRatio=16.2), + ) + CHRYSLER_PACIFICA_2018_HYBRID = ChryslerPlatformConfig( + [ChryslerCarDocs("Chrysler Pacifica Hybrid 2018")], + CHRYSLER_PACIFICA_2017_HYBRID.specs, + ) + CHRYSLER_PACIFICA_2019_HYBRID = ChryslerPlatformConfig( + [ChryslerCarDocs("Chrysler Pacifica Hybrid 2019-23")], + CHRYSLER_PACIFICA_2017_HYBRID.specs, + ) + CHRYSLER_PACIFICA_2018 = ChryslerPlatformConfig( + [ChryslerCarDocs("Chrysler Pacifica 2017-18")], + CHRYSLER_PACIFICA_2017_HYBRID.specs, + ) + CHRYSLER_PACIFICA_2020 = ChryslerPlatformConfig( + [ + ChryslerCarDocs("Chrysler Pacifica 2019-20"), + ChryslerCarDocs("Chrysler Pacifica 2021-23", package="All"), + ], + CHRYSLER_PACIFICA_2017_HYBRID.specs, + ) + + # Dodge + DODGE_DURANGO = ChryslerPlatformConfig( + [ChryslerCarDocs("Dodge Durango 2020-21")], + CHRYSLER_PACIFICA_2017_HYBRID.specs, + ) + + # Jeep + JEEP_GRAND_CHEROKEE = ChryslerPlatformConfig( # includes 2017 Trailhawk + [ChryslerCarDocs("Jeep Grand Cherokee 2016-18", video_link="https://www.youtube.com/watch?v=eLR9o2JkuRk")], + ChryslerCarSpecs(mass=1778., wheelbase=2.71, steerRatio=16.7), + ) + + JEEP_GRAND_CHEROKEE_2019 = ChryslerPlatformConfig( # includes 2020 Trailhawk + [ChryslerCarDocs("Jeep Grand Cherokee 2019-21", video_link="https://www.youtube.com/watch?v=jBe4lWnRSu4")], + JEEP_GRAND_CHEROKEE.specs, + ) + + # Ram + RAM_1500_5TH_GEN = ChryslerPlatformConfig( + [ChryslerCarDocs("Ram 1500 2019-24", car_parts=CarParts.common([CarHarness.ram]))], + ChryslerCarSpecs(mass=2493., wheelbase=3.88, steerRatio=16.3, minSteerSpeed=14.5), + dbc_dict('chrysler_ram_dt_generated', None), + ) + RAM_HD_5TH_GEN = ChryslerPlatformConfig( + [ + ChryslerCarDocs("Ram 2500 2020-24", car_parts=CarParts.common([CarHarness.ram])), + ChryslerCarDocs("Ram 3500 2019-22", car_parts=CarParts.common([CarHarness.ram])), + ], + ChryslerCarSpecs(mass=3405., wheelbase=3.785, steerRatio=15.61, minSteerSpeed=16.), + dbc_dict('chrysler_ram_hd_generated', None), + ) + + +class CarControllerParams: + def __init__(self, CP): + self.STEER_STEP = 2 # 50 Hz + self.STEER_ERROR_MAX = 80 + if CP.carFingerprint in RAM_HD: + self.STEER_DELTA_UP = 14 + self.STEER_DELTA_DOWN = 14 + self.STEER_MAX = 361 # higher than this faults the EPS + elif CP.carFingerprint in RAM_DT: + self.STEER_DELTA_UP = 6 + self.STEER_DELTA_DOWN = 6 + self.STEER_MAX = 261 # EPS allows more, up to 350? + else: + self.STEER_DELTA_UP = 3 + self.STEER_DELTA_DOWN = 3 + self.STEER_MAX = 261 # higher than this faults the EPS + + +STEER_THRESHOLD = 120 + +RAM_DT = {CAR.RAM_1500_5TH_GEN, } +RAM_HD = {CAR.RAM_HD_5TH_GEN, } +RAM_CARS = RAM_DT | RAM_HD + + +CHRYSLER_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ + p16(0xf132) +CHRYSLER_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ + p16(0xf132) + +CHRYSLER_SOFTWARE_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ + p16(uds.DATA_IDENTIFIER_TYPE.SYSTEM_SUPPLIER_ECU_SOFTWARE_NUMBER) +CHRYSLER_SOFTWARE_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ + p16(uds.DATA_IDENTIFIER_TYPE.SYSTEM_SUPPLIER_ECU_SOFTWARE_NUMBER) + +CHRYSLER_RX_OFFSET = -0x280 + +FW_QUERY_CONFIG = FwQueryConfig( + requests=[ + Request( + [CHRYSLER_VERSION_REQUEST], + [CHRYSLER_VERSION_RESPONSE], + whitelist_ecus=[Ecu.abs, Ecu.eps, Ecu.srs, Ecu.fwdRadar, Ecu.fwdCamera, Ecu.combinationMeter], + rx_offset=CHRYSLER_RX_OFFSET, + bus=0, + ), + Request( + [CHRYSLER_VERSION_REQUEST], + [CHRYSLER_VERSION_RESPONSE], + whitelist_ecus=[Ecu.abs, Ecu.hybrid, Ecu.engine, Ecu.transmission], + bus=0, + ), + Request( + [CHRYSLER_SOFTWARE_VERSION_REQUEST], + [CHRYSLER_SOFTWARE_VERSION_RESPONSE], + whitelist_ecus=[Ecu.engine, Ecu.transmission], + bus=0, + ), + ], + extra_ecus=[ + (Ecu.abs, 0x7e4, None), # alt address for abs on hybrids, NOTE: not on all hybrid platforms + ], +) + +DBC = CAR.create_dbc_map() diff --git a/car/ford/__init__.py b/car/ford/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/car/ford/carcontroller.py b/car/ford/carcontroller.py new file mode 100644 index 0000000000..7be3b2ebe9 --- /dev/null +++ b/car/ford/carcontroller.py @@ -0,0 +1,120 @@ +from cereal import car +from opendbc.can.packer import CANPacker +from openpilot.common.numpy_fast import clip +from openpilot.selfdrive.car import apply_std_steer_angle_limits +from openpilot.selfdrive.car.ford import fordcan +from openpilot.selfdrive.car.ford.values import CarControllerParams, FordFlags +from openpilot.selfdrive.car.interfaces import CarControllerBase +from openpilot.selfdrive.controls.lib.drive_helpers import V_CRUISE_MAX + +LongCtrlState = car.CarControl.Actuators.LongControlState +VisualAlert = car.CarControl.HUDControl.VisualAlert + + +def apply_ford_curvature_limits(apply_curvature, apply_curvature_last, current_curvature, v_ego_raw): + # No blending at low speed due to lack of torque wind-up and inaccurate current curvature + if v_ego_raw > 9: + apply_curvature = clip(apply_curvature, current_curvature - CarControllerParams.CURVATURE_ERROR, + current_curvature + CarControllerParams.CURVATURE_ERROR) + + # Curvature rate limit after driver torque limit + apply_curvature = apply_std_steer_angle_limits(apply_curvature, apply_curvature_last, v_ego_raw, CarControllerParams) + + return clip(apply_curvature, -CarControllerParams.CURVATURE_MAX, CarControllerParams.CURVATURE_MAX) + + +class CarController(CarControllerBase): + def __init__(self, dbc_name, CP, VM): + self.CP = CP + self.VM = VM + self.packer = CANPacker(dbc_name) + self.CAN = fordcan.CanBus(CP) + self.frame = 0 + + self.apply_curvature_last = 0 + self.main_on_last = False + self.lkas_enabled_last = False + self.steer_alert_last = False + self.lead_distance_bars_last = None + + def update(self, CC, CS, now_nanos): + can_sends = [] + + actuators = CC.actuators + hud_control = CC.hudControl + + main_on = CS.out.cruiseState.available + steer_alert = hud_control.visualAlert in (VisualAlert.steerRequired, VisualAlert.ldw) + fcw_alert = hud_control.visualAlert == VisualAlert.fcw + + ### acc buttons ### + if CC.cruiseControl.cancel: + can_sends.append(fordcan.create_button_msg(self.packer, self.CAN.camera, CS.buttons_stock_values, cancel=True)) + can_sends.append(fordcan.create_button_msg(self.packer, self.CAN.main, CS.buttons_stock_values, cancel=True)) + elif CC.cruiseControl.resume and (self.frame % CarControllerParams.BUTTONS_STEP) == 0: + can_sends.append(fordcan.create_button_msg(self.packer, self.CAN.camera, CS.buttons_stock_values, resume=True)) + can_sends.append(fordcan.create_button_msg(self.packer, self.CAN.main, CS.buttons_stock_values, resume=True)) + # if stock lane centering isn't off, send a button press to toggle it off + # the stock system checks for steering pressed, and eventually disengages cruise control + elif CS.acc_tja_status_stock_values["Tja_D_Stat"] != 0 and (self.frame % CarControllerParams.ACC_UI_STEP) == 0: + can_sends.append(fordcan.create_button_msg(self.packer, self.CAN.camera, CS.buttons_stock_values, tja_toggle=True)) + + ### lateral control ### + # send steer msg at 20Hz + if (self.frame % CarControllerParams.STEER_STEP) == 0: + if CC.latActive: + # apply rate limits, curvature error limit, and clip to signal range + current_curvature = -CS.out.yawRate / max(CS.out.vEgoRaw, 0.1) + apply_curvature = apply_ford_curvature_limits(actuators.curvature, self.apply_curvature_last, current_curvature, CS.out.vEgoRaw) + else: + apply_curvature = 0. + + self.apply_curvature_last = apply_curvature + + if self.CP.flags & FordFlags.CANFD: + # TODO: extended mode + mode = 1 if CC.latActive else 0 + counter = (self.frame // CarControllerParams.STEER_STEP) % 0x10 + can_sends.append(fordcan.create_lat_ctl2_msg(self.packer, self.CAN, mode, 0., 0., -apply_curvature, 0., counter)) + else: + can_sends.append(fordcan.create_lat_ctl_msg(self.packer, self.CAN, CC.latActive, 0., 0., -apply_curvature, 0.)) + + # send lka msg at 33Hz + if (self.frame % CarControllerParams.LKA_STEP) == 0: + can_sends.append(fordcan.create_lka_msg(self.packer, self.CAN)) + + ### longitudinal control ### + # send acc msg at 50Hz + if self.CP.openpilotLongitudinalControl and (self.frame % CarControllerParams.ACC_CONTROL_STEP) == 0: + # Both gas and accel are in m/s^2, accel is used solely for braking + accel = clip(actuators.accel, CarControllerParams.ACCEL_MIN, CarControllerParams.ACCEL_MAX) + gas = accel + if not CC.longActive or gas < CarControllerParams.MIN_GAS: + gas = CarControllerParams.INACTIVE_GAS + stopping = CC.actuators.longControlState == LongCtrlState.stopping + can_sends.append(fordcan.create_acc_msg(self.packer, self.CAN, CC.longActive, gas, accel, stopping, v_ego_kph=V_CRUISE_MAX)) + + ### ui ### + send_ui = (self.main_on_last != main_on) or (self.lkas_enabled_last != CC.latActive) or (self.steer_alert_last != steer_alert) + # send lkas ui msg at 1Hz or if ui state changes + if (self.frame % CarControllerParams.LKAS_UI_STEP) == 0 or send_ui: + can_sends.append(fordcan.create_lkas_ui_msg(self.packer, self.CAN, main_on, CC.latActive, steer_alert, hud_control, CS.lkas_status_stock_values)) + + # send acc ui msg at 5Hz or if ui state changes + if hud_control.leadDistanceBars != self.lead_distance_bars_last: + send_ui = True + if (self.frame % CarControllerParams.ACC_UI_STEP) == 0 or send_ui: + can_sends.append(fordcan.create_acc_ui_msg(self.packer, self.CAN, self.CP, main_on, CC.latActive, + fcw_alert, CS.out.cruiseState.standstill, hud_control, + CS.acc_tja_status_stock_values)) + + self.main_on_last = main_on + self.lkas_enabled_last = CC.latActive + self.steer_alert_last = steer_alert + self.lead_distance_bars_last = hud_control.leadDistanceBars + + new_actuators = actuators.as_builder() + new_actuators.curvature = self.apply_curvature_last + + self.frame += 1 + return new_actuators, can_sends diff --git a/car/ford/carstate.py b/car/ford/carstate.py new file mode 100644 index 0000000000..78f48ec5c4 --- /dev/null +++ b/car/ford/carstate.py @@ -0,0 +1,174 @@ +from cereal import car +from opendbc.can.can_define import CANDefine +from opendbc.can.parser import CANParser +from openpilot.common.conversions import Conversions as CV +from openpilot.selfdrive.car.ford.fordcan import CanBus +from openpilot.selfdrive.car.ford.values import DBC, CarControllerParams, FordFlags +from openpilot.selfdrive.car.interfaces import CarStateBase + +GearShifter = car.CarState.GearShifter +TransmissionType = car.CarParams.TransmissionType + + +class CarState(CarStateBase): + def __init__(self, CP): + super().__init__(CP) + can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) + if CP.transmissionType == TransmissionType.automatic: + self.shifter_values = can_define.dv["Gear_Shift_by_Wire_FD1"]["TrnRng_D_RqGsm"] + + self.vehicle_sensors_valid = False + + self.prev_distance_button = 0 + self.distance_button = 0 + + def update(self, cp, cp_cam): + ret = car.CarState.new_message() + + # Occasionally on startup, the ABS module recalibrates the steering pinion offset, so we need to block engagement + # The vehicle usually recovers out of this state within a minute of normal driving + self.vehicle_sensors_valid = cp.vl["SteeringPinion_Data"]["StePinCompAnEst_D_Qf"] == 3 + + # car speed + ret.vEgoRaw = cp.vl["BrakeSysFeatures"]["Veh_V_ActlBrk"] * CV.KPH_TO_MS + ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) + ret.yawRate = cp.vl["Yaw_Data_FD1"]["VehYaw_W_Actl"] + ret.standstill = cp.vl["DesiredTorqBrk"]["VehStop_D_Stat"] == 1 + + # gas pedal + ret.gas = cp.vl["EngVehicleSpThrottle"]["ApedPos_Pc_ActlArb"] / 100. + ret.gasPressed = ret.gas > 1e-6 + + # brake pedal + ret.brake = cp.vl["BrakeSnData_4"]["BrkTot_Tq_Actl"] / 32756. # torque in Nm + ret.brakePressed = cp.vl["EngBrakeData"]["BpedDrvAppl_D_Actl"] == 2 + ret.parkingBrake = cp.vl["DesiredTorqBrk"]["PrkBrkStatus"] in (1, 2) + + # steering wheel + ret.steeringAngleDeg = cp.vl["SteeringPinion_Data"]["StePinComp_An_Est"] + ret.steeringTorque = cp.vl["EPAS_INFO"]["SteeringColumnTorque"] + ret.steeringPressed = self.update_steering_pressed(abs(ret.steeringTorque) > CarControllerParams.STEER_DRIVER_ALLOWANCE, 5) + ret.steerFaultTemporary = cp.vl["EPAS_INFO"]["EPAS_Failure"] == 1 + ret.steerFaultPermanent = cp.vl["EPAS_INFO"]["EPAS_Failure"] in (2, 3) + ret.espDisabled = cp.vl["Cluster_Info1_FD1"]["DrvSlipCtlMde_D_Rq"] != 0 # 0 is default mode + + if self.CP.flags & FordFlags.CANFD: + # this signal is always 0 on non-CAN FD cars + ret.steerFaultTemporary |= cp.vl["Lane_Assist_Data3_FD1"]["LatCtlSte_D_Stat"] not in (1, 2, 3) + + # cruise state + is_metric = cp.vl["INSTRUMENT_PANEL"]["METRIC_UNITS"] == 1 if not self.CP.flags & FordFlags.CANFD else False + ret.cruiseState.speed = cp.vl["EngBrakeData"]["Veh_V_DsplyCcSet"] * (CV.KPH_TO_MS if is_metric else CV.MPH_TO_MS) + ret.cruiseState.enabled = cp.vl["EngBrakeData"]["CcStat_D_Actl"] in (4, 5) + ret.cruiseState.available = cp.vl["EngBrakeData"]["CcStat_D_Actl"] in (3, 4, 5) + ret.cruiseState.nonAdaptive = cp.vl["Cluster_Info1_FD1"]["AccEnbl_B_RqDrv"] == 0 + ret.cruiseState.standstill = cp.vl["EngBrakeData"]["AccStopMde_D_Rq"] == 3 + ret.accFaulted = cp.vl["EngBrakeData"]["CcStat_D_Actl"] in (1, 2) + if not self.CP.openpilotLongitudinalControl: + ret.accFaulted = ret.accFaulted or cp_cam.vl["ACCDATA"]["CmbbDeny_B_Actl"] == 1 + + # gear + if self.CP.transmissionType == TransmissionType.automatic: + gear = self.shifter_values.get(cp.vl["Gear_Shift_by_Wire_FD1"]["TrnRng_D_RqGsm"]) + ret.gearShifter = self.parse_gear_shifter(gear) + elif self.CP.transmissionType == TransmissionType.manual: + ret.clutchPressed = cp.vl["Engine_Clutch_Data"]["CluPdlPos_Pc_Meas"] > 0 + if bool(cp.vl["BCM_Lamp_Stat_FD1"]["RvrseLghtOn_B_Stat"]): + ret.gearShifter = GearShifter.reverse + else: + ret.gearShifter = GearShifter.drive + + # safety + ret.stockFcw = bool(cp_cam.vl["ACCDATA_3"]["FcwVisblWarn_B_Rq"]) + ret.stockAeb = bool(cp_cam.vl["ACCDATA_2"]["CmbbBrkDecel_B_Rq"]) + + # button presses + ret.leftBlinker = cp.vl["Steering_Data_FD1"]["TurnLghtSwtch_D_Stat"] == 1 + ret.rightBlinker = cp.vl["Steering_Data_FD1"]["TurnLghtSwtch_D_Stat"] == 2 + # TODO: block this going to the camera otherwise it will enable stock TJA + ret.genericToggle = bool(cp.vl["Steering_Data_FD1"]["TjaButtnOnOffPress"]) + self.prev_distance_button = self.distance_button + self.distance_button = cp.vl["Steering_Data_FD1"]["AccButtnGapTogglePress"] + + # lock info + ret.doorOpen = any([cp.vl["BodyInfo_3_FD1"]["DrStatDrv_B_Actl"], cp.vl["BodyInfo_3_FD1"]["DrStatPsngr_B_Actl"], + cp.vl["BodyInfo_3_FD1"]["DrStatRl_B_Actl"], cp.vl["BodyInfo_3_FD1"]["DrStatRr_B_Actl"]]) + ret.seatbeltUnlatched = cp.vl["RCMStatusMessage2_FD1"]["FirstRowBuckleDriver"] == 2 + + # blindspot sensors + if self.CP.enableBsm: + cp_bsm = cp_cam if self.CP.flags & FordFlags.CANFD else cp + ret.leftBlindspot = cp_bsm.vl["Side_Detect_L_Stat"]["SodDetctLeft_D_Stat"] != 0 + ret.rightBlindspot = cp_bsm.vl["Side_Detect_R_Stat"]["SodDetctRight_D_Stat"] != 0 + + # Stock steering buttons so that we can passthru blinkers etc. + self.buttons_stock_values = cp.vl["Steering_Data_FD1"] + # Stock values from IPMA so that we can retain some stock functionality + self.acc_tja_status_stock_values = cp_cam.vl["ACCDATA_3"] + self.lkas_status_stock_values = cp_cam.vl["IPMA_Data"] + + return ret + + @staticmethod + def get_can_parser(CP): + messages = [ + # sig_address, frequency + ("VehicleOperatingModes", 100), + ("BrakeSysFeatures", 50), + ("Yaw_Data_FD1", 100), + ("DesiredTorqBrk", 50), + ("EngVehicleSpThrottle", 100), + ("BrakeSnData_4", 50), + ("EngBrakeData", 10), + ("Cluster_Info1_FD1", 10), + ("SteeringPinion_Data", 100), + ("EPAS_INFO", 50), + ("Steering_Data_FD1", 10), + ("BodyInfo_3_FD1", 2), + ("RCMStatusMessage2_FD1", 10), + ] + + if CP.flags & FordFlags.CANFD: + messages += [ + ("Lane_Assist_Data3_FD1", 33), + ] + else: + messages += [ + ("INSTRUMENT_PANEL", 1), + ] + + if CP.transmissionType == TransmissionType.automatic: + messages += [ + ("Gear_Shift_by_Wire_FD1", 10), + ] + elif CP.transmissionType == TransmissionType.manual: + messages += [ + ("Engine_Clutch_Data", 33), + ("BCM_Lamp_Stat_FD1", 1), + ] + + if CP.enableBsm and not (CP.flags & FordFlags.CANFD): + messages += [ + ("Side_Detect_L_Stat", 5), + ("Side_Detect_R_Stat", 5), + ] + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus(CP).main) + + @staticmethod + def get_cam_can_parser(CP): + messages = [ + # sig_address, frequency + ("ACCDATA", 50), + ("ACCDATA_2", 50), + ("ACCDATA_3", 5), + ("IPMA_Data", 1), + ] + + if CP.enableBsm and CP.flags & FordFlags.CANFD: + messages += [ + ("Side_Detect_L_Stat", 5), + ("Side_Detect_R_Stat", 5), + ] + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus(CP).camera) diff --git a/car/ford/fingerprints.py b/car/ford/fingerprints.py new file mode 100644 index 0000000000..2201072fa3 --- /dev/null +++ b/car/ford/fingerprints.py @@ -0,0 +1,166 @@ +from cereal import car +from openpilot.selfdrive.car.ford.values import CAR + +Ecu = car.CarParams.Ecu + +FW_VERSIONS = { + CAR.FORD_BRONCO_SPORT_MK1: { + (Ecu.eps, 0x730, None): [ + b'LX6C-14D003-AH\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LX6C-14D003-AK\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LX6C-14D003-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x760, None): [ + b'LX6C-2D053-RD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LX6C-2D053-RE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LX6C-2D053-RF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'LB5T-14D049-AB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'M1PT-14F397-AC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'M1PT-14F397-AD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, + CAR.FORD_ESCAPE_MK4: { + (Ecu.eps, 0x730, None): [ + b'LX6C-14D003-AF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LX6C-14D003-AH\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LX6C-14D003-AK\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LX6C-14D003-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x760, None): [ + b'LX6C-2D053-NS\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LX6C-2D053-NT\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LX6C-2D053-NY\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LX6C-2D053-SA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LX6C-2D053-SD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'LB5T-14D049-AB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'LJ6T-14F397-AD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LJ6T-14F397-AE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LV4T-14F397-GG\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, + CAR.FORD_EXPLORER_MK6: { + (Ecu.eps, 0x730, None): [ + b'L1MC-14D003-AJ\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'L1MC-14D003-AK\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'L1MC-14D003-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'M1MC-14D003-AB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'M1MC-14D003-AC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'P1MC-14D003-AA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x760, None): [ + b'L1MC-2D053-AJ\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'L1MC-2D053-BA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'L1MC-2D053-BB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'L1MC-2D053-BD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'L1MC-2D053-BF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'L1MC-2D053-BJ\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'L1MC-2D053-KB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'LB5T-14D049-AB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'LB5T-14F397-AD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LB5T-14F397-AE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LB5T-14F397-AF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LC5T-14F397-AE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LC5T-14F397-AH\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, + CAR.FORD_F_150_MK14: { + (Ecu.eps, 0x730, None): [ + b'ML3V-14D003-BC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x760, None): [ + b'PL34-2D053-CA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'ML3T-14D049-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'ML3T-14H102-ABR\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PJ6T-14H102-ABJ\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, + CAR.FORD_F_150_LIGHTNING_MK1: { + (Ecu.abs, 0x760, None): [ + b'PL38-2D053-AA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'ML3T-14H102-ABT\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'ML3T-14D049-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, + CAR.FORD_MUSTANG_MACH_E_MK1: { + (Ecu.eps, 0x730, None): [ + b'LJ9C-14D003-AM\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'LJ9C-14D003-CC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x760, None): [ + b'LK9C-2D053-CK\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'ML3T-14D049-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'ML3T-14H102-ABS\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, + CAR.FORD_FOCUS_MK4: { + (Ecu.eps, 0x730, None): [ + b'JX6C-14D003-AH\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x760, None): [ + b'JX61-2D053-CJ\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'JX7T-14D049-AC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'JX7T-14F397-AH\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, + CAR.FORD_MAVERICK_MK1: { + (Ecu.eps, 0x730, None): [ + b'NZ6C-14D003-AK\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'NZ6C-14D003-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x760, None): [ + b'NZ6C-2D053-AE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'NZ6C-2D053-AG\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PZ6C-2D053-ED\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PZ6C-2D053-EE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PZ6C-2D053-EF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'NZ6T-14D049-AA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'NZ6T-14F397-AC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, + CAR.FORD_RANGER_MK2: { + (Ecu.eps, 0x730, None): [ + b'NL14-14D003-AE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x760, None): [ + b'PB3C-2D053-ZD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'ML3T-14D049-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'PJ6T-14H102-ABJ\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, +} diff --git a/car/ford/fordcan.py b/car/ford/fordcan.py new file mode 100644 index 0000000000..2cfd61a191 --- /dev/null +++ b/car/ford/fordcan.py @@ -0,0 +1,340 @@ +from cereal import car +from openpilot.selfdrive.car import CanBusBase + +HUDControl = car.CarControl.HUDControl + + +class CanBus(CanBusBase): + def __init__(self, CP=None, fingerprint=None) -> None: + super().__init__(CP, fingerprint) + + @property + def main(self) -> int: + return self.offset + + @property + def radar(self) -> int: + return self.offset + 1 + + @property + def camera(self) -> int: + return self.offset + 2 + + +def calculate_lat_ctl2_checksum(mode: int, counter: int, dat: bytearray) -> int: + curvature = (dat[2] << 3) | ((dat[3]) >> 5) + curvature_rate = (dat[6] << 3) | ((dat[7]) >> 5) + path_angle = ((dat[3] & 0x1F) << 6) | ((dat[4]) >> 2) + path_offset = ((dat[4] & 0x3) << 8) | dat[5] + + checksum = mode + counter + for sig_val in (curvature, curvature_rate, path_angle, path_offset): + checksum += sig_val + (sig_val >> 8) + + return 0xFF - (checksum & 0xFF) + + +def create_lka_msg(packer, CAN: CanBus): + """ + Creates an empty CAN message for the Ford LKA Command. + + This command can apply "Lane Keeping Aid" manoeuvres, which are subject to the PSCM lockout. + + Frequency is 33Hz. + """ + + return packer.make_can_msg("Lane_Assist_Data1", CAN.main, {}) + + +def create_lat_ctl_msg(packer, CAN: CanBus, lat_active: bool, path_offset: float, path_angle: float, curvature: float, + curvature_rate: float): + """ + Creates a CAN message for the Ford TJA/LCA Command. + + This command can apply "Lane Centering" manoeuvres: continuous lane centering for traffic jam assist and highway + driving. It is not subject to the PSCM lockout. + + Ford lane centering command uses a third order polynomial to describe the road centerline. The polynomial is defined + by the following coefficients: + c0: lateral offset between the vehicle and the centerline (positive is right) + c1: heading angle between the vehicle and the centerline (positive is right) + c2: curvature of the centerline (positive is left) + c3: rate of change of curvature of the centerline + As the PSCM combines this information with other sensor data, such as the vehicle's yaw rate and speed, the steering + angle cannot be easily controlled. + + The PSCM should be configured to accept TJA/LCA commands before these commands will be processed. This can be done + using tools such as Forscan. + + Frequency is 20Hz. + """ + + values = { + "LatCtlRng_L_Max": 0, # Unknown [0|126] meter + "HandsOffCnfm_B_Rq": 0, # Unknown: 0=Inactive, 1=Active [0|1] + "LatCtl_D_Rq": 1 if lat_active else 0, # Mode: 0=None, 1=ContinuousPathFollowing, 2=InterventionLeft, + # 3=InterventionRight, 4-7=NotUsed [0|7] + "LatCtlRampType_D_Rq": 0, # Ramp speed: 0=Slow, 1=Medium, 2=Fast, 3=Immediate [0|3] + # Makes no difference with curvature control + "LatCtlPrecision_D_Rq": 1, # Precision: 0=Comfortable, 1=Precise, 2/3=NotUsed [0|3] + # The stock system always uses comfortable + "LatCtlPathOffst_L_Actl": path_offset, # Path offset [-5.12|5.11] meter + "LatCtlPath_An_Actl": path_angle, # Path angle [-0.5|0.5235] radians + "LatCtlCurv_NoRate_Actl": curvature_rate, # Curvature rate [-0.001024|0.00102375] 1/meter^2 + "LatCtlCurv_No_Actl": curvature, # Curvature [-0.02|0.02094] 1/meter + } + return packer.make_can_msg("LateralMotionControl", CAN.main, values) + + +def create_lat_ctl2_msg(packer, CAN: CanBus, mode: int, path_offset: float, path_angle: float, curvature: float, + curvature_rate: float, counter: int): + """ + Create a CAN message for the new Ford Lane Centering command. + + This message is used on the CAN FD platform and replaces the old LateralMotionControl message. It is similar but has + additional signals for a counter and checksum. + + Frequency is 20Hz. + """ + + values = { + "LatCtl_D2_Rq": mode, # Mode: 0=None, 1=PathFollowingLimitedMode, 2=PathFollowingExtendedMode, + # 3=SafeRampOut, 4-7=NotUsed [0|7] + "LatCtlRampType_D_Rq": 0, # 0=Slow, 1=Medium, 2=Fast, 3=Immediate [0|3] + "LatCtlPrecision_D_Rq": 1, # 0=Comfortable, 1=Precise, 2/3=NotUsed [0|3] + "LatCtlPathOffst_L_Actl": path_offset, # [-5.12|5.11] meter + "LatCtlPath_An_Actl": path_angle, # [-0.5|0.5235] radians + "LatCtlCurv_No_Actl": curvature, # [-0.02|0.02094] 1/meter + "LatCtlCrv_NoRate2_Actl": curvature_rate, # [-0.001024|0.001023] 1/meter^2 + "HandsOffCnfm_B_Rq": 0, # 0=Inactive, 1=Active [0|1] + "LatCtlPath_No_Cnt": counter, # [0|15] + "LatCtlPath_No_Cs": 0, # [0|255] + } + + # calculate checksum + dat = packer.make_can_msg("LateralMotionControl2", 0, values)[2] + values["LatCtlPath_No_Cs"] = calculate_lat_ctl2_checksum(mode, counter, dat) + + return packer.make_can_msg("LateralMotionControl2", CAN.main, values) + + +def create_acc_msg(packer, CAN: CanBus, long_active: bool, gas: float, accel: float, stopping: bool, v_ego_kph: float): + """ + Creates a CAN message for the Ford ACC Command. + + This command can be used to enable ACC, to set the ACC gas/brake/decel values + and to disable ACC. + + Frequency is 50Hz. + """ + decel = accel < 0 and long_active + values = { + "AccBrkTot_A_Rq": accel, # Brake total accel request: [-20|11.9449] m/s^2 + "Cmbb_B_Enbl": 1 if long_active else 0, # Enabled: 0=No, 1=Yes + "AccPrpl_A_Rq": gas, # Acceleration request: [-5|5.23] m/s^2 + "AccPrpl_A_Pred": -5.0, # Acceleration request: [-5|5.23] m/s^2 + "AccResumEnbl_B_Rq": 1 if long_active else 0, + "AccVeh_V_Trg": v_ego_kph, # Target speed: [0|255] km/h + # TODO: we may be able to improve braking response by utilizing pre-charging better + "AccBrkPrchg_B_Rq": 1 if decel else 0, # Pre-charge brake request: 0=No, 1=Yes + "AccBrkDecel_B_Rq": 1 if decel else 0, # Deceleration request: 0=Inactive, 1=Active + "AccStopStat_B_Rq": 1 if stopping else 0, + } + return packer.make_can_msg("ACCDATA", CAN.main, values) + + +def create_acc_ui_msg(packer, CAN: CanBus, CP, main_on: bool, enabled: bool, fcw_alert: bool, standstill: bool, + hud_control, stock_values: dict): + """ + Creates a CAN message for the Ford IPC adaptive cruise, forward collision warning and traffic jam + assist status. + + Stock functionality is maintained by passing through unmodified signals. + + Frequency is 5Hz. + """ + + # Tja_D_Stat + if enabled: + if hud_control.leftLaneDepart: + status = 3 # ActiveInterventionLeft + elif hud_control.rightLaneDepart: + status = 4 # ActiveInterventionRight + else: + status = 2 # Active + elif main_on: + if hud_control.leftLaneDepart: + status = 5 # ActiveWarningLeft + elif hud_control.rightLaneDepart: + status = 6 # ActiveWarningRight + else: + status = 1 # Standby + else: + status = 0 # Off + + values = {s: stock_values[s] for s in [ + "HaDsply_No_Cs", + "HaDsply_No_Cnt", + "AccStopStat_D_Dsply", # ACC stopped status message + "AccTrgDist2_D_Dsply", # ACC target distance + "AccStopRes_B_Dsply", + "TjaWarn_D_Rq", # TJA warning + "TjaMsgTxt_D_Dsply", # TJA text + "IaccLamp_D_Rq", # iACC status icon + "AccMsgTxt_D2_Rq", # ACC text + "FcwDeny_B_Dsply", # FCW disabled + "FcwMemStat_B_Actl", # FCW enabled setting + "AccTGap_B_Dsply", # ACC time gap display setting + "CadsAlignIncplt_B_Actl", + "AccFllwMde_B_Dsply", # ACC follow mode display setting + "CadsRadrBlck_B_Actl", + "CmbbPostEvnt_B_Dsply", # AEB event status + "AccStopMde_B_Dsply", # ACC stop mode display setting + "FcwMemSens_D_Actl", # FCW sensitivity setting + "FcwMsgTxt_D_Rq", # FCW text + "AccWarn_D_Dsply", # ACC warning + "FcwVisblWarn_B_Rq", # FCW visible alert + "FcwAudioWarn_B_Rq", # FCW audio alert + "AccTGap_D_Dsply", # ACC time gap + "AccMemEnbl_B_RqDrv", # ACC adaptive/normal setting + "FdaMem_B_Stat", # FDA enabled setting + ]} + + values.update({ + "Tja_D_Stat": status, # TJA status + }) + + if CP.openpilotLongitudinalControl: + values.update({ + "AccStopStat_D_Dsply": 2 if standstill else 0, # Stopping status text + "AccMsgTxt_D2_Rq": 0, # ACC text + "AccTGap_B_Dsply": 0, # Show time gap control UI + "AccFllwMde_B_Dsply": 1 if hud_control.leadVisible else 0, # Lead indicator + "AccStopMde_B_Dsply": 1 if standstill else 0, + "AccWarn_D_Dsply": 0, # ACC warning + "AccTGap_D_Dsply": hud_control.leadDistanceBars, # Time gap + }) + + # Forwards FCW alert from IPMA + if fcw_alert: + values["FcwVisblWarn_B_Rq"] = 1 # FCW visible alert + + return packer.make_can_msg("ACCDATA_3", CAN.main, values) + + +def create_lkas_ui_msg(packer, CAN: CanBus, main_on: bool, enabled: bool, steer_alert: bool, hud_control, + stock_values: dict): + """ + Creates a CAN message for the Ford IPC IPMA/LKAS status. + + Show the LKAS status with the "driver assist" lines in the IPC. + + Stock functionality is maintained by passing through unmodified signals. + + Frequency is 1Hz. + """ + + # LaActvStats_D_Dsply + # R Intvn Warn Supprs Avail No + # L + # Intvn 24 19 14 9 4 + # Warn 23 18 13 8 3 + # Supprs 22 17 12 7 2 + # Avail 21 16 11 6 1 + # No 20 15 10 5 0 + # + # TODO: test suppress state + if enabled: + lines = 0 # NoLeft_NoRight + if hud_control.leftLaneDepart: + lines += 4 + elif hud_control.leftLaneVisible: + lines += 1 + if hud_control.rightLaneDepart: + lines += 20 + elif hud_control.rightLaneVisible: + lines += 5 + elif main_on: + lines = 0 + else: + if hud_control.leftLaneDepart: + lines = 3 # WarnLeft_NoRight + elif hud_control.rightLaneDepart: + lines = 15 # NoLeft_WarnRight + else: + lines = 30 # LA_Off + + hands_on_wheel_dsply = 1 if steer_alert else 0 + + values = {s: stock_values[s] for s in [ + "FeatConfigIpmaActl", + "FeatNoIpmaActl", + "PersIndexIpma_D_Actl", + "AhbcRampingV_D_Rq", # AHB ramping + "LaDenyStats_B_Dsply", # LKAS error + "CamraDefog_B_Req", # Windshield heater? + "CamraStats_D_Dsply", # Camera status + "DasAlrtLvl_D_Dsply", # DAS alert level + "DasStats_D_Dsply", # DAS status + "DasWarn_D_Dsply", # DAS warning + "AhbHiBeam_D_Rq", # AHB status + "Passthru_63", + "Passthru_48", + ]} + + values.update({ + "LaActvStats_D_Dsply": lines, # LKAS status (lines) [0|31] + "LaHandsOff_D_Dsply": hands_on_wheel_dsply, # 0=HandsOn, 1=Level1 (w/o chime), 2=Level2 (w/ chime), 3=Suppressed + }) + return packer.make_can_msg("IPMA_Data", CAN.main, values) + + +def create_button_msg(packer, bus: int, stock_values: dict, cancel=False, resume=False, tja_toggle=False): + """ + Creates a CAN message for the Ford SCCM buttons/switches. + + Includes cruise control buttons, turn lights and more. + + Frequency is 10Hz. + """ + + values = {s: stock_values[s] for s in [ + "HeadLghtHiFlash_D_Stat", # SCCM Passthrough the remaining buttons + "TurnLghtSwtch_D_Stat", # SCCM Turn signal switch + "WiprFront_D_Stat", + "LghtAmb_D_Sns", + "AccButtnGapDecPress", + "AccButtnGapIncPress", + "AslButtnOnOffCnclPress", + "AslButtnOnOffPress", + "LaSwtchPos_D_Stat", + "CcAslButtnCnclResPress", + "CcAslButtnDeny_B_Actl", + "CcAslButtnIndxDecPress", + "CcAslButtnIndxIncPress", + "CcAslButtnOffCnclPress", + "CcAslButtnOnOffCncl", + "CcAslButtnOnPress", + "CcAslButtnResDecPress", + "CcAslButtnResIncPress", + "CcAslButtnSetDecPress", + "CcAslButtnSetIncPress", + "CcAslButtnSetPress", + "CcButtnOffPress", + "CcButtnOnOffCnclPress", + "CcButtnOnOffPress", + "CcButtnOnPress", + "HeadLghtHiFlash_D_Actl", + "HeadLghtHiOn_B_StatAhb", + "AhbStat_B_Dsply", + "AccButtnGapTogglePress", + "WiprFrontSwtch_D_Stat", + "HeadLghtHiCtrl_D_RqAhb", + ]} + + values.update({ + "CcAslButtnCnclPress": 1 if cancel else 0, # CC cancel button + "CcAsllButtnResPress": 1 if resume else 0, # CC resume button + "TjaButtnOnOffPress": 1 if tja_toggle else 0, # LCA/TJA toggle button + }) + return packer.make_can_msg("Steering_Data_FD1", bus, values) diff --git a/car/ford/interface.py b/car/ford/interface.py new file mode 100644 index 0000000000..2ef5d427e6 --- /dev/null +++ b/car/ford/interface.py @@ -0,0 +1,85 @@ +from cereal import car +from panda import Panda +from openpilot.common.conversions import Conversions as CV +from openpilot.selfdrive.car import create_button_events, get_safety_config +from openpilot.selfdrive.car.ford.fordcan import CanBus +from openpilot.selfdrive.car.ford.values import Ecu, FordFlags +from openpilot.selfdrive.car.interfaces import CarInterfaceBase + +ButtonType = car.CarState.ButtonEvent.Type +TransmissionType = car.CarParams.TransmissionType +GearShifter = car.CarState.GearShifter + + +class CarInterface(CarInterfaceBase): + @staticmethod + def _get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs): + ret.carName = "ford" + ret.dashcamOnly = bool(ret.flags & FordFlags.CANFD) + + ret.radarUnavailable = True + ret.steerControlType = car.CarParams.SteerControlType.angle + ret.steerActuatorDelay = 0.2 + ret.steerLimitTimer = 1.0 + + ret.longitudinalTuning.kpBP = [0.] + ret.longitudinalTuning.kpV = [0.5] + ret.longitudinalTuning.kiV = [0.] + + CAN = CanBus(fingerprint=fingerprint) + cfgs = [get_safety_config(car.CarParams.SafetyModel.ford)] + if CAN.main >= 4: + cfgs.insert(0, get_safety_config(car.CarParams.SafetyModel.noOutput)) + ret.safetyConfigs = cfgs + + ret.experimentalLongitudinalAvailable = True + if experimental_long: + ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_FORD_LONG_CONTROL + ret.openpilotLongitudinalControl = True + + if ret.flags & FordFlags.CANFD: + ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_FORD_CANFD + else: + # Lock out if the car does not have needed lateral and longitudinal control APIs. + # Note that we also check CAN for adaptive cruise, but no known signal for LCA exists + pscm_config = next((fw for fw in car_fw if fw.ecu == Ecu.eps and b'\x22\xDE\x01' in fw.request), None) + if pscm_config: + if len(pscm_config.fwVersion) != 24: + ret.dashcamOnly = True + else: + config_tja = pscm_config.fwVersion[7] # Traffic Jam Assist + config_lca = pscm_config.fwVersion[8] # Lane Centering Assist + if config_tja != 0xFF or config_lca != 0xFF: + ret.dashcamOnly = True + + # Auto Transmission: 0x732 ECU or Gear_Shift_by_Wire_FD1 + found_ecus = [fw.ecu for fw in car_fw] + if Ecu.shiftByWire in found_ecus or 0x5A in fingerprint[CAN.main] or docs: + ret.transmissionType = TransmissionType.automatic + else: + ret.transmissionType = TransmissionType.manual + ret.minEnableSpeed = 20.0 * CV.MPH_TO_MS + + # BSM: Side_Detect_L_Stat, Side_Detect_R_Stat + # TODO: detect bsm in car_fw? + ret.enableBsm = 0x3A6 in fingerprint[CAN.main] and 0x3A7 in fingerprint[CAN.main] + + # LCA can steer down to zero + ret.minSteerSpeed = 0. + + ret.autoResumeSng = ret.minEnableSpeed == -1. + ret.centerToFront = ret.wheelbase * 0.44 + return ret + + def _update(self, c): + ret = self.CS.update(self.cp, self.cp_cam) + + ret.buttonEvents = create_button_events(self.CS.distance_button, self.CS.prev_distance_button, {1: ButtonType.gapAdjustCruise}) + + events = self.create_common_events(ret, extra_gears=[GearShifter.manumatic]) + if not self.CS.vehicle_sensors_valid: + events.add(car.CarEvent.EventName.vehicleSensorsInvalid) + + ret.events = events.to_msg() + + return ret diff --git a/car/ford/radar_interface.py b/car/ford/radar_interface.py new file mode 100644 index 0000000000..209bbebae3 --- /dev/null +++ b/car/ford/radar_interface.py @@ -0,0 +1,143 @@ +from math import cos, sin +from cereal import car +from opendbc.can.parser import CANParser +from openpilot.common.conversions import Conversions as CV +from openpilot.selfdrive.car.ford.fordcan import CanBus +from openpilot.selfdrive.car.ford.values import DBC, RADAR +from openpilot.selfdrive.car.interfaces import RadarInterfaceBase + +DELPHI_ESR_RADAR_MSGS = list(range(0x500, 0x540)) + +DELPHI_MRR_RADAR_START_ADDR = 0x120 +DELPHI_MRR_RADAR_MSG_COUNT = 64 + + +def _create_delphi_esr_radar_can_parser(CP) -> CANParser: + msg_n = len(DELPHI_ESR_RADAR_MSGS) + messages = list(zip(DELPHI_ESR_RADAR_MSGS, [20] * msg_n, strict=True)) + + return CANParser(RADAR.DELPHI_ESR, messages, CanBus(CP).radar) + + +def _create_delphi_mrr_radar_can_parser(CP) -> CANParser: + messages = [] + + for i in range(1, DELPHI_MRR_RADAR_MSG_COUNT + 1): + msg = f"MRR_Detection_{i:03d}" + messages += [(msg, 20)] + + return CANParser(RADAR.DELPHI_MRR, messages, CanBus(CP).radar) + + +class RadarInterface(RadarInterfaceBase): + def __init__(self, CP): + super().__init__(CP) + + self.updated_messages = set() + self.track_id = 0 + self.radar = DBC[CP.carFingerprint]['radar'] + if self.radar is None or CP.radarUnavailable: + self.rcp = None + elif self.radar == RADAR.DELPHI_ESR: + self.rcp = _create_delphi_esr_radar_can_parser(CP) + self.trigger_msg = DELPHI_ESR_RADAR_MSGS[-1] + self.valid_cnt = {key: 0 for key in DELPHI_ESR_RADAR_MSGS} + elif self.radar == RADAR.DELPHI_MRR: + self.rcp = _create_delphi_mrr_radar_can_parser(CP) + self.trigger_msg = DELPHI_MRR_RADAR_START_ADDR + DELPHI_MRR_RADAR_MSG_COUNT - 1 + else: + raise ValueError(f"Unsupported radar: {self.radar}") + + def update(self, can_strings): + if self.rcp is None: + return super().update(None) + + vls = self.rcp.update_strings(can_strings) + self.updated_messages.update(vls) + + if self.trigger_msg not in self.updated_messages: + return None + + ret = car.RadarData.new_message() + errors = [] + if not self.rcp.can_valid: + errors.append("canError") + ret.errors = errors + + if self.radar == RADAR.DELPHI_ESR: + self._update_delphi_esr() + elif self.radar == RADAR.DELPHI_MRR: + self._update_delphi_mrr() + + ret.points = list(self.pts.values()) + self.updated_messages.clear() + return ret + + def _update_delphi_esr(self): + for ii in sorted(self.updated_messages): + cpt = self.rcp.vl[ii] + + if cpt['X_Rel'] > 0.00001: + self.valid_cnt[ii] = 0 # reset counter + + if cpt['X_Rel'] > 0.00001: + self.valid_cnt[ii] += 1 + else: + self.valid_cnt[ii] = max(self.valid_cnt[ii] - 1, 0) + #print ii, self.valid_cnt[ii], cpt['VALID'], cpt['X_Rel'], cpt['Angle'] + + # radar point only valid if there have been enough valid measurements + if self.valid_cnt[ii] > 0: + if ii not in self.pts: + self.pts[ii] = car.RadarData.RadarPoint.new_message() + self.pts[ii].trackId = self.track_id + self.track_id += 1 + self.pts[ii].dRel = cpt['X_Rel'] # from front of car + self.pts[ii].yRel = cpt['X_Rel'] * cpt['Angle'] * CV.DEG_TO_RAD # in car frame's y axis, left is positive + self.pts[ii].vRel = cpt['V_Rel'] + self.pts[ii].aRel = float('nan') + self.pts[ii].yvRel = float('nan') + self.pts[ii].measured = True + else: + if ii in self.pts: + del self.pts[ii] + + def _update_delphi_mrr(self): + for ii in range(1, DELPHI_MRR_RADAR_MSG_COUNT + 1): + msg = self.rcp.vl[f"MRR_Detection_{ii:03d}"] + + # SCAN_INDEX rotates through 0..3 on each message + # treat these as separate points + scanIndex = msg[f"CAN_SCAN_INDEX_2LSB_{ii:02d}"] + i = (ii - 1) * 4 + scanIndex + + if i not in self.pts: + self.pts[i] = car.RadarData.RadarPoint.new_message() + self.pts[i].trackId = self.track_id + self.pts[i].aRel = float('nan') + self.pts[i].yvRel = float('nan') + self.track_id += 1 + + valid = bool(msg[f"CAN_DET_VALID_LEVEL_{ii:02d}"]) + + if valid: + azimuth = msg[f"CAN_DET_AZIMUTH_{ii:02d}"] # rad [-3.1416|3.13964] + dist = msg[f"CAN_DET_RANGE_{ii:02d}"] # m [0|255.984] + distRate = msg[f"CAN_DET_RANGE_RATE_{ii:02d}"] # m/s [-128|127.984] + dRel = cos(azimuth) * dist # m from front of car + yRel = -sin(azimuth) * dist # in car frame's y axis, left is positive + + # delphi doesn't notify of track switches, so do it manually + # TODO: refactor this to radard if more radars behave this way + if abs(self.pts[i].vRel - distRate) > 2 or abs(self.pts[i].dRel - dRel) > 5: + self.track_id += 1 + self.pts[i].trackId = self.track_id + + self.pts[i].dRel = dRel + self.pts[i].yRel = yRel + self.pts[i].vRel = distRate + + self.pts[i].measured = True + + else: + del self.pts[i] diff --git a/car/ford/tests/__init__.py b/car/ford/tests/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/car/ford/tests/print_platform_codes.py b/car/ford/tests/print_platform_codes.py new file mode 100755 index 0000000000..670199980a --- /dev/null +++ b/car/ford/tests/print_platform_codes.py @@ -0,0 +1,30 @@ +#!/usr/bin/env python3 +from collections import defaultdict + +from cereal import car +from openpilot.selfdrive.car.ford.values import get_platform_codes +from openpilot.selfdrive.car.ford.fingerprints import FW_VERSIONS + +Ecu = car.CarParams.Ecu +ECU_NAME = {v: k for k, v in Ecu.schema.enumerants.items()} + + +if __name__ == "__main__": + cars_for_code: defaultdict = defaultdict(lambda: defaultdict(set)) + + for car_model, ecus in FW_VERSIONS.items(): + print(car_model) + for ecu in sorted(ecus, key=lambda x: int(x[0])): + platform_codes = get_platform_codes(ecus[ecu]) + for code in platform_codes: + cars_for_code[ecu][code].add(car_model) + + print(f' (Ecu.{ECU_NAME[ecu[0]]}, {hex(ecu[1])}, {ecu[2]}):') + print(f' Codes: {sorted(platform_codes)}') + print() + + print('\nCar models vs. platform codes:') + for ecu, codes in cars_for_code.items(): + print(f' (Ecu.{ECU_NAME[ecu[0]]}, {hex(ecu[1])}, {ecu[2]}):') + for code, cars in codes.items(): + print(f' {code!r}: {sorted(map(str, cars))}') diff --git a/car/ford/tests/test_ford.py b/car/ford/tests/test_ford.py new file mode 100644 index 0000000000..b1a19017d4 --- /dev/null +++ b/car/ford/tests/test_ford.py @@ -0,0 +1,143 @@ +import random +from collections.abc import Iterable + +import capnp +from hypothesis import settings, given, strategies as st +from parameterized import parameterized + +from cereal import car +from openpilot.selfdrive.car.fw_versions import build_fw_dict +from openpilot.selfdrive.car.ford.values import CAR, FW_QUERY_CONFIG, FW_PATTERN, get_platform_codes +from openpilot.selfdrive.car.ford.fingerprints import FW_VERSIONS + +Ecu = car.CarParams.Ecu + + +ECU_ADDRESSES = { + Ecu.eps: 0x730, # Power Steering Control Module (PSCM) + Ecu.abs: 0x760, # Anti-Lock Brake System (ABS) + Ecu.fwdRadar: 0x764, # Cruise Control Module (CCM) + Ecu.fwdCamera: 0x706, # Image Processing Module A (IPMA) + Ecu.engine: 0x7E0, # Powertrain Control Module (PCM) + Ecu.shiftByWire: 0x732, # Gear Shift Module (GSM) + Ecu.debug: 0x7D0, # Accessory Protocol Interface Module (APIM) +} + + +ECU_PART_NUMBER = { + Ecu.eps: [ + b"14D003", + ], + Ecu.abs: [ + b"2D053", + ], + Ecu.fwdRadar: [ + b"14D049", + ], + Ecu.fwdCamera: [ + b"14F397", # Ford Q3 + b"14H102", # Ford Q4 + ], +} + + +class TestFordFW: + def test_fw_query_config(self): + for (ecu, addr, subaddr) in FW_QUERY_CONFIG.extra_ecus: + assert ecu in ECU_ADDRESSES, "Unknown ECU" + assert addr == ECU_ADDRESSES[ecu], "ECU address mismatch" + assert subaddr is None, "Unexpected ECU subaddress" + + @parameterized.expand(FW_VERSIONS.items()) + def test_fw_versions(self, car_model: str, fw_versions: dict[tuple[capnp.lib.capnp._EnumModule, int, int | None], Iterable[bytes]]): + for (ecu, addr, subaddr), fws in fw_versions.items(): + assert ecu in ECU_PART_NUMBER, "Unexpected ECU" + assert addr == ECU_ADDRESSES[ecu], "ECU address mismatch" + assert subaddr is None, "Unexpected ECU subaddress" + + for fw in fws: + assert len(fw) == 24, "Expected ECU response to be 24 bytes" + + match = FW_PATTERN.match(fw) + assert match is not None, f"Unable to parse FW: {fw!r}" + if match: + part_number = match.group("part_number") + assert part_number in ECU_PART_NUMBER[ecu], f"Unexpected part number for {fw!r}" + + codes = get_platform_codes([fw]) + assert 1 == len(codes), f"Unable to parse FW: {fw!r}" + + @settings(max_examples=100) + @given(data=st.data()) + def test_platform_codes_fuzzy_fw(self, data): + """Ensure function doesn't raise an exception""" + fw_strategy = st.lists(st.binary()) + fws = data.draw(fw_strategy) + get_platform_codes(fws) + + def test_platform_codes_spot_check(self): + # Asserts basic platform code parsing behavior for a few cases + results = get_platform_codes([ + b"JX6A-14C204-BPL\x00\x00\x00\x00\x00\x00\x00\x00\x00", + b"NZ6T-14F397-AC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00", + b"PJ6T-14H102-ABJ\x00\x00\x00\x00\x00\x00\x00\x00\x00", + b"LB5A-14C204-EAC\x00\x00\x00\x00\x00\x00\x00\x00\x00", + ]) + assert results == {(b"X6A", b"J"), (b"Z6T", b"N"), (b"J6T", b"P"), (b"B5A", b"L")} + + def test_fuzzy_match(self): + for platform, fw_by_addr in FW_VERSIONS.items(): + # Ensure there's no overlaps in platform codes + for _ in range(20): + car_fw = [] + for ecu, fw_versions in fw_by_addr.items(): + ecu_name, addr, sub_addr = ecu + fw = random.choice(fw_versions) + car_fw.append({"ecu": ecu_name, "fwVersion": fw, "address": addr, + "subAddress": 0 if sub_addr is None else sub_addr}) + + CP = car.CarParams.new_message(carFw=car_fw) + matches = FW_QUERY_CONFIG.match_fw_to_car_fuzzy(build_fw_dict(CP.carFw), CP.carVin, FW_VERSIONS) + assert matches == {platform} + + def test_match_fw_fuzzy(self): + offline_fw = { + (Ecu.eps, 0x730, None): [ + b"L1MC-14D003-AJ\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00", + b"L1MC-14D003-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00", + ], + (Ecu.abs, 0x760, None): [ + b"L1MC-2D053-BA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00", + b"L1MC-2D053-BD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00", + ], + (Ecu.fwdRadar, 0x764, None): [ + b"LB5T-14D049-AB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00", + b"LB5T-14D049-AD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00", + ], + # We consider all model year hints for ECU, even with different platform codes + (Ecu.fwdCamera, 0x706, None): [ + b"LB5T-14F397-AD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00", + b"NC5T-14F397-AF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00", + ], + } + expected_fingerprint = CAR.FORD_EXPLORER_MK6 + + # ensure that we fuzzy match on all non-exact FW with changed revisions + live_fw = { + (0x730, None): {b"L1MC-14D003-XX\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00"}, + (0x760, None): {b"L1MC-2D053-XX\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00"}, + (0x764, None): {b"LB5T-14D049-XX\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00"}, + (0x706, None): {b"LB5T-14F397-XX\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00"}, + } + candidates = FW_QUERY_CONFIG.match_fw_to_car_fuzzy(live_fw, '', {expected_fingerprint: offline_fw}) + assert candidates == {expected_fingerprint} + + # model year hint in between the range should match + live_fw[(0x706, None)] = {b"MB5T-14F397-XX\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00"} + candidates = FW_QUERY_CONFIG.match_fw_to_car_fuzzy(live_fw, '', {expected_fingerprint: offline_fw,}) + assert candidates == {expected_fingerprint} + + # unseen model year hint should not match + live_fw[(0x760, None)] = {b"M1MC-2D053-XX\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00"} + candidates = FW_QUERY_CONFIG.match_fw_to_car_fuzzy(live_fw, '', {expected_fingerprint: offline_fw}) + assert len(candidates) == 0, "Should not match new model year hint" diff --git a/car/ford/values.py b/car/ford/values.py new file mode 100644 index 0000000000..b1868bfa9b --- /dev/null +++ b/car/ford/values.py @@ -0,0 +1,279 @@ +import copy +import re +from dataclasses import dataclass, field, replace +from enum import Enum, IntFlag + +import panda.python.uds as uds +from cereal import car +from openpilot.selfdrive.car import AngleRateLimit, CarSpecs, dbc_dict, DbcDict, PlatformConfig, Platforms +from openpilot.selfdrive.car.docs_definitions import CarFootnote, CarHarness, CarDocs, CarParts, Column, \ + Device +from openpilot.selfdrive.car.fw_query_definitions import FwQueryConfig, LiveFwVersions, OfflineFwVersions, Request, StdQueries, p16 + +Ecu = car.CarParams.Ecu + + +class CarControllerParams: + STEER_STEP = 5 # LateralMotionControl, 20Hz + LKA_STEP = 3 # Lane_Assist_Data1, 33Hz + ACC_CONTROL_STEP = 2 # ACCDATA, 50Hz + LKAS_UI_STEP = 100 # IPMA_Data, 1Hz + ACC_UI_STEP = 20 # ACCDATA_3, 5Hz + BUTTONS_STEP = 5 # Steering_Data_FD1, 10Hz, but send twice as fast + + CURVATURE_MAX = 0.02 # Max curvature for steering command, m^-1 + STEER_DRIVER_ALLOWANCE = 1.0 # Driver intervention threshold, Nm + + # Curvature rate limits + # The curvature signal is limited to 0.003 to 0.009 m^-1/sec by the EPS depending on speed and direction + # Limit to ~2 m/s^3 up, ~3 m/s^3 down at 75 mph + # Worst case, the low speed limits will allow 4.3 m/s^3 up, 4.9 m/s^3 down at 75 mph + ANGLE_RATE_LIMIT_UP = AngleRateLimit(speed_bp=[5, 25], angle_v=[0.0002, 0.0001]) + ANGLE_RATE_LIMIT_DOWN = AngleRateLimit(speed_bp=[5, 25], angle_v=[0.000225, 0.00015]) + CURVATURE_ERROR = 0.002 # ~6 degrees at 10 m/s, ~10 degrees at 35 m/s + + ACCEL_MAX = 2.0 # m/s^2 max acceleration + ACCEL_MIN = -3.5 # m/s^2 max deceleration + MIN_GAS = -0.5 + INACTIVE_GAS = -5.0 + + def __init__(self, CP): + pass + + +class FordFlags(IntFlag): + # Static flags + CANFD = 1 + + +class RADAR: + DELPHI_ESR = 'ford_fusion_2018_adas' + DELPHI_MRR = 'FORD_CADS' + + +class Footnote(Enum): + FOCUS = CarFootnote( + "Refers only to the Focus Mk4 (C519) available in Europe/China/Taiwan/Australasia, not the Focus Mk3 (C346) in " + + "North and South America/Southeast Asia.", + Column.MODEL, + ) + + +@dataclass +class FordCarDocs(CarDocs): + package: str = "Co-Pilot360 Assist+" + hybrid: bool = False + plug_in_hybrid: bool = False + + def init_make(self, CP: car.CarParams): + harness = CarHarness.ford_q4 if CP.flags & FordFlags.CANFD else CarHarness.ford_q3 + if CP.carFingerprint in (CAR.FORD_BRONCO_SPORT_MK1, CAR.FORD_MAVERICK_MK1, CAR.FORD_F_150_MK14, CAR.FORD_F_150_LIGHTNING_MK1): + self.car_parts = CarParts([Device.threex_angled_mount, harness]) + else: + self.car_parts = CarParts([Device.threex, harness]) + + +@dataclass +class FordPlatformConfig(PlatformConfig): + dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict('ford_lincoln_base_pt', RADAR.DELPHI_MRR)) + + def init(self): + for car_docs in list(self.car_docs): + if car_docs.hybrid: + name = f"{car_docs.make} {car_docs.model} Hybrid {car_docs.years}" + self.car_docs.append(replace(copy.deepcopy(car_docs), name=name)) + if car_docs.plug_in_hybrid: + name = f"{car_docs.make} {car_docs.model} Plug-in Hybrid {car_docs.years}" + self.car_docs.append(replace(copy.deepcopy(car_docs), name=name)) + + +@dataclass +class FordCANFDPlatformConfig(FordPlatformConfig): + dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict('ford_lincoln_base_pt', None)) + + def init(self): + super().init() + self.flags |= FordFlags.CANFD + + +class CAR(Platforms): + FORD_BRONCO_SPORT_MK1 = FordPlatformConfig( + [FordCarDocs("Ford Bronco Sport 2021-23")], + CarSpecs(mass=1625, wheelbase=2.67, steerRatio=17.7), + ) + FORD_ESCAPE_MK4 = FordPlatformConfig( + [ + FordCarDocs("Ford Escape 2020-22", hybrid=True, plug_in_hybrid=True), + FordCarDocs("Ford Kuga 2020-22", "Adaptive Cruise Control with Lane Centering", hybrid=True, plug_in_hybrid=True), + ], + CarSpecs(mass=1750, wheelbase=2.71, steerRatio=16.7), + ) + FORD_EXPLORER_MK6 = FordPlatformConfig( + [ + FordCarDocs("Ford Explorer 2020-23", hybrid=True), # Hybrid: Limited and Platinum only + FordCarDocs("Lincoln Aviator 2020-23", "Co-Pilot360 Plus", plug_in_hybrid=True), # Hybrid: Grand Touring only + ], + CarSpecs(mass=2050, wheelbase=3.025, steerRatio=16.8), + ) + FORD_F_150_MK14 = FordCANFDPlatformConfig( + [FordCarDocs("Ford F-150 2022-23", "Co-Pilot360 Active 2.0", hybrid=True)], + CarSpecs(mass=2000, wheelbase=3.69, steerRatio=17.0), + ) + FORD_F_150_LIGHTNING_MK1 = FordCANFDPlatformConfig( + [FordCarDocs("Ford F-150 Lightning 2021-23", "Co-Pilot360 Active 2.0")], + CarSpecs(mass=2948, wheelbase=3.70, steerRatio=16.9), + ) + FORD_FOCUS_MK4 = FordPlatformConfig( + [FordCarDocs("Ford Focus 2018", "Adaptive Cruise Control with Lane Centering", footnotes=[Footnote.FOCUS], hybrid=True)], # mHEV only + CarSpecs(mass=1350, wheelbase=2.7, steerRatio=15.0), + ) + FORD_MAVERICK_MK1 = FordPlatformConfig( + [ + FordCarDocs("Ford Maverick 2022", "LARIAT Luxury", hybrid=True), + FordCarDocs("Ford Maverick 2023-24", "Co-Pilot360 Assist", hybrid=True), + ], + CarSpecs(mass=1650, wheelbase=3.076, steerRatio=17.0), + ) + FORD_MUSTANG_MACH_E_MK1 = FordCANFDPlatformConfig( + [FordCarDocs("Ford Mustang Mach-E 2021-23", "Co-Pilot360 Active 2.0")], + CarSpecs(mass=2200, wheelbase=2.984, steerRatio=17.0), # TODO: check steer ratio + ) + FORD_RANGER_MK2 = FordCANFDPlatformConfig( + [FordCarDocs("Ford Ranger 2024", "Adaptive Cruise Control with Lane Centering")], + CarSpecs(mass=2000, wheelbase=3.27, steerRatio=17.0), + ) + + +# FW response contains a combined software and part number +# A-Z except no I, O or W +# e.g. NZ6A-14C204-AAA +# 1222-333333-444 +# 1 = Model year hint (approximates model year/generation) +# 2 = Platform hint +# 3 = Part number +# 4 = Software version +FW_ALPHABET = b'A-HJ-NP-VX-Z' +FW_PATTERN = re.compile(b'^(?P[' + FW_ALPHABET + b'])' + + b'(?P[0-9' + FW_ALPHABET + b']{3})-' + + b'(?P[0-9' + FW_ALPHABET + b']{5,6})-' + + b'(?P[' + FW_ALPHABET + b']{2,})\x00*$') + + +def get_platform_codes(fw_versions: list[bytes] | set[bytes]) -> set[tuple[bytes, bytes]]: + codes = set() + for fw in fw_versions: + match = FW_PATTERN.match(fw) + if match is not None: + codes.add((match.group('platform_hint'), match.group('model_year_hint'))) + + return codes + + +def match_fw_to_car_fuzzy(live_fw_versions: LiveFwVersions, vin: str, offline_fw_versions: OfflineFwVersions) -> set[str]: + candidates: set[str] = set() + + for candidate, fws in offline_fw_versions.items(): + # Keep track of ECUs which pass all checks (platform hint, within model year hint range) + valid_found_ecus = set() + valid_expected_ecus = {ecu[1:] for ecu in fws if ecu[0] in PLATFORM_CODE_ECUS} + for ecu, expected_versions in fws.items(): + addr = ecu[1:] + # Only check ECUs expected to have platform codes + if ecu[0] not in PLATFORM_CODE_ECUS: + continue + + # Expected platform codes & model year hints + codes = get_platform_codes(expected_versions) + expected_platform_codes = {code for code, _ in codes} + expected_model_year_hints = {model_year_hint for _, model_year_hint in codes} + + # Found platform codes & model year hints + codes = get_platform_codes(live_fw_versions.get(addr, set())) + found_platform_codes = {code for code, _ in codes} + found_model_year_hints = {model_year_hint for _, model_year_hint in codes} + + # Check platform code matches for any found versions + if not any(found_platform_code in expected_platform_codes for found_platform_code in found_platform_codes): + break + + # Check any model year hint within range in the database. Note that some models have more than one + # platform code per ECU which we don't consider as separate ranges + if not any(min(expected_model_year_hints) <= found_model_year_hint <= max(expected_model_year_hints) for + found_model_year_hint in found_model_year_hints): + break + + valid_found_ecus.add(addr) + + # If all live ECUs pass all checks for candidate, add it as a match + if valid_expected_ecus.issubset(valid_found_ecus): + candidates.add(candidate) + + return candidates + + +# All of these ECUs must be present and are expected to have platform codes we can match +PLATFORM_CODE_ECUS = (Ecu.abs, Ecu.fwdCamera, Ecu.fwdRadar, Ecu.eps) + +DATA_IDENTIFIER_FORD_ASBUILT = 0xDE00 + +ASBUILT_BLOCKS: list[tuple[int, list]] = [ + (1, [Ecu.debug, Ecu.fwdCamera, Ecu.eps]), + (2, [Ecu.abs, Ecu.debug, Ecu.eps]), + (3, [Ecu.abs, Ecu.debug, Ecu.eps]), + (4, [Ecu.debug, Ecu.fwdCamera]), + (5, [Ecu.debug]), + (6, [Ecu.debug]), + (7, [Ecu.debug]), + (8, [Ecu.debug]), + (9, [Ecu.debug]), + (16, [Ecu.debug, Ecu.fwdCamera]), + (18, [Ecu.fwdCamera]), + (20, [Ecu.fwdCamera]), + (21, [Ecu.fwdCamera]), +] + + +def ford_asbuilt_block_request(block_id: int): + return bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + p16(DATA_IDENTIFIER_FORD_ASBUILT + block_id - 1) + + +def ford_asbuilt_block_response(block_id: int): + return bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + p16(DATA_IDENTIFIER_FORD_ASBUILT + block_id - 1) + + +FW_QUERY_CONFIG = FwQueryConfig( + requests=[ + # CAN and CAN FD queries are combined. + # FIXME: For CAN FD, ECUs respond with frames larger than 8 bytes on the powertrain bus + Request( + [StdQueries.TESTER_PRESENT_REQUEST, StdQueries.MANUFACTURER_SOFTWARE_VERSION_REQUEST], + [StdQueries.TESTER_PRESENT_RESPONSE, StdQueries.MANUFACTURER_SOFTWARE_VERSION_RESPONSE], + whitelist_ecus=[Ecu.abs, Ecu.debug, Ecu.engine, Ecu.eps, Ecu.fwdCamera, Ecu.fwdRadar, Ecu.shiftByWire], + logging=True, + ), + Request( + [StdQueries.TESTER_PRESENT_REQUEST, StdQueries.MANUFACTURER_SOFTWARE_VERSION_REQUEST], + [StdQueries.TESTER_PRESENT_RESPONSE, StdQueries.MANUFACTURER_SOFTWARE_VERSION_RESPONSE], + whitelist_ecus=[Ecu.abs, Ecu.debug, Ecu.engine, Ecu.eps, Ecu.fwdCamera, Ecu.fwdRadar, Ecu.shiftByWire], + bus=0, + auxiliary=True, + ), + *[Request( + [StdQueries.TESTER_PRESENT_REQUEST, ford_asbuilt_block_request(block_id)], + [StdQueries.TESTER_PRESENT_RESPONSE, ford_asbuilt_block_response(block_id)], + whitelist_ecus=ecus, + bus=0, + logging=True, + ) for block_id, ecus in ASBUILT_BLOCKS], + ], + extra_ecus=[ + (Ecu.engine, 0x7e0, None), # Powertrain Control Module + # Note: We are unlikely to get a response from behind the gateway + (Ecu.shiftByWire, 0x732, None), # Gear Shift Module + (Ecu.debug, 0x7d0, None), # Accessory Protocol Interface Module + ], + # Custom fuzzy fingerprinting function using platform and model year hints + match_fw_to_car_fuzzy=match_fw_to_car_fuzzy, +) + +DBC = CAR.create_dbc_map() diff --git a/car/gm/__init__.py b/car/gm/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/car/gm/carcontroller.py b/car/gm/carcontroller.py new file mode 100644 index 0000000000..b204d3b80f --- /dev/null +++ b/car/gm/carcontroller.py @@ -0,0 +1,165 @@ +from cereal import car +from openpilot.common.conversions import Conversions as CV +from openpilot.common.numpy_fast import interp +from openpilot.common.realtime import DT_CTRL +from opendbc.can.packer import CANPacker +from openpilot.selfdrive.car import apply_driver_steer_torque_limits +from openpilot.selfdrive.car.gm import gmcan +from openpilot.selfdrive.car.gm.values import DBC, CanBus, CarControllerParams, CruiseButtons +from openpilot.selfdrive.car.interfaces import CarControllerBase + +VisualAlert = car.CarControl.HUDControl.VisualAlert +NetworkLocation = car.CarParams.NetworkLocation +LongCtrlState = car.CarControl.Actuators.LongControlState + +# Camera cancels up to 0.1s after brake is pressed, ECM allows 0.5s +CAMERA_CANCEL_DELAY_FRAMES = 10 +# Enforce a minimum interval between steering messages to avoid a fault +MIN_STEER_MSG_INTERVAL_MS = 15 + + +class CarController(CarControllerBase): + def __init__(self, dbc_name, CP, VM): + self.CP = CP + self.start_time = 0. + self.apply_steer_last = 0 + self.apply_gas = 0 + self.apply_brake = 0 + self.frame = 0 + self.last_steer_frame = 0 + self.last_button_frame = 0 + self.cancel_counter = 0 + + self.lka_steering_cmd_counter = 0 + self.lka_icon_status_last = (False, False) + + self.params = CarControllerParams(self.CP) + + self.packer_pt = CANPacker(DBC[self.CP.carFingerprint]['pt']) + self.packer_obj = CANPacker(DBC[self.CP.carFingerprint]['radar']) + self.packer_ch = CANPacker(DBC[self.CP.carFingerprint]['chassis']) + + def update(self, CC, CS, now_nanos): + actuators = CC.actuators + hud_control = CC.hudControl + hud_alert = hud_control.visualAlert + hud_v_cruise = hud_control.setSpeed + if hud_v_cruise > 70: + hud_v_cruise = 0 + + # Send CAN commands. + can_sends = [] + + # Steering (Active: 50Hz, inactive: 10Hz) + steer_step = self.params.STEER_STEP if CC.latActive else self.params.INACTIVE_STEER_STEP + + if self.CP.networkLocation == NetworkLocation.fwdCamera: + # Also send at 50Hz: + # - on startup, first few msgs are blocked + # - until we're in sync with camera so counters align when relay closes, preventing a fault. + # openpilot can subtly drift, so this is activated throughout a drive to stay synced + out_of_sync = self.lka_steering_cmd_counter % 4 != (CS.cam_lka_steering_cmd_counter + 1) % 4 + if CS.loopback_lka_steering_cmd_ts_nanos == 0 or out_of_sync: + steer_step = self.params.STEER_STEP + + self.lka_steering_cmd_counter += 1 if CS.loopback_lka_steering_cmd_updated else 0 + + # Avoid GM EPS faults when transmitting messages too close together: skip this transmit if we + # received the ASCMLKASteeringCmd loopback confirmation too recently + last_lka_steer_msg_ms = (now_nanos - CS.loopback_lka_steering_cmd_ts_nanos) * 1e-6 + if (self.frame - self.last_steer_frame) >= steer_step and last_lka_steer_msg_ms > MIN_STEER_MSG_INTERVAL_MS: + # Initialize ASCMLKASteeringCmd counter using the camera until we get a msg on the bus + if CS.loopback_lka_steering_cmd_ts_nanos == 0: + self.lka_steering_cmd_counter = CS.pt_lka_steering_cmd_counter + 1 + + if CC.latActive: + new_steer = int(round(actuators.steer * self.params.STEER_MAX)) + apply_steer = apply_driver_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.params) + else: + apply_steer = 0 + + self.last_steer_frame = self.frame + self.apply_steer_last = apply_steer + idx = self.lka_steering_cmd_counter % 4 + can_sends.append(gmcan.create_steering_control(self.packer_pt, CanBus.POWERTRAIN, apply_steer, idx, CC.latActive)) + + if self.CP.openpilotLongitudinalControl: + # Gas/regen, brakes, and UI commands - all at 25Hz + if self.frame % 4 == 0: + stopping = actuators.longControlState == LongCtrlState.stopping + if not CC.longActive: + # ASCM sends max regen when not enabled + self.apply_gas = self.params.INACTIVE_REGEN + self.apply_brake = 0 + else: + self.apply_gas = int(round(interp(actuators.accel, self.params.GAS_LOOKUP_BP, self.params.GAS_LOOKUP_V))) + self.apply_brake = int(round(interp(actuators.accel, self.params.BRAKE_LOOKUP_BP, self.params.BRAKE_LOOKUP_V))) + # Don't allow any gas above inactive regen while stopping + # FIXME: brakes aren't applied immediately when enabling at a stop + if stopping: + self.apply_gas = self.params.INACTIVE_REGEN + + idx = (self.frame // 4) % 4 + + at_full_stop = CC.longActive and CS.out.standstill + near_stop = CC.longActive and (CS.out.vEgo < self.params.NEAR_STOP_BRAKE_PHASE) + friction_brake_bus = CanBus.CHASSIS + # GM Camera exceptions + # TODO: can we always check the longControlState? + if self.CP.networkLocation == NetworkLocation.fwdCamera: + at_full_stop = at_full_stop and stopping + friction_brake_bus = CanBus.POWERTRAIN + + # GasRegenCmdActive needs to be 1 to avoid cruise faults. It describes the ACC state, not actuation + can_sends.append(gmcan.create_gas_regen_command(self.packer_pt, CanBus.POWERTRAIN, self.apply_gas, idx, CC.enabled, at_full_stop)) + can_sends.append(gmcan.create_friction_brake_command(self.packer_ch, friction_brake_bus, self.apply_brake, + idx, CC.enabled, near_stop, at_full_stop, self.CP)) + + # Send dashboard UI commands (ACC status) + send_fcw = hud_alert == VisualAlert.fcw + can_sends.append(gmcan.create_acc_dashboard_command(self.packer_pt, CanBus.POWERTRAIN, CC.enabled, + hud_v_cruise * CV.MS_TO_KPH, hud_control, send_fcw)) + + # Radar needs to know current speed and yaw rate (50hz), + # and that ADAS is alive (10hz) + if not self.CP.radarUnavailable: + tt = self.frame * DT_CTRL + time_and_headlights_step = 10 + if self.frame % time_and_headlights_step == 0: + idx = (self.frame // time_and_headlights_step) % 4 + can_sends.append(gmcan.create_adas_time_status(CanBus.OBSTACLE, int((tt - self.start_time) * 60), idx)) + can_sends.append(gmcan.create_adas_headlights_status(self.packer_obj, CanBus.OBSTACLE)) + + speed_and_accelerometer_step = 2 + if self.frame % speed_and_accelerometer_step == 0: + idx = (self.frame // speed_and_accelerometer_step) % 4 + can_sends.append(gmcan.create_adas_steering_status(CanBus.OBSTACLE, idx)) + can_sends.append(gmcan.create_adas_accelerometer_speed_status(CanBus.OBSTACLE, CS.out.vEgo, idx)) + + if self.CP.networkLocation == NetworkLocation.gateway and self.frame % self.params.ADAS_KEEPALIVE_STEP == 0: + can_sends += gmcan.create_adas_keepalive(CanBus.POWERTRAIN) + + else: + # While car is braking, cancel button causes ECM to enter a soft disable state with a fault status. + # A delayed cancellation allows camera to cancel and avoids a fault when user depresses brake quickly + self.cancel_counter = self.cancel_counter + 1 if CC.cruiseControl.cancel else 0 + + # Stock longitudinal, integrated at camera + if (self.frame - self.last_button_frame) * DT_CTRL > 0.04: + if self.cancel_counter > CAMERA_CANCEL_DELAY_FRAMES: + self.last_button_frame = self.frame + can_sends.append(gmcan.create_buttons(self.packer_pt, CanBus.CAMERA, CS.buttons_counter, CruiseButtons.CANCEL)) + + if self.CP.networkLocation == NetworkLocation.fwdCamera: + # Silence "Take Steering" alert sent by camera, forward PSCMStatus with HandsOffSWlDetectionStatus=1 + if self.frame % 10 == 0: + can_sends.append(gmcan.create_pscm_status(self.packer_pt, CanBus.CAMERA, CS.pscm_status)) + + new_actuators = actuators.as_builder() + new_actuators.steer = self.apply_steer_last / self.params.STEER_MAX + new_actuators.steerOutputCan = self.apply_steer_last + new_actuators.gas = self.apply_gas + new_actuators.brake = self.apply_brake + + self.frame += 1 + return new_actuators, can_sends diff --git a/car/gm/carstate.py b/car/gm/carstate.py new file mode 100644 index 0000000000..a1129c59c8 --- /dev/null +++ b/car/gm/carstate.py @@ -0,0 +1,180 @@ +import copy +from cereal import car +from openpilot.common.conversions import Conversions as CV +from openpilot.common.numpy_fast import mean +from opendbc.can.can_define import CANDefine +from opendbc.can.parser import CANParser +from openpilot.selfdrive.car.interfaces import CarStateBase +from openpilot.selfdrive.car.gm.values import DBC, AccState, CanBus, STEER_THRESHOLD + +TransmissionType = car.CarParams.TransmissionType +NetworkLocation = car.CarParams.NetworkLocation +STANDSTILL_THRESHOLD = 10 * 0.0311 * CV.KPH_TO_MS + + +class CarState(CarStateBase): + def __init__(self, CP): + super().__init__(CP) + can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) + self.shifter_values = can_define.dv["ECMPRDNL2"]["PRNDL2"] + self.cluster_speed_hyst_gap = CV.KPH_TO_MS / 2. + self.cluster_min_speed = CV.KPH_TO_MS / 2. + + self.loopback_lka_steering_cmd_updated = False + self.loopback_lka_steering_cmd_ts_nanos = 0 + self.pt_lka_steering_cmd_counter = 0 + self.cam_lka_steering_cmd_counter = 0 + self.buttons_counter = 0 + + self.prev_distance_button = 0 + self.distance_button = 0 + + def update(self, pt_cp, cam_cp, loopback_cp): + ret = car.CarState.new_message() + + self.prev_cruise_buttons = self.cruise_buttons + self.prev_distance_button = self.distance_button + self.cruise_buttons = pt_cp.vl["ASCMSteeringButton"]["ACCButtons"] + self.distance_button = pt_cp.vl["ASCMSteeringButton"]["DistanceButton"] + self.buttons_counter = pt_cp.vl["ASCMSteeringButton"]["RollingCounter"] + self.pscm_status = copy.copy(pt_cp.vl["PSCMStatus"]) + # This is to avoid a fault where you engage while still moving backwards after shifting to D. + # An Equinox has been seen with an unsupported status (3), so only check if either wheel is in reverse (2) + self.moving_backward = (pt_cp.vl["EBCMWheelSpdRear"]["RLWheelDir"] == 2) or (pt_cp.vl["EBCMWheelSpdRear"]["RRWheelDir"] == 2) + + # Variables used for avoiding LKAS faults + self.loopback_lka_steering_cmd_updated = len(loopback_cp.vl_all["ASCMLKASteeringCmd"]["RollingCounter"]) > 0 + if self.loopback_lka_steering_cmd_updated: + self.loopback_lka_steering_cmd_ts_nanos = loopback_cp.ts_nanos["ASCMLKASteeringCmd"]["RollingCounter"] + if self.CP.networkLocation == NetworkLocation.fwdCamera: + self.pt_lka_steering_cmd_counter = pt_cp.vl["ASCMLKASteeringCmd"]["RollingCounter"] + self.cam_lka_steering_cmd_counter = cam_cp.vl["ASCMLKASteeringCmd"]["RollingCounter"] + + ret.wheelSpeeds = self.get_wheel_speeds( + pt_cp.vl["EBCMWheelSpdFront"]["FLWheelSpd"], + pt_cp.vl["EBCMWheelSpdFront"]["FRWheelSpd"], + pt_cp.vl["EBCMWheelSpdRear"]["RLWheelSpd"], + pt_cp.vl["EBCMWheelSpdRear"]["RRWheelSpd"], + ) + 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) + # sample rear wheel speeds, standstill=True if ECM allows engagement with brake + ret.standstill = ret.wheelSpeeds.rl <= STANDSTILL_THRESHOLD and ret.wheelSpeeds.rr <= STANDSTILL_THRESHOLD + + 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)) + + ret.brake = pt_cp.vl["ECMAcceleratorPos"]["BrakePedalPos"] + if self.CP.networkLocation == NetworkLocation.fwdCamera: + ret.brakePressed = pt_cp.vl["ECMEngineStatus"]["BrakePressed"] != 0 + else: + # Some Volt 2016-17 have loose brake pedal push rod retainers which causes the ECM to believe + # that the brake is being intermittently pressed without user interaction. + # To avoid a cruise fault we need to use a conservative brake position threshold + # https://static.nhtsa.gov/odi/tsbs/2017/MC-10137629-9999.pdf + ret.brakePressed = ret.brake >= 8 + + # Regen braking is braking + if self.CP.transmissionType == TransmissionType.direct: + ret.regenBraking = pt_cp.vl["EBCMRegenPaddle"]["RegenPaddle"] != 0 + + ret.gas = pt_cp.vl["AcceleratorPedal2"]["AcceleratorPedal2"] / 254. + ret.gasPressed = ret.gas > 1e-5 + + ret.steeringAngleDeg = pt_cp.vl["PSCMSteeringAngle"]["SteeringWheelAngle"] + ret.steeringRateDeg = pt_cp.vl["PSCMSteeringAngle"]["SteeringWheelRate"] + ret.steeringTorque = pt_cp.vl["PSCMStatus"]["LKADriverAppldTrq"] + ret.steeringTorqueEps = pt_cp.vl["PSCMStatus"]["LKATorqueDelivered"] + ret.steeringPressed = abs(ret.steeringTorque) > STEER_THRESHOLD + + # 0 inactive, 1 active, 2 temporarily limited, 3 failed + self.lkas_status = pt_cp.vl["PSCMStatus"]["LKATorqueDeliveredStatus"] + ret.steerFaultTemporary = self.lkas_status == 2 + ret.steerFaultPermanent = self.lkas_status == 3 + + # 1 - open, 0 - closed + ret.doorOpen = (pt_cp.vl["BCMDoorBeltStatus"]["FrontLeftDoor"] == 1 or + pt_cp.vl["BCMDoorBeltStatus"]["FrontRightDoor"] == 1 or + pt_cp.vl["BCMDoorBeltStatus"]["RearLeftDoor"] == 1 or + pt_cp.vl["BCMDoorBeltStatus"]["RearRightDoor"] == 1) + + # 1 - latched + ret.seatbeltUnlatched = pt_cp.vl["BCMDoorBeltStatus"]["LeftSeatBelt"] == 0 + ret.leftBlinker = pt_cp.vl["BCMTurnSignals"]["TurnSignals"] == 1 + ret.rightBlinker = pt_cp.vl["BCMTurnSignals"]["TurnSignals"] == 2 + + ret.parkingBrake = pt_cp.vl["BCMGeneralPlatformStatus"]["ParkBrakeSwActive"] == 1 + ret.cruiseState.available = pt_cp.vl["ECMEngineStatus"]["CruiseMainOn"] != 0 + ret.espDisabled = pt_cp.vl["ESPStatus"]["TractionControlOn"] != 1 + ret.accFaulted = (pt_cp.vl["AcceleratorPedal2"]["CruiseState"] == AccState.FAULTED or + pt_cp.vl["EBCMFrictionBrakeStatus"]["FrictionBrakeUnavailable"] == 1) + + ret.cruiseState.enabled = pt_cp.vl["AcceleratorPedal2"]["CruiseState"] != AccState.OFF + ret.cruiseState.standstill = pt_cp.vl["AcceleratorPedal2"]["CruiseState"] == AccState.STANDSTILL + if self.CP.networkLocation == NetworkLocation.fwdCamera: + ret.cruiseState.speed = cam_cp.vl["ASCMActiveCruiseControlStatus"]["ACCSpeedSetpoint"] * CV.KPH_TO_MS + ret.stockAeb = cam_cp.vl["AEBCmd"]["AEBCmdActive"] != 0 + # openpilot controls nonAdaptive when not pcmCruise + if self.CP.pcmCruise: + ret.cruiseState.nonAdaptive = cam_cp.vl["ASCMActiveCruiseControlStatus"]["ACCCruiseState"] not in (2, 3) + + if self.CP.enableBsm: + ret.leftBlindspot = pt_cp.vl["BCMBlindSpotMonitor"]["LeftBSM"] == 1 + ret.rightBlindspot = pt_cp.vl["BCMBlindSpotMonitor"]["RightBSM"] == 1 + + return ret + + @staticmethod + def get_cam_can_parser(CP): + messages = [] + if CP.networkLocation == NetworkLocation.fwdCamera: + messages += [ + ("AEBCmd", 10), + ("ASCMLKASteeringCmd", 10), + ("ASCMActiveCruiseControlStatus", 25), + ] + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus.CAMERA) + + @staticmethod + def get_can_parser(CP): + messages = [ + ("BCMTurnSignals", 1), + ("ECMPRDNL2", 10), + ("PSCMStatus", 10), + ("ESPStatus", 10), + ("BCMDoorBeltStatus", 10), + ("BCMGeneralPlatformStatus", 10), + ("EBCMWheelSpdFront", 20), + ("EBCMWheelSpdRear", 20), + ("EBCMFrictionBrakeStatus", 20), + ("AcceleratorPedal2", 33), + ("ASCMSteeringButton", 33), + ("ECMEngineStatus", 100), + ("PSCMSteeringAngle", 100), + ("ECMAcceleratorPos", 80), + ] + + if CP.enableBsm: + messages.append(("BCMBlindSpotMonitor", 10)) + + # Used to read back last counter sent to PT by camera + if CP.networkLocation == NetworkLocation.fwdCamera: + messages += [ + ("ASCMLKASteeringCmd", 0), + ] + + if CP.transmissionType == TransmissionType.direct: + messages.append(("EBCMRegenPaddle", 50)) + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus.POWERTRAIN) + + @staticmethod + def get_loopback_can_parser(CP): + messages = [ + ("ASCMLKASteeringCmd", 0), + ] + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus.LOOPBACK) diff --git a/car/gm/fingerprints.py b/car/gm/fingerprints.py new file mode 100644 index 0000000000..3752fbb8d3 --- /dev/null +++ b/car/gm/fingerprints.py @@ -0,0 +1,63 @@ +# ruff: noqa: E501 +from openpilot.selfdrive.car.gm.values import CAR + +# Trailblazer also matches as a SILVERADO, TODO: split with fw versions +# FIXME: There are Equinox users with different message lengths, specifically 304 and 320 + + +FINGERPRINTS = { + CAR.HOLDEN_ASTRA: [{ + 190: 8, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 8, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 393: 8, 398: 8, 401: 8, 413: 8, 417: 8, 419: 8, 422: 1, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 8, 455: 7, 456: 8, 458: 5, 479: 8, 481: 7, 485: 8, 489: 8, 497: 8, 499: 3, 500: 8, 501: 8, 508: 8, 528: 5, 532: 6, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 567: 5, 647: 5, 707: 8, 715: 8, 723: 8, 753: 5, 761: 7, 806: 1, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 961: 8, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1009: 8, 1011: 6, 1017: 8, 1019: 3, 1020: 8, 1105: 6, 1217: 8, 1221: 5, 1225: 8, 1233: 8, 1249: 8, 1257: 6, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 8, 1280: 4, 1300: 8, 1328: 4, 1417: 8, 1906: 7, 1907: 7, 1908: 7, 1912: 7, 1919: 7 + }], + CAR.CHEVROLET_VOLT: [{ + 170: 8, 171: 8, 189: 7, 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 288: 5, 289: 8, 298: 8, 304: 1, 308: 4, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 389: 2, 390: 7, 417: 7, 419: 1, 426: 7, 451: 8, 452: 8, 453: 6, 454: 8, 456: 8, 479: 3, 481: 7, 485: 8, 489: 8, 493: 8, 495: 4, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 528: 4, 532: 6, 546: 7, 550: 8, 554: 3, 558: 8, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 566: 5, 567: 3, 568: 1, 573: 1, 577: 8, 647: 3, 707: 8, 711: 6, 715: 8, 761: 7, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 961: 8, 969: 8, 977: 8, 979: 7, 988: 6, 989: 8, 995: 7, 1001: 8, 1005: 6, 1009: 8, 1017: 8, 1019: 2, 1020: 8, 1105: 6, 1187: 4, 1217: 8, 1221: 5, 1223: 3, 1225: 7, 1227: 4, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1273: 3, 1275: 3, 1280: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1601: 8, 1905: 7, 1906: 7, 1907: 7, 1910: 7, 1912: 7, 1922: 7, 1927: 7, 1928: 7, 2016: 8, 2020: 8, 2024: 8, 2028: 8 + }, + { + 170: 8, 171: 8, 189: 7, 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 288: 5, 298: 8, 304: 1, 308: 4, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 389: 2, 390: 7, 417: 7, 419: 1, 426: 7, 451: 8, 452: 8, 453: 6, 454: 8, 456: 8, 479: 3, 481: 7, 485: 8, 489: 8, 493: 8, 495: 4, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 528: 4, 532: 6, 546: 7, 550: 8, 554: 3, 558: 8, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 566: 5, 567: 3, 568: 1, 573: 1, 577: 8, 578: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 3, 707: 8, 711: 6, 715: 8, 717: 5, 761: 7, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 961: 8, 967: 4, 969: 8, 977: 8, 979: 7, 988: 6, 989: 8, 995: 7, 1001: 8, 1005: 6, 1009: 8, 1017: 8, 1019: 2, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1187: 4, 1217: 8, 1221: 5, 1223: 3, 1225: 7, 1227: 4, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1273: 3, 1275: 3, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1516: 8, 1601: 8, 1618: 8, 1905: 7, 1906: 7, 1907: 7, 1910: 7, 1912: 7, 1922: 7, 1927: 7, 1930: 7, 2016: 8, 2018: 8, 2020: 8, 2024: 8, 2028: 8 + }, + { + 170: 8, 171: 8, 189: 7, 190: 6, 192: 5, 193: 8, 197: 8, 199: 4, 201: 6, 209: 7, 211: 2, 241: 6, 288: 5, 289: 1, 290: 1, 298: 2, 304: 1, 308: 4, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 368: 8, 381: 2, 384: 8, 386: 5, 388: 8, 389: 2, 390: 7, 417: 7, 419: 1, 426: 7, 451: 8, 452: 8, 453: 6, 454: 8, 456: 8, 458: 8, 479: 3, 481: 7, 485: 8, 489: 5, 493: 8, 495: 4, 497: 8, 499: 3, 500: 6, 501: 3, 508: 8, 512: 3, 528: 4, 530: 8, 532: 6, 537: 5, 539: 8, 542: 7, 546: 7, 550: 8, 554: 3, 558: 8, 560: 6, 562: 4, 563: 5, 564: 5, 565: 5, 566: 5, 567: 3, 568: 1, 573: 1, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 3, 707: 8, 711: 6, 761: 7, 810: 8, 821: 4, 823: 7, 832: 8, 840: 5, 842: 5, 844: 8, 853: 8, 866: 4, 961: 8, 967: 4, 969: 8, 977: 8, 979: 7, 988: 6, 989: 8, 995: 7, 1001: 5, 1003: 5, 1005: 6, 1009: 8, 1017: 8, 1019: 2, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1187: 4, 1217: 8, 1221: 5, 1223: 3, 1225: 7, 1227: 4, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1273: 3, 1275: 3, 1280: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1905: 7, 1906: 7, 1907: 7, 1910: 7, 1912: 7, 1922: 7, 1927: 7 + }], + CAR.BUICK_LACROSSE: [{ + 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 322: 7, 328: 1, 352: 5, 353: 3, 381: 6, 386: 8, 388: 8, 393: 7, 398: 8, 407: 7, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 455: 7, 456: 8, 463: 3, 479: 3, 481: 7, 485: 8, 487: 8, 489: 8, 495: 4, 497: 8, 499: 3, 500: 6, 501: 8, 503: 1, 508: 8, 510: 8, 528: 5, 532: 6, 534: 2, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 567: 5, 573: 1, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 5, 707: 8, 753: 5, 761: 7, 801: 8, 804: 3, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 872: 1, 882: 8, 890: 1, 892: 2, 893: 1, 894: 1, 961: 8, 967: 4, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1005: 6, 1009: 8, 1011: 6, 1013: 3, 1017: 8, 1019: 2, 1020: 8, 1022: 1, 1105: 6, 1217: 8, 1221: 5, 1223: 2, 1225: 7, 1233: 8, 1243: 3, 1249: 8, 1257: 6, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 1, 1280: 4, 1300: 8, 1322: 6, 1328: 4, 1417: 8, 1609: 8, 1613: 8, 1649: 8, 1792: 8, 1798: 8, 1824: 8, 1825: 8, 1840: 8, 1842: 8, 1858: 8, 1860: 8, 1863: 8, 1872: 8, 1875: 8, 1882: 8, 1888: 8, 1889: 8, 1892: 8, 1904: 7, 1906: 7, 1907: 7, 1912: 7, 1913: 7, 1914: 7, 1916: 7, 1918: 7, 1919: 7, 1937: 8, 1953: 8, 1968: 8, 2001: 8, 2017: 8, 2018: 8, 2020: 8, 2026: 8 + }], + CAR.BUICK_REGAL: [{ + 190: 8, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 8, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 322: 7, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 393: 7, 398: 8, 407: 7, 413: 8, 417: 8, 419: 8, 422: 4, 426: 8, 431: 8, 442: 8, 451: 8, 452: 8, 453: 8, 455: 7, 456: 8, 463: 3, 479: 8, 481: 7, 485: 8, 487: 8, 489: 8, 495: 8, 497: 8, 499: 3, 500: 8, 501: 8, 508: 8, 528: 5, 532: 6, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 567: 5, 569: 3, 573: 1, 577: 8, 578: 8, 579: 8, 587: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 3, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 882: 8, 884: 8, 890: 1, 892: 2, 893: 2, 894: 1, 961: 8, 967: 8, 969: 8, 977: 8, 979: 8, 985: 8, 1001: 8, 1005: 6, 1009: 8, 1011: 8, 1013: 3, 1017: 8, 1020: 8, 1024: 8, 1025: 8, 1026: 8, 1027: 8, 1028: 8, 1029: 8, 1030: 8, 1031: 8, 1032: 2, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1223: 8, 1225: 7, 1233: 8, 1249: 8, 1257: 6, 1259: 8, 1261: 8, 1263: 8, 1265: 8, 1267: 8, 1271: 8, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1328: 4, 1417: 8, 1601: 8, 1602: 8, 1603: 7, 1611: 8, 1618: 8, 1906: 8, 1907: 7, 1912: 7, 1914: 7, 1916: 7, 1919: 7, 1930: 7, 2016: 8, 2018: 8, 2019: 8, 2024: 8, 2026: 8 + }], + CAR.CADILLAC_ATS: [{ + 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 322: 7, 328: 1, 352: 5, 368: 3, 381: 6, 384: 4, 386: 8, 388: 8, 393: 7, 398: 8, 401: 8, 407: 7, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 455: 7, 456: 8, 462: 4, 479: 3, 481: 7, 485: 8, 487: 8, 489: 8, 491: 2, 493: 8, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 510: 8, 528: 5, 532: 6, 534: 2, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 567: 5, 573: 1, 577: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 6, 707: 8, 715: 8, 717: 5, 719: 5, 723: 2, 753: 5, 761: 7, 801: 8, 804: 3, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 882: 8, 890: 1, 892: 2, 893: 2, 894: 1, 961: 8, 967: 4, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1005: 6, 1009: 8, 1011: 6, 1013: 3, 1017: 8, 1019: 2, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1223: 3, 1225: 7, 1233: 8, 1241: 3, 1249: 8, 1257: 6, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 1, 1271: 8, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1601: 8, 1904: 7, 1906: 7, 1907: 7, 1912: 7, 1916: 7, 1917: 7, 1918: 7, 1919: 7, 1920: 7, 1930: 7, 2016: 8, 2024: 8 + }], + CAR.CHEVROLET_MALIBU: [{ + 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 393: 7, 398: 8, 407: 7, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 455: 7, 456: 8, 479: 3, 481: 7, 485: 8, 487: 8, 489: 8, 495: 4, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 510: 8, 528: 5, 532: 6, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 567: 5, 573: 1, 577: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 6, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 961: 8, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1005: 6, 1009: 8, 1013: 3, 1017: 8, 1019: 2, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1223: 2, 1225: 7, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1601: 8, 1906: 7, 1907: 7, 1912: 7, 1919: 7, 1930: 7, 2016: 8, 2024: 8 + }], + CAR.GMC_ACADIA: [{ + 190: 6, 192: 5, 193: 8, 197: 8, 199: 4, 201: 6, 208: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 289: 1, 290: 1, 298: 8, 304: 8, 309: 8, 313: 8, 320: 8, 322: 7, 328: 1, 352: 7, 368: 8, 381: 8, 384: 8, 386: 8, 388: 8, 393: 8, 398: 8, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 454: 8, 455: 7, 458: 8, 460: 4, 462: 4, 463: 3, 479: 3, 481: 7, 485: 8, 489: 5, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 510: 8, 512: 3, 530: 8, 532: 6, 534: 2, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 567: 5, 568: 2, 573: 1, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 6, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 789: 5, 800: 6, 801: 8, 803: 8, 804: 3, 805: 8, 832: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 961: 8, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1003: 5, 1005: 6, 1009: 8, 1017: 8, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1225: 8, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1328: 4, 1417: 8, 1906: 7, 1907: 7, 1912: 7, 1914: 7, 1918: 7, 1919: 7, 1920: 7, 1930: 7 + }, + { + 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 208: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 289: 8, 298: 8, 304: 1, 309: 8, 313: 8, 320: 3, 322: 7, 328: 1, 338: 6, 340: 6, 352: 5, 381: 8, 384: 4, 386: 8, 388: 8, 393: 8, 398: 8, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 454: 8, 455: 7, 462: 4, 463: 3, 479: 3, 481: 7, 485: 8, 489: 8, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 510: 8, 532: 6, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 567: 5, 573: 1, 577: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 6, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 961: 8, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1005: 6, 1009: 8, 1017: 8, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1225: 8, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1328: 4, 1417: 8, 1601: 8, 1906: 7, 1907: 7, 1912: 7, 1914: 7, 1919: 7, 1920: 7, 1930: 7, 2016: 8, 2024: 8 + }], + CAR.CADILLAC_ESCALADE: [{ + 170: 8, 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 208: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 322: 7, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 393: 7, 398: 8, 407: 4, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 454: 8, 455: 7, 460: 5, 462: 4, 463: 3, 479: 3, 481: 7, 485: 8, 487: 8, 489: 8, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 510: 8, 532: 6, 534: 2, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 573: 1, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 6, 707: 8, 715: 8, 717: 5, 719: 5, 761: 7, 801: 8, 804: 3, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 961: 8, 967: 4, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1005: 6, 1009: 8, 1017: 8, 1019: 2, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1223: 2, 1225: 7, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1609: 8, 1613: 8, 1649: 8, 1792: 8, 1798: 8, 1824: 8, 1825: 8, 1840: 8, 1842: 8, 1858: 8, 1860: 8, 1863: 8, 1872: 8, 1875: 8, 1882: 8, 1888: 8, 1889: 8, 1892: 8, 1906: 7, 1907: 7, 1912: 7, 1914: 7, 1917: 7, 1918: 7, 1919: 7, 1920: 7, 1930: 7, 1937: 8, 1953: 8, 1968: 8, 2001: 8, 2017: 8, 2018: 8, 2020: 8, 2026: 8 + }], + CAR.CADILLAC_ESCALADE_ESV: [{ + 309: 1, 848: 8, 849: 8, 850: 8, 851: 8, 852: 8, 853: 8, 854: 3, 1056: 6, 1057: 8, 1058: 8, 1059: 8, 1060: 8, 1061: 8, 1062: 8, 1063: 8, 1064: 8, 1065: 8, 1066: 8, 1067: 8, 1068: 8, 1120: 8, 1121: 8, 1122: 8, 1123: 8, 1124: 8, 1125: 8, 1126: 8, 1127: 8, 1128: 8, 1129: 8, 1130: 8, 1131: 8, 1132: 8, 1133: 8, 1134: 8, 1135: 8, 1136: 8, 1137: 8, 1138: 8, 1139: 8, 1140: 8, 1141: 8, 1142: 8, 1143: 8, 1146: 8, 1147: 8, 1148: 8, 1149: 8, 1150: 8, 1151: 8, 1216: 8, 1217: 8, 1218: 8, 1219: 8, 1220: 8, 1221: 8, 1222: 8, 1223: 8, 1224: 8, 1225: 8, 1226: 8, 1232: 8, 1233: 8, 1234: 8, 1235: 8, 1236: 8, 1237: 8, 1238: 8, 1239: 8, 1240: 8, 1241: 8, 1242: 8, 1787: 8, 1788: 8 + }], + CAR.CADILLAC_ESCALADE_ESV_2019: [{ + 715: 8, 840: 5, 717: 5, 869: 4, 880: 6, 289: 8, 454: 8, 842: 5, 460: 5, 463: 3, 801: 8, 170: 8, 190: 6, 241: 6, 201: 8, 417: 7, 211: 2, 419: 1, 398: 8, 426: 7, 487: 8, 442: 8, 451: 8, 452: 8, 453: 6, 479: 3, 311: 8, 500: 6, 647: 6, 193: 8, 707: 8, 197: 8, 209: 7, 199: 4, 455: 7, 313: 8, 481: 7, 485: 8, 489: 8, 249: 8, 393: 7, 407: 7, 413: 8, 422: 4, 431: 8, 501: 8, 499: 3, 810: 8, 508: 8, 381: 8, 462: 4, 532: 6, 562: 8, 386: 8, 761: 7, 573: 1, 554: 3, 719: 5, 560: 8, 1279: 4, 388: 8, 288: 5, 1005: 6, 497: 8, 844: 8, 961: 8, 967: 4, 977: 8, 979: 8, 985: 5, 1001: 8, 1017: 8, 1019: 2, 1020: 8, 1217: 8, 510: 8, 866: 4, 304: 1, 969: 8, 384: 4, 1033: 7, 1009: 8, 1034: 7, 1296: 4, 1930: 7, 1105: 5, 1013: 5, 1225: 7, 1919: 7, 320: 3, 534: 2, 352: 5, 298: 8, 1223: 2, 1233: 8, 608: 8, 1265: 8, 609: 6, 1267: 1, 1417: 8, 610: 6, 1906: 7, 611: 6, 612: 8, 613: 8, 208: 8, 564: 5, 309: 8, 1221: 5, 1280: 4, 1249: 8, 1907: 7, 1257: 6, 1300: 8, 1920: 7, 563: 5, 1322: 6, 1323: 4, 1328: 4, 1917: 7, 328: 1, 1912: 7, 1914: 7, 804: 3, 1918: 7 + }], + CAR.CHEVROLET_BOLT_EUV: [{ + 189: 7, 190: 7, 193: 8, 197: 8, 201: 8, 209: 7, 211: 3, 241: 6, 257: 8, 288: 5, 289: 8, 298: 8, 304: 3, 309: 8, 311: 8, 313: 8, 320: 4, 322: 7, 328: 1, 352: 5, 381: 8, 384: 4, 386: 8, 388: 8, 451: 8, 452: 8, 453: 6, 458: 5, 463: 3, 479: 3, 481: 7, 485: 8, 489: 8, 497: 8, 500: 6, 501: 8, 528: 5, 532: 6, 560: 8, 562: 8, 563: 5, 565: 5, 566: 8, 587: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 789: 5, 800: 6, 810: 8, 840: 5, 842: 5, 844: 8, 848: 4, 869: 4, 880: 6, 977: 8, 1001: 8, 1017: 8, 1020: 8, 1217: 8, 1221: 5, 1233: 8, 1249: 8, 1265: 8, 1280: 4, 1296: 4, 1300: 8, 1611: 8, 1930: 7 + }], + CAR.CHEVROLET_SILVERADO: [{ + 190: 6, 193: 8, 197: 8, 201: 8, 208: 8, 209: 7, 211: 2, 241: 6, 249: 8, 257: 8, 288: 5, 289: 8, 298: 8, 304: 3, 309: 8, 311: 8, 313: 8, 320: 4, 322: 7, 328: 1, 352: 5, 381: 8, 384: 4, 386: 8, 388: 8, 413: 8, 451: 8, 452: 8, 453: 6, 455: 7, 460: 5, 463: 3, 479: 3, 481: 7, 485: 8, 489: 8, 497: 8, 500: 6, 501: 8, 528: 5, 532: 6, 534: 2, 560: 8, 562: 8, 563: 5, 565: 5, 587: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 707: 8, 715: 8, 717: 5, 761: 7, 789: 5, 800: 6, 801: 8, 810: 8, 840: 5, 842: 5, 844: 8, 848: 4, 869: 4, 880: 6, 977: 8, 1001: 8, 1011: 6, 1017: 8, 1020: 8, 1033: 7, 1034: 7, 1217: 8, 1221: 5, 1233: 8, 1249: 8, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 1, 1271: 8, 1280: 4, 1296: 4, 1300: 8, 1611: 8, 1930: 7 + }], + CAR.CHEVROLET_EQUINOX: [{ + 190: 6, 193: 8, 197: 8, 201: 8, 209: 7, 211: 2, 241: 6, 249: 8, 257: 8, 288: 5, 289: 8, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 8, 384: 4, 386: 8, 388: 8, 413: 8, 451: 8, 452: 8, 453: 6, 455: 7, 463: 3, 479: 3, 481: 7, 485: 8, 489: 8, 497: 8, 500: 6, 501: 8, 510: 8, 528: 5, 532: 6, 560: 8, 562: 8, 563: 5, 565: 5, 587: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 789: 5, 800: 6, 810: 8, 840: 5, 842: 5, 844: 8, 869: 4, 880: 6, 977: 8, 1001: 8, 1011: 6, 1017: 8, 1020: 8, 1033: 7, 1034: 7, 1217: 8, 1221: 5, 1233: 8, 1249: 8, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 1, 1271: 8, 1280: 4, 1296: 4, 1300: 8, 1611: 8, 1930: 7 + }, + { + 190: 6, 201: 8, 211: 2, 717: 5, 241: 6, 451: 8, 298: 8, 452: 8, 453: 6, 479: 3, 485: 8, 249: 8, 500: 6, 587: 8, 1611: 8, 289: 8, 481: 7, 193: 8, 197: 8, 209: 7, 455: 7, 489: 8, 309: 8, 413: 8, 501: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 311: 8, 510: 8, 528: 5, 532: 6, 715: 8, 560: 8, 562: 8, 707: 8, 789: 5, 869: 4, 880: 6, 761: 7, 840: 5, 842: 5, 844: 8, 313: 8, 381: 8, 386: 8, 810: 8, 322: 7, 384: 4, 800: 6, 1033: 7, 1034: 7, 1296: 4, 753: 5, 388: 8, 288: 5, 497: 8, 463: 3, 304: 3, 977: 8, 1001: 8, 1280: 4, 320: 4, 352: 5, 563: 5, 565: 5, 1221: 5, 1011: 6, 1017: 8, 1020: 8, 1249: 8, 1300: 8, 328: 1, 1217: 8, 1233: 8, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 1, 1930: 7, 1271: 8 + }], +} + +FW_VERSIONS: dict[str, dict[tuple, list[bytes]]] = { +} diff --git a/car/gm/gmcan.py b/car/gm/gmcan.py new file mode 100644 index 0000000000..e833e77636 --- /dev/null +++ b/car/gm/gmcan.py @@ -0,0 +1,173 @@ +from openpilot.selfdrive.car import make_can_msg +from openpilot.selfdrive.car.gm.values import CAR + + +def create_buttons(packer, bus, idx, button): + values = { + "ACCButtons": button, + "RollingCounter": idx, + "ACCAlwaysOne": 1, + "DistanceButton": 0, + } + + checksum = 240 + int(values["ACCAlwaysOne"] * 0xf) + checksum += values["RollingCounter"] * (0x4ef if values["ACCAlwaysOne"] != 0 else 0x3f0) + checksum -= int(values["ACCButtons"] - 1) << 4 # not correct if value is 0 + checksum -= 2 * values["DistanceButton"] + + values["SteeringButtonChecksum"] = checksum + return packer.make_can_msg("ASCMSteeringButton", bus, values) + + +def create_pscm_status(packer, bus, pscm_status): + values = {s: pscm_status[s] for s in [ + "HandsOffSWDetectionMode", + "HandsOffSWlDetectionStatus", + "LKATorqueDeliveredStatus", + "LKADriverAppldTrq", + "LKATorqueDelivered", + "LKATotalTorqueDelivered", + "RollingCounter", + "PSCMStatusChecksum", + ]} + checksum_mod = int(1 - values["HandsOffSWlDetectionStatus"]) << 5 + values["HandsOffSWlDetectionStatus"] = 1 + values["PSCMStatusChecksum"] += checksum_mod + return packer.make_can_msg("PSCMStatus", bus, values) + + +def create_steering_control(packer, bus, apply_steer, idx, lkas_active): + values = { + "LKASteeringCmdActive": lkas_active, + "LKASteeringCmd": apply_steer, + "RollingCounter": idx, + "LKASteeringCmdChecksum": 0x1000 - (lkas_active << 11) - (apply_steer & 0x7ff) - idx + } + + return packer.make_can_msg("ASCMLKASteeringCmd", bus, values) + + +def create_adas_keepalive(bus): + dat = b"\x00\x00\x00\x00\x00\x00\x00" + return [make_can_msg(0x409, dat, bus), make_can_msg(0x40a, dat, bus)] + + +def create_gas_regen_command(packer, bus, throttle, idx, enabled, at_full_stop): + values = { + "GasRegenCmdActive": enabled, + "RollingCounter": idx, + "GasRegenCmdActiveInv": 1 - enabled, + "GasRegenCmd": throttle, + "GasRegenFullStopActive": at_full_stop, + "GasRegenAlwaysOne": 1, + "GasRegenAlwaysOne2": 1, + "GasRegenAlwaysOne3": 1, + } + + dat = packer.make_can_msg("ASCMGasRegenCmd", bus, values)[2] + values["GasRegenChecksum"] = (((0xff - dat[1]) & 0xff) << 16) | \ + (((0xff - dat[2]) & 0xff) << 8) | \ + ((0x100 - dat[3] - idx) & 0xff) + + return packer.make_can_msg("ASCMGasRegenCmd", bus, values) + + +def create_friction_brake_command(packer, bus, apply_brake, idx, enabled, near_stop, at_full_stop, CP): + mode = 0x1 + + # TODO: Understand this better. Volts and ICE Camera ACC cars are 0x1 when enabled with no brake + if enabled and CP.carFingerprint in (CAR.CHEVROLET_BOLT_EUV,): + mode = 0x9 + + if apply_brake > 0: + mode = 0xa + if at_full_stop: + mode = 0xd + + # TODO: this is to have GM bringing the car to complete stop, + # but currently it conflicts with OP controls, so turned off. Not set by all cars + #elif near_stop: + # mode = 0xb + + brake = (0x1000 - apply_brake) & 0xfff + checksum = (0x10000 - (mode << 12) - brake - idx) & 0xffff + + values = { + "RollingCounter": idx, + "FrictionBrakeMode": mode, + "FrictionBrakeChecksum": checksum, + "FrictionBrakeCmd": -apply_brake + } + + return packer.make_can_msg("EBCMFrictionBrakeCmd", bus, values) + + +def create_acc_dashboard_command(packer, bus, enabled, target_speed_kph, hud_control, fcw): + target_speed = min(target_speed_kph, 255) + + values = { + "ACCAlwaysOne": 1, + "ACCResumeButton": 0, + "ACCSpeedSetpoint": target_speed, + "ACCGapLevel": hud_control.leadDistanceBars * enabled, # 3 "far", 0 "inactive" + "ACCCmdActive": enabled, + "ACCAlwaysOne2": 1, + "ACCLeadCar": hud_control.leadVisible, + "FCWAlert": 0x3 if fcw else 0 + } + + return packer.make_can_msg("ASCMActiveCruiseControlStatus", bus, values) + + +def create_adas_time_status(bus, tt, idx): + dat = [(tt >> 20) & 0xff, (tt >> 12) & 0xff, (tt >> 4) & 0xff, + ((tt & 0xf) << 4) + (idx << 2)] + chksum = 0x1000 - dat[0] - dat[1] - dat[2] - dat[3] + chksum = chksum & 0xfff + dat += [0x40 + (chksum >> 8), chksum & 0xff, 0x12] + return make_can_msg(0xa1, bytes(dat), bus) + + +def create_adas_steering_status(bus, idx): + dat = [idx << 6, 0xf0, 0x20, 0, 0, 0] + chksum = 0x60 + sum(dat) + dat += [chksum >> 8, chksum & 0xff] + return make_can_msg(0x306, bytes(dat), bus) + + +def create_adas_accelerometer_speed_status(bus, speed_ms, idx): + spd = int(speed_ms * 16) & 0xfff + accel = 0 & 0xfff + # 0 if in park/neutral, 0x10 if in reverse, 0x08 for D/L + #stick = 0x08 + near_range_cutoff = 0x27 + near_range_mode = 1 if spd <= near_range_cutoff else 0 + far_range_mode = 1 - near_range_mode + dat = [0x08, spd >> 4, ((spd & 0xf) << 4) | (accel >> 8), accel & 0xff, 0] + chksum = 0x62 + far_range_mode + (idx << 2) + dat[0] + dat[1] + dat[2] + dat[3] + dat[4] + dat += [(idx << 5) + (far_range_mode << 4) + (near_range_mode << 3) + (chksum >> 8), chksum & 0xff] + return make_can_msg(0x308, bytes(dat), bus) + + +def create_adas_headlights_status(packer, bus): + values = { + "Always42": 0x42, + "Always4": 0x4, + } + return packer.make_can_msg("ASCMHeadlight", bus, values) + + +def create_lka_icon_command(bus, active, critical, steer): + if active and steer == 1: + if critical: + dat = b"\x50\xc0\x14" + else: + dat = b"\x50\x40\x18" + elif active: + if critical: + dat = b"\x40\xc0\x14" + else: + dat = b"\x40\x40\x18" + else: + dat = b"\x00\x00\x00" + return make_can_msg(0x104c006c, dat, bus) diff --git a/car/gm/interface.py b/car/gm/interface.py new file mode 100755 index 0000000000..358bc9e5ba --- /dev/null +++ b/car/gm/interface.py @@ -0,0 +1,239 @@ +#!/usr/bin/env python3 +import os +from cereal import car +from math import fabs, exp +from panda import Panda + +from openpilot.common.basedir import BASEDIR +from openpilot.common.conversions import Conversions as CV +from openpilot.selfdrive.car import create_button_events, get_safety_config +from openpilot.selfdrive.car.gm.radar_interface import RADAR_HEADER_MSG +from openpilot.selfdrive.car.gm.values import CAR, CruiseButtons, CarControllerParams, EV_CAR, CAMERA_ACC_CAR, CanBus +from openpilot.selfdrive.car.interfaces import CarInterfaceBase, TorqueFromLateralAccelCallbackType, FRICTION_THRESHOLD, LatControlInputs, NanoFFModel +from openpilot.selfdrive.controls.lib.drive_helpers import get_friction + +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, + CruiseButtons.MAIN: ButtonType.altButton3, CruiseButtons.CANCEL: ButtonType.cancel} + + +NON_LINEAR_TORQUE_PARAMS = { + CAR.CHEVROLET_BOLT_EUV: [2.6531724862969748, 1.0, 0.1919764879840985, 0.009054123646805178], + CAR.GMC_ACADIA: [4.78003305, 1.0, 0.3122, 0.05591772], + CAR.CHEVROLET_SILVERADO: [3.29974374, 1.0, 0.25571356, 0.0465122] +} + +NEURAL_PARAMS_PATH = os.path.join(BASEDIR, 'selfdrive/car/torque_data/neural_ff_weights.json') + + +class CarInterface(CarInterfaceBase): + @staticmethod + def get_pid_accel_limits(CP, current_speed, cruise_speed): + return CarControllerParams.ACCEL_MIN, CarControllerParams.ACCEL_MAX + + # Determined by iteratively plotting and minimizing error for f(angle, speed) = steer. + @staticmethod + def get_steer_feedforward_volt(desired_angle, v_ego): + desired_angle *= 0.02904609 + sigmoid = desired_angle / (1 + fabs(desired_angle)) + return 0.10006696 * sigmoid * (v_ego + 3.12485927) + + def get_steer_feedforward_function(self): + if self.CP.carFingerprint == CAR.CHEVROLET_VOLT: + return self.get_steer_feedforward_volt + else: + return CarInterfaceBase.get_steer_feedforward_default + + def torque_from_lateral_accel_siglin(self, latcontrol_inputs: LatControlInputs, torque_params: car.CarParams.LateralTorqueTuning, lateral_accel_error: float, + lateral_accel_deadzone: float, friction_compensation: bool, gravity_adjusted: bool) -> float: + friction = get_friction(lateral_accel_error, lateral_accel_deadzone, FRICTION_THRESHOLD, torque_params, friction_compensation) + + def sig(val): + return 1 / (1 + exp(-val)) - 0.5 + + # The "lat_accel vs torque" relationship is assumed to be the sum of "sigmoid + linear" curves + # An important thing to consider is that the slope at 0 should be > 0 (ideally >1) + # This has big effect on the stability about 0 (noise when going straight) + # ToDo: To generalize to other GMs, explore tanh function as the nonlinear + non_linear_torque_params = NON_LINEAR_TORQUE_PARAMS.get(self.CP.carFingerprint) + assert non_linear_torque_params, "The params are not defined" + a, b, c, _ = non_linear_torque_params + steer_torque = (sig(latcontrol_inputs.lateral_acceleration * a) * b) + (latcontrol_inputs.lateral_acceleration * c) + return float(steer_torque) + friction + + def torque_from_lateral_accel_neural(self, latcontrol_inputs: LatControlInputs, torque_params: car.CarParams.LateralTorqueTuning, lateral_accel_error: float, + lateral_accel_deadzone: float, friction_compensation: bool, gravity_adjusted: bool) -> float: + friction = get_friction(lateral_accel_error, lateral_accel_deadzone, FRICTION_THRESHOLD, torque_params, friction_compensation) + inputs = list(latcontrol_inputs) + if gravity_adjusted: + inputs[0] += inputs[1] + return float(self.neural_ff_model.predict(inputs)) + friction + + def torque_from_lateral_accel(self) -> TorqueFromLateralAccelCallbackType: + if self.CP.carFingerprint == CAR.CHEVROLET_BOLT_EUV: + self.neural_ff_model = NanoFFModel(NEURAL_PARAMS_PATH, self.CP.carFingerprint) + return self.torque_from_lateral_accel_neural + elif self.CP.carFingerprint in NON_LINEAR_TORQUE_PARAMS: + return self.torque_from_lateral_accel_siglin + else: + return self.torque_from_lateral_accel_linear + + @staticmethod + def _get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs): + ret.carName = "gm" + ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.gm)] + ret.autoResumeSng = False + ret.enableBsm = 0x142 in fingerprint[CanBus.POWERTRAIN] + + if candidate in EV_CAR: + ret.transmissionType = TransmissionType.direct + else: + ret.transmissionType = TransmissionType.automatic + + ret.longitudinalTuning.deadzoneBP = [0.] + ret.longitudinalTuning.deadzoneV = [0.15] + + ret.longitudinalTuning.kpBP = [5., 35.] + ret.longitudinalTuning.kiBP = [0.] + + if candidate in CAMERA_ACC_CAR: + ret.experimentalLongitudinalAvailable = True + ret.networkLocation = NetworkLocation.fwdCamera + ret.radarUnavailable = True # no radar + ret.pcmCruise = True + ret.safetyConfigs[0].safetyParam |= Panda.FLAG_GM_HW_CAM + ret.minEnableSpeed = 5 * CV.KPH_TO_MS + ret.minSteerSpeed = 10 * CV.KPH_TO_MS + + # Tuning for experimental long + ret.longitudinalTuning.kpV = [2.0, 1.5] + ret.longitudinalTuning.kiV = [0.72] + ret.stoppingDecelRate = 2.0 # reach brake quickly after enabling + ret.vEgoStopping = 0.25 + ret.vEgoStarting = 0.25 + + if experimental_long: + ret.pcmCruise = False + ret.openpilotLongitudinalControl = True + ret.safetyConfigs[0].safetyParam |= Panda.FLAG_GM_HW_CAM_LONG + + else: # ASCM, OBD-II harness + ret.openpilotLongitudinalControl = True + ret.networkLocation = NetworkLocation.gateway + ret.radarUnavailable = RADAR_HEADER_MSG not in fingerprint[CanBus.OBSTACLE] and not docs + ret.pcmCruise = False # stock non-adaptive cruise control is kept off + # supports stop and go, but initial engage must (conservatively) be above 18mph + ret.minEnableSpeed = 18 * CV.MPH_TO_MS + ret.minSteerSpeed = 7 * CV.MPH_TO_MS + + # Tuning + ret.longitudinalTuning.kpV = [2.4, 1.5] + ret.longitudinalTuning.kiV = [0.36] + + # These cars have been put into dashcam only due to both a lack of users and test coverage. + # These cars likely still work fine. Once a user confirms each car works and a test route is + # added to selfdrive/car/tests/routes.py, we can remove it from this list. + ret.dashcamOnly = candidate in {CAR.CADILLAC_ATS, CAR.HOLDEN_ASTRA, CAR.CHEVROLET_MALIBU, CAR.BUICK_REGAL} or \ + (ret.networkLocation == NetworkLocation.gateway and ret.radarUnavailable) + + # Start with a baseline tuning for all GM vehicles. Override tuning as needed in each model section below. + ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2], [0.00]] + ret.lateralTuning.pid.kf = 0.00004 # full torque for 20 deg at 80mph means 0.00007818594 + ret.steerActuatorDelay = 0.1 # Default delay, not measured yet + + 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 + + if candidate == CAR.CHEVROLET_VOLT: + ret.lateralTuning.pid.kpBP = [0., 40.] + ret.lateralTuning.pid.kpV = [0., 0.17] + ret.lateralTuning.pid.kiBP = [0.] + ret.lateralTuning.pid.kiV = [0.] + ret.lateralTuning.pid.kf = 1. # get_steer_feedforward_volt() + ret.steerActuatorDelay = 0.2 + + elif candidate == CAR.GMC_ACADIA: + ret.minEnableSpeed = -1. # engage speed is decided by pcm + ret.steerActuatorDelay = 0.2 + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) + + elif candidate == CAR.BUICK_LACROSSE: + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) + + elif candidate == CAR.CADILLAC_ESCALADE: + ret.minEnableSpeed = -1. # engage speed is decided by pcm + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) + + elif candidate in (CAR.CADILLAC_ESCALADE_ESV, CAR.CADILLAC_ESCALADE_ESV_2019): + ret.minEnableSpeed = -1. # engage speed is decided by pcm + + if candidate == CAR.CADILLAC_ESCALADE_ESV: + ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[10., 41.0], [10., 41.0]] + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.13, 0.24], [0.01, 0.02]] + ret.lateralTuning.pid.kf = 0.000045 + else: + ret.steerActuatorDelay = 0.2 + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) + + elif candidate == CAR.CHEVROLET_BOLT_EUV: + ret.steerActuatorDelay = 0.2 + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) + + elif candidate == CAR.CHEVROLET_SILVERADO: + # On the Bolt, the ECM and camera independently check that you are either above 5 kph or at a stop + # with foot on brake to allow engagement, but this platform only has that check in the camera. + # TODO: check if this is split by EV/ICE with more platforms in the future + if ret.openpilotLongitudinalControl: + ret.minEnableSpeed = -1. + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) + + elif candidate == CAR.CHEVROLET_EQUINOX: + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) + + elif candidate == CAR.CHEVROLET_TRAILBLAZER: + ret.steerActuatorDelay = 0.2 + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) + + return ret + + # returns a car.CarState + def _update(self, c): + ret = self.CS.update(self.cp, self.cp_cam, self.cp_loopback) + + # Don't add event if transitioning from INIT, unless it's to an actual button + if self.CS.cruise_buttons != CruiseButtons.UNPRESS or self.CS.prev_cruise_buttons != CruiseButtons.INIT: + ret.buttonEvents = [ + *create_button_events(self.CS.cruise_buttons, self.CS.prev_cruise_buttons, BUTTONS_DICT, + unpressed_btn=CruiseButtons.UNPRESS), + *create_button_events(self.CS.distance_button, self.CS.prev_distance_button, + {1: ButtonType.gapAdjustCruise}) + ] + + # The ECM allows enabling on falling edge of set, but only rising edge of resume + events = self.create_common_events(ret, extra_gears=[GearShifter.sport, GearShifter.low, + GearShifter.eco, GearShifter.manumatic], + pcm_enable=self.CP.pcmCruise, enable_buttons=(ButtonType.decelCruise,)) + if not self.CP.pcmCruise: + if any(b.type == ButtonType.accelCruise and b.pressed for b in ret.buttonEvents): + events.add(EventName.buttonEnable) + + # Enabling at a standstill with brake is allowed + # TODO: verify 17 Volt can enable for the first time at a stop and allow for all GMs + below_min_enable_speed = ret.vEgo < self.CP.minEnableSpeed or self.CS.moving_backward + if below_min_enable_speed and not (ret.standstill and ret.brake >= 20 and + self.CP.networkLocation == NetworkLocation.fwdCamera): + events.add(EventName.belowEngageSpeed) + if ret.cruiseState.standstill: + events.add(EventName.resumeRequired) + if ret.vEgo < self.CP.minSteerSpeed: + events.add(EventName.belowSteerSpeed) + + ret.events = events.to_msg() + + return ret diff --git a/car/gm/radar_interface.py b/car/gm/radar_interface.py new file mode 100755 index 0000000000..b893babd31 --- /dev/null +++ b/car/gm/radar_interface.py @@ -0,0 +1,101 @@ +#!/usr/bin/env python3 +import math +from cereal import car +from openpilot.common.conversions import Conversions as CV +from opendbc.can.parser import CANParser +from openpilot.selfdrive.car.gm.values import DBC, CanBus +from openpilot.selfdrive.car.interfaces import RadarInterfaceBase + +RADAR_HEADER_MSG = 1120 +SLOT_1_MSG = RADAR_HEADER_MSG + 1 +NUM_SLOTS = 20 + +# Actually it's 0x47f, but can parser only reports +# messages that are present in DBC +LAST_RADAR_MSG = RADAR_HEADER_MSG + NUM_SLOTS + + +def create_radar_can_parser(car_fingerprint): + # C1A-ARS3-A by Continental + radar_targets = list(range(SLOT_1_MSG, SLOT_1_MSG + NUM_SLOTS)) + signals = list(zip(['FLRRNumValidTargets', + 'FLRRSnsrBlckd', 'FLRRYawRtPlsblityFlt', + 'FLRRHWFltPrsntInt', 'FLRRAntTngFltPrsnt', + 'FLRRAlgnFltPrsnt', 'FLRRSnstvFltPrsntInt'] + + ['TrkRange'] * NUM_SLOTS + ['TrkRangeRate'] * NUM_SLOTS + + ['TrkRangeAccel'] * NUM_SLOTS + ['TrkAzimuth'] * NUM_SLOTS + + ['TrkWidth'] * NUM_SLOTS + ['TrkObjectID'] * NUM_SLOTS, + [RADAR_HEADER_MSG] * 7 + radar_targets * 6, strict=True)) + + messages = list({(s[1], 14) for s in signals}) + + return CANParser(DBC[car_fingerprint]['radar'], messages, CanBus.OBSTACLE) + + +class RadarInterface(RadarInterfaceBase): + def __init__(self, CP): + super().__init__(CP) + + self.rcp = None if CP.radarUnavailable else create_radar_can_parser(CP.carFingerprint) + + self.trigger_msg = LAST_RADAR_MSG + self.updated_messages = set() + self.radar_ts = CP.radarTimeStep + + def update(self, can_strings): + if self.rcp is None: + return super().update(None) + + vls = self.rcp.update_strings(can_strings) + self.updated_messages.update(vls) + + if self.trigger_msg not in self.updated_messages: + return None + + ret = car.RadarData.new_message() + header = self.rcp.vl[RADAR_HEADER_MSG] + fault = header['FLRRSnsrBlckd'] or header['FLRRSnstvFltPrsntInt'] or \ + header['FLRRYawRtPlsblityFlt'] or header['FLRRHWFltPrsntInt'] or \ + header['FLRRAntTngFltPrsnt'] or header['FLRRAlgnFltPrsnt'] + errors = [] + if not self.rcp.can_valid: + errors.append("canError") + if fault: + errors.append("fault") + ret.errors = errors + + currentTargets = set() + num_targets = header['FLRRNumValidTargets'] + + # Not all radar messages describe targets, + # no need to monitor all of the self.rcp.msgs_upd + for ii in self.updated_messages: + if ii == RADAR_HEADER_MSG: + continue + + if num_targets == 0: + break + + cpt = self.rcp.vl[ii] + # Zero distance means it's an empty target slot + if cpt['TrkRange'] > 0.0: + targetId = cpt['TrkObjectID'] + currentTargets.add(targetId) + if targetId not in self.pts: + self.pts[targetId] = car.RadarData.RadarPoint.new_message() + self.pts[targetId].trackId = targetId + distance = cpt['TrkRange'] + self.pts[targetId].dRel = distance # from front of car + # From driver's pov, left is positive + self.pts[targetId].yRel = math.sin(cpt['TrkAzimuth'] * CV.DEG_TO_RAD) * distance + self.pts[targetId].vRel = cpt['TrkRangeRate'] + self.pts[targetId].aRel = float('nan') + self.pts[targetId].yvRel = float('nan') + + for oldTarget in list(self.pts.keys()): + if oldTarget not in currentTargets: + del self.pts[oldTarget] + + ret.points = list(self.pts.values()) + self.updated_messages.clear() + return ret diff --git a/car/gm/tests/__init__.py b/car/gm/tests/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/car/gm/tests/test_gm.py b/car/gm/tests/test_gm.py new file mode 100644 index 0000000000..a0a4a94ffa --- /dev/null +++ b/car/gm/tests/test_gm.py @@ -0,0 +1,20 @@ +from parameterized import parameterized + +from openpilot.selfdrive.car.gm.fingerprints import FINGERPRINTS +from openpilot.selfdrive.car.gm.values import CAMERA_ACC_CAR, GM_RX_OFFSET + +CAMERA_DIAGNOSTIC_ADDRESS = 0x24b + + +class TestGMFingerprint: + @parameterized.expand(FINGERPRINTS.items()) + def test_can_fingerprints(self, car_model, fingerprints): + assert len(fingerprints) > 0 + + assert all(len(finger) for finger in fingerprints) + + # The camera can sometimes be communicating on startup + if car_model in CAMERA_ACC_CAR: + for finger in fingerprints: + for required_addr in (CAMERA_DIAGNOSTIC_ADDRESS, CAMERA_DIAGNOSTIC_ADDRESS + GM_RX_OFFSET): + assert finger.get(required_addr) == 8, required_addr diff --git a/car/gm/values.py b/car/gm/values.py new file mode 100644 index 0000000000..53a4621d27 --- /dev/null +++ b/car/gm/values.py @@ -0,0 +1,234 @@ +from dataclasses import dataclass, field + +from cereal import car +from openpilot.selfdrive.car import dbc_dict, PlatformConfig, DbcDict, Platforms, CarSpecs +from openpilot.selfdrive.car.docs_definitions import CarHarness, CarDocs, CarParts +from openpilot.selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries + +Ecu = car.CarParams.Ecu + + +class CarControllerParams: + STEER_MAX = 300 # GM limit is 3Nm. Used by carcontroller to generate LKA output + STEER_STEP = 3 # Active control frames per command (~33hz) + INACTIVE_STEER_STEP = 10 # Inactive control frames per command (10hz) + STEER_DELTA_UP = 10 # Delta rates require review due to observed EPS weakness + STEER_DELTA_DOWN = 15 + STEER_DRIVER_ALLOWANCE = 65 + STEER_DRIVER_MULTIPLIER = 4 + STEER_DRIVER_FACTOR = 100 + NEAR_STOP_BRAKE_PHASE = 0.5 # m/s + + # Heartbeat for dash "Service Adaptive Cruise" and "Service Front Camera" + ADAS_KEEPALIVE_STEP = 100 + CAMERA_KEEPALIVE_STEP = 100 + + # Allow small margin below -3.5 m/s^2 from ISO 15622:2018 since we + # perform the closed loop control, and might need some + # to apply some more braking if we're on a downhill slope. + # Our controller should still keep the 2 second average above + # -3.5 m/s^2 as per planner limits + ACCEL_MAX = 2. # m/s^2 + ACCEL_MIN = -4. # m/s^2 + + def __init__(self, CP): + # Gas/brake lookups + self.ZERO_GAS = 2048 # Coasting + self.MAX_BRAKE = 400 # ~ -4.0 m/s^2 with regen + + if CP.carFingerprint in CAMERA_ACC_CAR: + self.MAX_GAS = 3400 + self.MAX_ACC_REGEN = 1514 + self.INACTIVE_REGEN = 1554 + # Camera ACC vehicles have no regen while enabled. + # Camera transitions to MAX_ACC_REGEN from ZERO_GAS and uses friction brakes instantly + max_regen_acceleration = 0. + + else: + self.MAX_GAS = 3072 # Safety limit, not ACC max. Stock ACC >4096 from standstill. + self.MAX_ACC_REGEN = 1404 # Max ACC regen is slightly less than max paddle regen + self.INACTIVE_REGEN = 1404 + # ICE has much less engine braking force compared to regen in EVs, + # lower threshold removes some braking deadzone + max_regen_acceleration = -1. if CP.carFingerprint in EV_CAR else -0.1 + + self.GAS_LOOKUP_BP = [max_regen_acceleration, 0., self.ACCEL_MAX] + self.GAS_LOOKUP_V = [self.MAX_ACC_REGEN, self.ZERO_GAS, self.MAX_GAS] + + self.BRAKE_LOOKUP_BP = [self.ACCEL_MIN, max_regen_acceleration] + self.BRAKE_LOOKUP_V = [self.MAX_BRAKE, 0.] + + +@dataclass +class GMCarDocs(CarDocs): + package: str = "Adaptive Cruise Control (ACC)" + + def init_make(self, CP: car.CarParams): + if CP.networkLocation == car.CarParams.NetworkLocation.fwdCamera: + self.car_parts = CarParts.common([CarHarness.gm]) + else: + self.car_parts = CarParts.common([CarHarness.obd_ii]) + + +@dataclass(frozen=True, kw_only=True) +class GMCarSpecs(CarSpecs): + tireStiffnessFactor: float = 0.444 # not optimized yet + + +@dataclass +class GMPlatformConfig(PlatformConfig): + dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict('gm_global_a_powertrain_generated', 'gm_global_a_object', chassis_dbc='gm_global_a_chassis')) + + +@dataclass +class GMASCMPlatformConfig(GMPlatformConfig): + def init(self): + # ASCM is supported, but due to a janky install and hardware configuration, we are not showing in the car docs + self.car_docs = [] + + +class CAR(Platforms): + HOLDEN_ASTRA = GMASCMPlatformConfig( + [GMCarDocs("Holden Astra 2017")], + GMCarSpecs(mass=1363, wheelbase=2.662, steerRatio=15.7, centerToFrontRatio=0.4), + ) + CHEVROLET_VOLT = GMASCMPlatformConfig( + [GMCarDocs("Chevrolet Volt 2017-18", min_enable_speed=0, video_link="https://youtu.be/QeMCN_4TFfQ")], + GMCarSpecs(mass=1607, wheelbase=2.69, steerRatio=17.7, centerToFrontRatio=0.45, tireStiffnessFactor=0.469), + ) + CADILLAC_ATS = GMASCMPlatformConfig( + [GMCarDocs("Cadillac ATS Premium Performance 2018")], + GMCarSpecs(mass=1601, wheelbase=2.78, steerRatio=15.3), + ) + CHEVROLET_MALIBU = GMASCMPlatformConfig( + [GMCarDocs("Chevrolet Malibu Premier 2017")], + GMCarSpecs(mass=1496, wheelbase=2.83, steerRatio=15.8, centerToFrontRatio=0.4), + ) + GMC_ACADIA = GMASCMPlatformConfig( + [GMCarDocs("GMC Acadia 2018", video_link="https://www.youtube.com/watch?v=0ZN6DdsBUZo")], + GMCarSpecs(mass=1975, wheelbase=2.86, steerRatio=14.4, centerToFrontRatio=0.4), + ) + BUICK_LACROSSE = GMASCMPlatformConfig( + [GMCarDocs("Buick LaCrosse 2017-19", "Driver Confidence Package 2")], + GMCarSpecs(mass=1712, wheelbase=2.91, steerRatio=15.8, centerToFrontRatio=0.4), + ) + BUICK_REGAL = GMASCMPlatformConfig( + [GMCarDocs("Buick Regal Essence 2018")], + GMCarSpecs(mass=1714, wheelbase=2.83, steerRatio=14.4, centerToFrontRatio=0.4), + ) + CADILLAC_ESCALADE = GMASCMPlatformConfig( + [GMCarDocs("Cadillac Escalade 2017", "Driver Assist Package")], + GMCarSpecs(mass=2564, wheelbase=2.95, steerRatio=17.3), + ) + CADILLAC_ESCALADE_ESV = GMASCMPlatformConfig( + [GMCarDocs("Cadillac Escalade ESV 2016", "Adaptive Cruise Control (ACC) & LKAS")], + GMCarSpecs(mass=2739, wheelbase=3.302, steerRatio=17.3, tireStiffnessFactor=1.0), + ) + CADILLAC_ESCALADE_ESV_2019 = GMASCMPlatformConfig( + [GMCarDocs("Cadillac Escalade ESV 2019", "Adaptive Cruise Control (ACC) & LKAS")], + CADILLAC_ESCALADE_ESV.specs, + ) + CHEVROLET_BOLT_EUV = GMPlatformConfig( + [ + GMCarDocs("Chevrolet Bolt EUV 2022-23", "Premier or Premier Redline Trim without Super Cruise Package", video_link="https://youtu.be/xvwzGMUA210"), + GMCarDocs("Chevrolet Bolt EV 2022-23", "2LT Trim with Adaptive Cruise Control Package"), + ], + GMCarSpecs(mass=1669, wheelbase=2.63779, steerRatio=16.8, centerToFrontRatio=0.4, tireStiffnessFactor=1.0), + ) + CHEVROLET_SILVERADO = GMPlatformConfig( + [ + GMCarDocs("Chevrolet Silverado 1500 2020-21", "Safety Package II"), + GMCarDocs("GMC Sierra 1500 2020-21", "Driver Alert Package II", video_link="https://youtu.be/5HbNoBLzRwE"), + ], + GMCarSpecs(mass=2450, wheelbase=3.75, steerRatio=16.3, tireStiffnessFactor=1.0), + ) + CHEVROLET_EQUINOX = GMPlatformConfig( + [GMCarDocs("Chevrolet Equinox 2019-22")], + GMCarSpecs(mass=1588, wheelbase=2.72, steerRatio=14.4, centerToFrontRatio=0.4), + ) + CHEVROLET_TRAILBLAZER = GMPlatformConfig( + [GMCarDocs("Chevrolet Trailblazer 2021-22")], + GMCarSpecs(mass=1345, wheelbase=2.64, steerRatio=16.8, centerToFrontRatio=0.4, tireStiffnessFactor=1.0), + ) + + +class CruiseButtons: + INIT = 0 + UNPRESS = 1 + RES_ACCEL = 2 + DECEL_SET = 3 + MAIN = 5 + CANCEL = 6 + +class AccState: + OFF = 0 + ACTIVE = 1 + FAULTED = 3 + STANDSTILL = 4 + +class CanBus: + POWERTRAIN = 0 + OBSTACLE = 1 + CAMERA = 2 + CHASSIS = 2 + LOOPBACK = 128 + DROPPED = 192 + + +# In a Data Module, an identifier is a string used to recognize an object, +# either by itself or together with the identifiers of parent objects. +# Each returns a 4 byte hex representation of the decimal part number. `b"\x02\x8c\xf0'"` -> 42790951 +GM_BOOT_SOFTWARE_PART_NUMER_REQUEST = b'\x1a\xc0' # likely does not contain anything useful +GM_SOFTWARE_MODULE_1_REQUEST = b'\x1a\xc1' +GM_SOFTWARE_MODULE_2_REQUEST = b'\x1a\xc2' +GM_SOFTWARE_MODULE_3_REQUEST = b'\x1a\xc3' + +# Part number of XML data file that is used to configure ECU +GM_XML_DATA_FILE_PART_NUMBER = b'\x1a\x9c' +GM_XML_CONFIG_COMPAT_ID = b'\x1a\x9b' # used to know if XML file is compatible with the ECU software/hardware + +# This DID is for identifying the part number that reflects the mix of hardware, +# software, and calibrations in the ECU when it first arrives at the vehicle assembly plant. +# If there's an Alpha Code, it's associated with this part number and stored in the DID $DB. +GM_END_MODEL_PART_NUMBER_REQUEST = b'\x1a\xcb' +GM_END_MODEL_PART_NUMBER_ALPHA_CODE_REQUEST = b'\x1a\xdb' +GM_BASE_MODEL_PART_NUMBER_REQUEST = b'\x1a\xcc' +GM_BASE_MODEL_PART_NUMBER_ALPHA_CODE_REQUEST = b'\x1a\xdc' +GM_FW_RESPONSE = b'\x5a' + +GM_FW_REQUESTS = [ + GM_BOOT_SOFTWARE_PART_NUMER_REQUEST, + GM_SOFTWARE_MODULE_1_REQUEST, + GM_SOFTWARE_MODULE_2_REQUEST, + GM_SOFTWARE_MODULE_3_REQUEST, + GM_XML_DATA_FILE_PART_NUMBER, + GM_XML_CONFIG_COMPAT_ID, + GM_END_MODEL_PART_NUMBER_REQUEST, + GM_END_MODEL_PART_NUMBER_ALPHA_CODE_REQUEST, + GM_BASE_MODEL_PART_NUMBER_REQUEST, + GM_BASE_MODEL_PART_NUMBER_ALPHA_CODE_REQUEST, +] + +GM_RX_OFFSET = 0x400 + +FW_QUERY_CONFIG = FwQueryConfig( + requests=[request for req in GM_FW_REQUESTS for request in [ + Request( + [StdQueries.SHORT_TESTER_PRESENT_REQUEST, req], + [StdQueries.SHORT_TESTER_PRESENT_RESPONSE, GM_FW_RESPONSE + bytes([req[-1]])], + rx_offset=GM_RX_OFFSET, + bus=0, + logging=True, + ), + ]], + extra_ecus=[(Ecu.fwdCamera, 0x24b, None)], +) + +EV_CAR = {CAR.CHEVROLET_VOLT, CAR.CHEVROLET_BOLT_EUV} + +# We're integrated at the camera with VOACC on these cars (instead of ASCM w/ OBD-II harness) +CAMERA_ACC_CAR = {CAR.CHEVROLET_BOLT_EUV, CAR.CHEVROLET_SILVERADO, CAR.CHEVROLET_EQUINOX, CAR.CHEVROLET_TRAILBLAZER} + +STEER_THRESHOLD = 1.0 + +DBC = CAR.create_dbc_map() diff --git a/car/honda/__init__.py b/car/honda/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/car/honda/carcontroller.py b/car/honda/carcontroller.py new file mode 100644 index 0000000000..fe023ea17d --- /dev/null +++ b/car/honda/carcontroller.py @@ -0,0 +1,256 @@ +from collections import namedtuple + +from cereal import car +from openpilot.common.numpy_fast import clip, interp +from openpilot.common.realtime import DT_CTRL +from opendbc.can.packer import CANPacker +from openpilot.selfdrive.car.honda import hondacan +from openpilot.selfdrive.car.honda.values import CruiseButtons, VISUAL_HUD, HONDA_BOSCH, HONDA_BOSCH_RADARLESS, HONDA_NIDEC_ALT_PCM_ACCEL, CarControllerParams +from openpilot.selfdrive.car.interfaces import CarControllerBase +from openpilot.selfdrive.controls.lib.drive_helpers import rate_limit + +VisualAlert = car.CarControl.HUDControl.VisualAlert +LongCtrlState = car.CarControl.Actuators.LongControlState + + +def compute_gb_honda_bosch(accel, speed): + # TODO returns 0s, is unused + return 0.0, 0.0 + + +def compute_gb_honda_nidec(accel, speed): + creep_brake = 0.0 + creep_speed = 2.3 + creep_brake_value = 0.15 + if speed < creep_speed: + creep_brake = (creep_speed - speed) / creep_speed * creep_brake_value + gb = float(accel) / 4.8 - creep_brake + return clip(gb, 0.0, 1.0), clip(-gb, 0.0, 1.0) + + +def compute_gas_brake(accel, speed, fingerprint): + if fingerprint in HONDA_BOSCH: + return compute_gb_honda_bosch(accel, speed) + else: + return compute_gb_honda_nidec(accel, speed) + + +# TODO not clear this does anything useful +def actuator_hysteresis(brake, braking, brake_steady, v_ego, car_fingerprint): + # hyst params + brake_hyst_on = 0.02 # to activate brakes exceed this value + brake_hyst_off = 0.005 # to deactivate brakes below this value + brake_hyst_gap = 0.01 # don't change brake command for small oscillations within this value + + # *** hysteresis logic to avoid brake blinking. go above 0.1 to trigger + if (brake < brake_hyst_on and not braking) or brake < brake_hyst_off: + brake = 0. + braking = brake > 0. + + # for small brake oscillations within brake_hyst_gap, don't change the brake command + if brake == 0.: + brake_steady = 0. + elif brake > brake_steady + brake_hyst_gap: + brake_steady = brake - brake_hyst_gap + elif brake < brake_steady - brake_hyst_gap: + brake_steady = brake + brake_hyst_gap + brake = brake_steady + + return brake, braking, brake_steady + + +def brake_pump_hysteresis(apply_brake, apply_brake_last, last_pump_ts, ts): + pump_on = False + + # reset pump timer if: + # - there is an increment in brake request + # - we are applying steady state brakes and we haven't been running the pump + # for more than 20s (to prevent pressure bleeding) + if apply_brake > apply_brake_last or (ts - last_pump_ts > 20. and apply_brake > 0): + last_pump_ts = ts + + # once the pump is on, run it for at least 0.2s + if ts - last_pump_ts < 0.2 and apply_brake > 0: + pump_on = True + + return pump_on, last_pump_ts + + +def process_hud_alert(hud_alert): + # initialize to no alert + fcw_display = 0 + steer_required = 0 + acc_alert = 0 + + # priority is: FCW, steer required, all others + if hud_alert == VisualAlert.fcw: + fcw_display = VISUAL_HUD[hud_alert.raw] + elif hud_alert in (VisualAlert.steerRequired, VisualAlert.ldw): + steer_required = VISUAL_HUD[hud_alert.raw] + else: + acc_alert = VISUAL_HUD[hud_alert.raw] + + return fcw_display, steer_required, acc_alert + + +HUDData = namedtuple("HUDData", + ["pcm_accel", "v_cruise", "lead_visible", + "lanes_visible", "fcw", "acc_alert", "steer_required", "lead_distance_bars"]) + + +def rate_limit_steer(new_steer, last_steer): + # TODO just hardcoded ramp to min/max in 0.33s for all Honda + MAX_DELTA = 3 * DT_CTRL + return clip(new_steer, last_steer - MAX_DELTA, last_steer + MAX_DELTA) + + +class CarController(CarControllerBase): + def __init__(self, dbc_name, CP, VM): + self.CP = CP + self.packer = CANPacker(dbc_name) + self.params = CarControllerParams(CP) + self.CAN = hondacan.CanBus(CP) + self.frame = 0 + + self.braking = False + self.brake_steady = 0. + self.brake_last = 0. + self.apply_brake_last = 0 + self.last_pump_ts = 0. + self.stopping_counter = 0 + + self.accel = 0.0 + self.speed = 0.0 + self.gas = 0.0 + self.brake = 0.0 + self.last_steer = 0.0 + + def update(self, CC, CS, now_nanos): + actuators = CC.actuators + hud_control = CC.hudControl + conversion = hondacan.get_cruise_speed_conversion(self.CP.carFingerprint, CS.is_metric) + hud_v_cruise = hud_control.setSpeed / conversion if hud_control.speedVisible else 255 + pcm_cancel_cmd = CC.cruiseControl.cancel + + if CC.longActive: + accel = actuators.accel + gas, brake = compute_gas_brake(actuators.accel, CS.out.vEgo, self.CP.carFingerprint) + else: + accel = 0.0 + gas, brake = 0.0, 0.0 + + # *** rate limit steer *** + limited_steer = rate_limit_steer(actuators.steer, self.last_steer) + self.last_steer = limited_steer + + # *** apply brake hysteresis *** + pre_limit_brake, self.braking, self.brake_steady = actuator_hysteresis(brake, self.braking, self.brake_steady, + CS.out.vEgo, self.CP.carFingerprint) + + # *** rate limit after the enable check *** + self.brake_last = rate_limit(pre_limit_brake, self.brake_last, -2., DT_CTRL) + + # vehicle hud display, wait for one update from 10Hz 0x304 msg + fcw_display, steer_required, acc_alert = process_hud_alert(hud_control.visualAlert) + + # **** process the car messages **** + + # steer torque is converted back to CAN reference (positive when steering right) + apply_steer = int(interp(-limited_steer * self.params.STEER_MAX, + self.params.STEER_LOOKUP_BP, self.params.STEER_LOOKUP_V)) + + # Send CAN commands + can_sends = [] + + # tester present - w/ no response (keeps radar disabled) + if self.CP.carFingerprint in (HONDA_BOSCH - HONDA_BOSCH_RADARLESS) and self.CP.openpilotLongitudinalControl: + if self.frame % 10 == 0: + can_sends.append((0x18DAB0F1, 0, b"\x02\x3E\x80\x00\x00\x00\x00\x00", 1)) + + # Send steering command. + can_sends.append(hondacan.create_steering_control(self.packer, self.CAN, apply_steer, CC.latActive, self.CP.carFingerprint, + CS.CP.openpilotLongitudinalControl)) + + # wind brake from air resistance decel at high speed + wind_brake = interp(CS.out.vEgo, [0.0, 2.3, 35.0], [0.001, 0.002, 0.15]) + # all of this is only relevant for HONDA NIDEC + max_accel = interp(CS.out.vEgo, self.params.NIDEC_MAX_ACCEL_BP, self.params.NIDEC_MAX_ACCEL_V) + # TODO this 1.44 is just to maintain previous behavior + pcm_speed_BP = [-wind_brake, + -wind_brake * (3 / 4), + 0.0, + 0.5] + # The Honda ODYSSEY seems to have different PCM_ACCEL + # msgs, is it other cars too? + if not CC.longActive: + pcm_speed = 0.0 + pcm_accel = int(0.0) + elif self.CP.carFingerprint in HONDA_NIDEC_ALT_PCM_ACCEL: + pcm_speed_V = [0.0, + clip(CS.out.vEgo - 3.0, 0.0, 100.0), + clip(CS.out.vEgo + 0.0, 0.0, 100.0), + clip(CS.out.vEgo + 5.0, 0.0, 100.0)] + pcm_speed = interp(gas - brake, pcm_speed_BP, pcm_speed_V) + pcm_accel = int(1.0 * self.params.NIDEC_GAS_MAX) + else: + pcm_speed_V = [0.0, + clip(CS.out.vEgo - 2.0, 0.0, 100.0), + clip(CS.out.vEgo + 2.0, 0.0, 100.0), + clip(CS.out.vEgo + 5.0, 0.0, 100.0)] + pcm_speed = interp(gas - brake, pcm_speed_BP, pcm_speed_V) + pcm_accel = int(clip((accel / 1.44) / max_accel, 0.0, 1.0) * self.params.NIDEC_GAS_MAX) + + if not self.CP.openpilotLongitudinalControl: + if self.frame % 2 == 0 and self.CP.carFingerprint not in HONDA_BOSCH_RADARLESS: # radarless cars don't have supplemental message + can_sends.append(hondacan.create_bosch_supplemental_1(self.packer, self.CAN, self.CP.carFingerprint)) + # If using stock ACC, spam cancel command to kill gas when OP disengages. + if pcm_cancel_cmd: + can_sends.append(hondacan.spam_buttons_command(self.packer, self.CAN, CruiseButtons.CANCEL, self.CP.carFingerprint)) + elif CC.cruiseControl.resume: + can_sends.append(hondacan.spam_buttons_command(self.packer, self.CAN, CruiseButtons.RES_ACCEL, self.CP.carFingerprint)) + + else: + # Send gas and brake commands. + if self.frame % 2 == 0: + ts = self.frame * DT_CTRL + + if self.CP.carFingerprint in HONDA_BOSCH: + self.accel = clip(accel, self.params.BOSCH_ACCEL_MIN, self.params.BOSCH_ACCEL_MAX) + self.gas = interp(accel, self.params.BOSCH_GAS_LOOKUP_BP, self.params.BOSCH_GAS_LOOKUP_V) + + stopping = actuators.longControlState == LongCtrlState.stopping + self.stopping_counter = self.stopping_counter + 1 if stopping else 0 + can_sends.extend(hondacan.create_acc_commands(self.packer, self.CAN, CC.enabled, CC.longActive, self.accel, self.gas, + self.stopping_counter, self.CP.carFingerprint)) + else: + apply_brake = clip(self.brake_last - wind_brake, 0.0, 1.0) + apply_brake = int(clip(apply_brake * self.params.NIDEC_BRAKE_MAX, 0, self.params.NIDEC_BRAKE_MAX - 1)) + pump_on, self.last_pump_ts = brake_pump_hysteresis(apply_brake, self.apply_brake_last, self.last_pump_ts, ts) + + pcm_override = True + can_sends.append(hondacan.create_brake_command(self.packer, self.CAN, apply_brake, pump_on, + pcm_override, pcm_cancel_cmd, fcw_display, + self.CP.carFingerprint, CS.stock_brake)) + self.apply_brake_last = apply_brake + self.brake = apply_brake / self.params.NIDEC_BRAKE_MAX + + # Send dashboard UI commands. + if self.frame % 10 == 0: + hud = HUDData(int(pcm_accel), int(round(hud_v_cruise)), hud_control.leadVisible, + hud_control.lanesVisible, fcw_display, acc_alert, steer_required, hud_control.leadDistanceBars) + can_sends.extend(hondacan.create_ui_commands(self.packer, self.CAN, self.CP, CC.enabled, pcm_speed, hud, CS.is_metric, CS.acc_hud, CS.lkas_hud)) + + if self.CP.openpilotLongitudinalControl and self.CP.carFingerprint not in HONDA_BOSCH: + self.speed = pcm_speed + self.gas = pcm_accel / self.params.NIDEC_GAS_MAX + + new_actuators = actuators.as_builder() + new_actuators.speed = self.speed + new_actuators.accel = self.accel + new_actuators.gas = self.gas + new_actuators.brake = self.brake + new_actuators.steer = self.last_steer + new_actuators.steerOutputCan = apply_steer + + self.frame += 1 + return new_actuators, can_sends diff --git a/car/honda/carstate.py b/car/honda/carstate.py new file mode 100644 index 0000000000..c98d1a72d3 --- /dev/null +++ b/car/honda/carstate.py @@ -0,0 +1,297 @@ +from collections import defaultdict + +from cereal import car +from openpilot.common.conversions import Conversions as CV +from openpilot.common.numpy_fast import interp +from opendbc.can.can_define import CANDefine +from opendbc.can.parser import CANParser +from openpilot.selfdrive.car.honda.hondacan import CanBus, get_cruise_speed_conversion +from openpilot.selfdrive.car.honda.values import CAR, DBC, STEER_THRESHOLD, HONDA_BOSCH, \ + HONDA_NIDEC_ALT_SCM_MESSAGES, HONDA_BOSCH_RADARLESS, \ + HondaFlags +from openpilot.selfdrive.car.interfaces import CarStateBase + +TransmissionType = car.CarParams.TransmissionType + + +def get_can_messages(CP, gearbox_msg): + messages = [ + ("ENGINE_DATA", 100), + ("WHEEL_SPEEDS", 50), + ("STEERING_SENSORS", 100), + ("SEATBELT_STATUS", 10), + ("CRUISE", 10), + ("POWERTRAIN_DATA", 100), + ("CAR_SPEED", 10), + ("VSA_STATUS", 50), + ("STEER_STATUS", 100), + ("STEER_MOTOR_TORQUE", 0), # TODO: not on every car + ] + + if CP.carFingerprint == CAR.HONDA_ODYSSEY_CHN: + messages += [ + ("SCM_FEEDBACK", 25), + ("SCM_BUTTONS", 50), + ] + else: + messages += [ + ("SCM_FEEDBACK", 10), + ("SCM_BUTTONS", 25), + ] + + if CP.carFingerprint in (CAR.HONDA_CRV_HYBRID, CAR.HONDA_CIVIC_BOSCH_DIESEL, CAR.ACURA_RDX_3G, CAR.HONDA_E): + messages.append((gearbox_msg, 50)) + else: + messages.append((gearbox_msg, 100)) + + if CP.flags & HondaFlags.BOSCH_ALT_BRAKE: + messages.append(("BRAKE_MODULE", 50)) + + if CP.carFingerprint in (HONDA_BOSCH | {CAR.HONDA_CIVIC, CAR.HONDA_ODYSSEY, CAR.HONDA_ODYSSEY_CHN}): + messages.append(("EPB_STATUS", 50)) + + if CP.carFingerprint in HONDA_BOSCH: + # these messages are on camera bus on radarless cars + if not CP.openpilotLongitudinalControl and CP.carFingerprint not in HONDA_BOSCH_RADARLESS: + messages += [ + ("ACC_HUD", 10), + ("ACC_CONTROL", 50), + ] + else: # Nidec signals + if CP.carFingerprint == CAR.HONDA_ODYSSEY_CHN: + messages.append(("CRUISE_PARAMS", 10)) + else: + messages.append(("CRUISE_PARAMS", 50)) + + # TODO: clean this up + if CP.carFingerprint in (CAR.HONDA_ACCORD, CAR.HONDA_CIVIC_BOSCH, CAR.HONDA_CIVIC_BOSCH_DIESEL, CAR.HONDA_CRV_HYBRID, CAR.HONDA_INSIGHT, + CAR.ACURA_RDX_3G, CAR.HONDA_E, CAR.HONDA_CIVIC_2022, CAR.HONDA_HRV_3G): + pass + elif CP.carFingerprint in (CAR.HONDA_ODYSSEY_CHN, CAR.HONDA_FREED, CAR.HONDA_HRV): + pass + else: + messages.append(("DOORS_STATUS", 3)) + + if CP.carFingerprint in HONDA_BOSCH_RADARLESS: + messages.append(("CRUISE_FAULT_STATUS", 50)) + elif CP.openpilotLongitudinalControl: + messages.append(("STANDSTILL", 50)) + + return messages + + +class CarState(CarStateBase): + def __init__(self, CP): + super().__init__(CP) + can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) + self.gearbox_msg = "GEARBOX" + if CP.carFingerprint == CAR.HONDA_ACCORD and CP.transmissionType == TransmissionType.cvt: + self.gearbox_msg = "GEARBOX_15T" + + self.main_on_sig_msg = "SCM_FEEDBACK" + if CP.carFingerprint in HONDA_NIDEC_ALT_SCM_MESSAGES: + self.main_on_sig_msg = "SCM_BUTTONS" + + self.shifter_values = can_define.dv[self.gearbox_msg]["GEAR_SHIFTER"] + self.steer_status_values = defaultdict(lambda: "UNKNOWN", can_define.dv["STEER_STATUS"]["STEER_STATUS"]) + + self.brake_switch_prev = False + self.brake_switch_active = False + self.cruise_setting = 0 + self.v_cruise_pcm_prev = 0 + + # When available we use cp.vl["CAR_SPEED"]["ROUGH_CAR_SPEED_2"] to populate vEgoCluster + # However, on cars without a digital speedometer this is not always present (HRV, FIT, CRV 2016, ILX and RDX) + self.dash_speed_seen = False + + def update(self, cp, cp_cam, cp_body): + ret = car.CarState.new_message() + + # car params + v_weight_v = [0., 1.] # don't trust smooth speed at low values to avoid premature zero snapping + v_weight_bp = [1., 6.] # smooth blending, below ~0.6m/s the smooth speed snaps to zero + + # update prevs, update must run once per loop + self.prev_cruise_buttons = self.cruise_buttons + self.prev_cruise_setting = self.cruise_setting + self.cruise_setting = cp.vl["SCM_BUTTONS"]["CRUISE_SETTING"] + self.cruise_buttons = cp.vl["SCM_BUTTONS"]["CRUISE_BUTTONS"] + + # used for car hud message + self.is_metric = not cp.vl["CAR_SPEED"]["IMPERIAL_UNIT"] + + # ******************* parse out can ******************* + # STANDSTILL->WHEELS_MOVING bit can be noisy around zero, so use XMISSION_SPEED + # panda checks if the signal is non-zero + ret.standstill = cp.vl["ENGINE_DATA"]["XMISSION_SPEED"] < 1e-5 + # TODO: find a common signal across all cars + if self.CP.carFingerprint in (CAR.HONDA_ACCORD, CAR.HONDA_CIVIC_BOSCH, CAR.HONDA_CIVIC_BOSCH_DIESEL, CAR.HONDA_CRV_HYBRID, CAR.HONDA_INSIGHT, + CAR.ACURA_RDX_3G, CAR.HONDA_E, CAR.HONDA_CIVIC_2022, CAR.HONDA_HRV_3G): + ret.doorOpen = bool(cp.vl["SCM_FEEDBACK"]["DRIVERS_DOOR_OPEN"]) + elif self.CP.carFingerprint in (CAR.HONDA_ODYSSEY_CHN, CAR.HONDA_FREED, CAR.HONDA_HRV): + ret.doorOpen = bool(cp.vl["SCM_BUTTONS"]["DRIVERS_DOOR_OPEN"]) + else: + ret.doorOpen = any([cp.vl["DOORS_STATUS"]["DOOR_OPEN_FL"], cp.vl["DOORS_STATUS"]["DOOR_OPEN_FR"], + cp.vl["DOORS_STATUS"]["DOOR_OPEN_RL"], cp.vl["DOORS_STATUS"]["DOOR_OPEN_RR"]]) + ret.seatbeltUnlatched = bool(cp.vl["SEATBELT_STATUS"]["SEATBELT_DRIVER_LAMP"] or not cp.vl["SEATBELT_STATUS"]["SEATBELT_DRIVER_LATCHED"]) + + steer_status = self.steer_status_values[cp.vl["STEER_STATUS"]["STEER_STATUS"]] + ret.steerFaultPermanent = steer_status not in ("NORMAL", "NO_TORQUE_ALERT_1", "NO_TORQUE_ALERT_2", "LOW_SPEED_LOCKOUT", "TMP_FAULT") + # LOW_SPEED_LOCKOUT is not worth a warning + # NO_TORQUE_ALERT_2 can be caused by bump or steering nudge from driver + ret.steerFaultTemporary = steer_status not in ("NORMAL", "LOW_SPEED_LOCKOUT", "NO_TORQUE_ALERT_2") + + if self.CP.carFingerprint in HONDA_BOSCH_RADARLESS: + ret.accFaulted = bool(cp.vl["CRUISE_FAULT_STATUS"]["CRUISE_FAULT"]) + else: + # On some cars, these two signals are always 1, this flag is masking a bug in release + # FIXME: find and set the ACC faulted signals on more platforms + if self.CP.openpilotLongitudinalControl: + ret.accFaulted = bool(cp.vl["STANDSTILL"]["BRAKE_ERROR_1"] or cp.vl["STANDSTILL"]["BRAKE_ERROR_2"]) + + # Log non-critical stock ACC/LKAS faults if Nidec (camera) + if self.CP.carFingerprint not in HONDA_BOSCH: + ret.carFaultedNonCritical = bool(cp_cam.vl["ACC_HUD"]["ACC_PROBLEM"] or cp_cam.vl["LKAS_HUD"]["LKAS_PROBLEM"]) + + ret.espDisabled = cp.vl["VSA_STATUS"]["ESP_DISABLED"] != 0 + + ret.wheelSpeeds = self.get_wheel_speeds( + cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_FL"], + cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_FR"], + cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_RL"], + cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_RR"], + ) + v_wheel = (ret.wheelSpeeds.fl + ret.wheelSpeeds.fr + ret.wheelSpeeds.rl + ret.wheelSpeeds.rr) / 4.0 + + # blend in transmission speed at low speed, since it has more low speed accuracy + v_weight = interp(v_wheel, v_weight_bp, v_weight_v) + ret.vEgoRaw = (1. - v_weight) * cp.vl["ENGINE_DATA"]["XMISSION_SPEED"] * CV.KPH_TO_MS * self.CP.wheelSpeedFactor + v_weight * v_wheel + ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) + + self.dash_speed_seen = self.dash_speed_seen or cp.vl["CAR_SPEED"]["ROUGH_CAR_SPEED_2"] > 1e-3 + if self.dash_speed_seen: + conversion = CV.KPH_TO_MS if self.is_metric else CV.MPH_TO_MS + ret.vEgoCluster = cp.vl["CAR_SPEED"]["ROUGH_CAR_SPEED_2"] * conversion + + ret.steeringAngleDeg = cp.vl["STEERING_SENSORS"]["STEER_ANGLE"] + ret.steeringRateDeg = cp.vl["STEERING_SENSORS"]["STEER_ANGLE_RATE"] + + ret.leftBlinker, ret.rightBlinker = self.update_blinker_from_stalk( + 250, cp.vl["SCM_FEEDBACK"]["LEFT_BLINKER"], cp.vl["SCM_FEEDBACK"]["RIGHT_BLINKER"]) + ret.brakeHoldActive = cp.vl["VSA_STATUS"]["BRAKE_HOLD_ACTIVE"] == 1 + + # TODO: set for all cars + if self.CP.carFingerprint in (HONDA_BOSCH | {CAR.HONDA_CIVIC, CAR.HONDA_ODYSSEY, CAR.HONDA_ODYSSEY_CHN}): + ret.parkingBrake = cp.vl["EPB_STATUS"]["EPB_STATE"] != 0 + + gear = int(cp.vl[self.gearbox_msg]["GEAR_SHIFTER"]) + ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(gear, None)) + + ret.gas = cp.vl["POWERTRAIN_DATA"]["PEDAL_GAS"] + ret.gasPressed = ret.gas > 1e-5 + + ret.steeringTorque = cp.vl["STEER_STATUS"]["STEER_TORQUE_SENSOR"] + ret.steeringTorqueEps = cp.vl["STEER_MOTOR_TORQUE"]["MOTOR_TORQUE"] + ret.steeringPressed = abs(ret.steeringTorque) > STEER_THRESHOLD.get(self.CP.carFingerprint, 1200) + + if self.CP.carFingerprint in HONDA_BOSCH: + # The PCM always manages its own cruise control state, but doesn't publish it + if self.CP.carFingerprint in HONDA_BOSCH_RADARLESS: + ret.cruiseState.nonAdaptive = cp_cam.vl["ACC_HUD"]["CRUISE_CONTROL_LABEL"] != 0 + + if not self.CP.openpilotLongitudinalControl: + # ACC_HUD is on camera bus on radarless cars + acc_hud = cp_cam.vl["ACC_HUD"] if self.CP.carFingerprint in HONDA_BOSCH_RADARLESS else cp.vl["ACC_HUD"] + ret.cruiseState.nonAdaptive = acc_hud["CRUISE_CONTROL_LABEL"] != 0 + ret.cruiseState.standstill = acc_hud["CRUISE_SPEED"] == 252. + + conversion = get_cruise_speed_conversion(self.CP.carFingerprint, self.is_metric) + # On set, cruise set speed pulses between 254~255 and the set speed prev is set to avoid this. + ret.cruiseState.speed = self.v_cruise_pcm_prev if acc_hud["CRUISE_SPEED"] > 160.0 else acc_hud["CRUISE_SPEED"] * conversion + self.v_cruise_pcm_prev = ret.cruiseState.speed + else: + ret.cruiseState.speed = cp.vl["CRUISE"]["CRUISE_SPEED_PCM"] * CV.KPH_TO_MS + + if self.CP.flags & HondaFlags.BOSCH_ALT_BRAKE: + ret.brakePressed = cp.vl["BRAKE_MODULE"]["BRAKE_PRESSED"] != 0 + else: + # brake switch has shown some single time step noise, so only considered when + # switch is on for at least 2 consecutive CAN samples + # brake switch rises earlier than brake pressed but is never 1 when in park + brake_switch_vals = cp.vl_all["POWERTRAIN_DATA"]["BRAKE_SWITCH"] + if len(brake_switch_vals): + brake_switch = cp.vl["POWERTRAIN_DATA"]["BRAKE_SWITCH"] != 0 + if len(brake_switch_vals) > 1: + self.brake_switch_prev = brake_switch_vals[-2] != 0 + self.brake_switch_active = brake_switch and self.brake_switch_prev + self.brake_switch_prev = brake_switch + ret.brakePressed = (cp.vl["POWERTRAIN_DATA"]["BRAKE_PRESSED"] != 0) or self.brake_switch_active + + ret.brake = cp.vl["VSA_STATUS"]["USER_BRAKE"] + ret.cruiseState.enabled = cp.vl["POWERTRAIN_DATA"]["ACC_STATUS"] != 0 + ret.cruiseState.available = bool(cp.vl[self.main_on_sig_msg]["MAIN_ON"]) + + # Gets rid of Pedal Grinding noise when brake is pressed at slow speeds for some models + if self.CP.carFingerprint in (CAR.HONDA_PILOT, CAR.HONDA_RIDGELINE): + if ret.brake > 0.1: + ret.brakePressed = True + + if self.CP.carFingerprint in HONDA_BOSCH: + # TODO: find the radarless AEB_STATUS bit and make sure ACCEL_COMMAND is correct to enable AEB alerts + if self.CP.carFingerprint not in HONDA_BOSCH_RADARLESS: + ret.stockAeb = (not self.CP.openpilotLongitudinalControl) and bool(cp.vl["ACC_CONTROL"]["AEB_STATUS"] and cp.vl["ACC_CONTROL"]["ACCEL_COMMAND"] < -1e-5) + else: + ret.stockAeb = bool(cp_cam.vl["BRAKE_COMMAND"]["AEB_REQ_1"] and cp_cam.vl["BRAKE_COMMAND"]["COMPUTER_BRAKE"] > 1e-5) + + self.acc_hud = False + self.lkas_hud = False + if self.CP.carFingerprint not in HONDA_BOSCH: + ret.stockFcw = cp_cam.vl["BRAKE_COMMAND"]["FCW"] != 0 + self.acc_hud = cp_cam.vl["ACC_HUD"] + self.stock_brake = cp_cam.vl["BRAKE_COMMAND"] + if self.CP.carFingerprint in HONDA_BOSCH_RADARLESS: + self.lkas_hud = cp_cam.vl["LKAS_HUD"] + + if self.CP.enableBsm: + # BSM messages are on B-CAN, requires a panda forwarding B-CAN messages to CAN 0 + # more info here: https://github.com/commaai/openpilot/pull/1867 + ret.leftBlindspot = cp_body.vl["BSM_STATUS_LEFT"]["BSM_ALERT"] == 1 + ret.rightBlindspot = cp_body.vl["BSM_STATUS_RIGHT"]["BSM_ALERT"] == 1 + + return ret + + def get_can_parser(self, CP): + messages = get_can_messages(CP, self.gearbox_msg) + return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus(CP).pt) + + @staticmethod + def get_cam_can_parser(CP): + messages = [ + ("STEERING_CONTROL", 100), + ] + + if CP.carFingerprint in HONDA_BOSCH_RADARLESS: + messages += [ + ("ACC_HUD", 10), + ("LKAS_HUD", 10), + ] + + elif CP.carFingerprint not in HONDA_BOSCH: + messages += [ + ("ACC_HUD", 10), + ("LKAS_HUD", 10), + ("BRAKE_COMMAND", 50), + ] + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus(CP).camera) + + @staticmethod + def get_body_can_parser(CP): + if CP.enableBsm: + messages = [ + ("BSM_STATUS_LEFT", 3), + ("BSM_STATUS_RIGHT", 3), + ] + bus_body = CanBus(CP).radar # B-CAN is forwarded to ACC-CAN radar side (CAN 0 on fake ethernet port) + return CANParser(DBC[CP.carFingerprint]["body"], messages, bus_body) + return None diff --git a/car/honda/fingerprints.py b/car/honda/fingerprints.py new file mode 100644 index 0000000000..8a5b79b41e --- /dev/null +++ b/car/honda/fingerprints.py @@ -0,0 +1,895 @@ +from cereal import car +from openpilot.selfdrive.car.honda.values import CAR + +Ecu = car.CarParams.Ecu + +# Modified FW can be identified by the second dash being replaced by a comma +# For example: `b'39990-TVA,A150\x00\x00'` +# +# TODO: vsa is "essential" for fpv2 but doesn't appear on some CAR.FREED models + + +FW_VERSIONS = { + CAR.HONDA_ACCORD: { + (Ecu.shiftByWire, 0x18da0bf1, None): [ + b'54008-TVC-A910\x00\x00', + b'54008-TWA-A910\x00\x00', + ], + (Ecu.transmission, 0x18da1ef1, None): [ + b'28101-6A7-A220\x00\x00', + b'28101-6A7-A230\x00\x00', + b'28101-6A7-A320\x00\x00', + b'28101-6A7-A330\x00\x00', + b'28101-6A7-A410\x00\x00', + b'28101-6A7-A510\x00\x00', + b'28101-6A7-A610\x00\x00', + b'28101-6A7-A710\x00\x00', + b'28101-6A9-H140\x00\x00', + b'28101-6A9-H420\x00\x00', + b'28102-6B8-A560\x00\x00', + b'28102-6B8-A570\x00\x00', + b'28102-6B8-A700\x00\x00', + b'28102-6B8-A800\x00\x00', + b'28102-6B8-C560\x00\x00', + b'28102-6B8-C570\x00\x00', + b'28102-6B8-M520\x00\x00', + b'28102-6B8-R700\x00\x00', + ], + (Ecu.electricBrakeBooster, 0x18da2bf1, None): [ + b'46114-TVA-A050\x00\x00', + b'46114-TVA-A060\x00\x00', + b'46114-TVA-A080\x00\x00', + b'46114-TVA-A120\x00\x00', + b'46114-TVA-A320\x00\x00', + b'46114-TVE-H550\x00\x00', + b'46114-TVE-H560\x00\x00', + ], + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-TVA-B040\x00\x00', + b'57114-TVA-B050\x00\x00', + b'57114-TVA-B060\x00\x00', + b'57114-TVA-B530\x00\x00', + b'57114-TVA-C040\x00\x00', + b'57114-TVA-C050\x00\x00', + b'57114-TVA-C060\x00\x00', + b'57114-TVA-C530\x00\x00', + b'57114-TVA-E520\x00\x00', + b'57114-TVE-H250\x00\x00', + b'57114-TWA-A040\x00\x00', + b'57114-TWA-A050\x00\x00', + b'57114-TWA-A530\x00\x00', + b'57114-TWA-B520\x00\x00', + b'57114-TWA-C510\x00\x00', + b'57114-TWB-H030\x00\x00', + ], + (Ecu.eps, 0x18da30f1, None): [ + b'39990-TBX-H120\x00\x00', + b'39990-TVA,A150\x00\x00', + b'39990-TVA-A140\x00\x00', + b'39990-TVA-A150\x00\x00', + b'39990-TVA-A160\x00\x00', + b'39990-TVA-A340\x00\x00', + b'39990-TVA-X030\x00\x00', + b'39990-TVA-X040\x00\x00', + b'39990-TVE-H130\x00\x00', + b'39990-TWB-H120\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-TBX-H230\x00\x00', + b'77959-TVA-A460\x00\x00', + b'77959-TVA-F330\x00\x00', + b'77959-TVA-H230\x00\x00', + b'77959-TVA-L420\x00\x00', + b'77959-TVA-X330\x00\x00', + b'77959-TWA-A440\x00\x00', + b'77959-TWA-L420\x00\x00', + b'77959-TWB-H220\x00\x00', + ], + (Ecu.hud, 0x18da61f1, None): [ + b'78209-TVA-A010\x00\x00', + b'78209-TVA-A110\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36802-TBX-H140\x00\x00', + b'36802-TVA-A150\x00\x00', + b'36802-TVA-A160\x00\x00', + b'36802-TVA-A170\x00\x00', + b'36802-TVA-A180\x00\x00', + b'36802-TVA-A330\x00\x00', + b'36802-TVC-A330\x00\x00', + b'36802-TVE-H070\x00\x00', + b'36802-TWA-A070\x00\x00', + b'36802-TWA-A080\x00\x00', + b'36802-TWA-A210\x00\x00', + b'36802-TWA-A330\x00\x00', + b'36802-TWB-H060\x00\x00', + ], + (Ecu.fwdCamera, 0x18dab5f1, None): [ + b'36161-TBX-H130\x00\x00', + b'36161-TVA-A060\x00\x00', + b'36161-TVA-A330\x00\x00', + b'36161-TVC-A330\x00\x00', + b'36161-TVE-H050\x00\x00', + b'36161-TWA-A070\x00\x00', + b'36161-TWA-A330\x00\x00', + b'36161-TWB-H040\x00\x00', + ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-TVA-A010\x00\x00', + b'38897-TVA-A020\x00\x00', + b'38897-TVA-A230\x00\x00', + b'38897-TVA-A240\x00\x00', + b'38897-TWA-A120\x00\x00', + b'38897-TWD-J020\x00\x00', + ], + }, + CAR.HONDA_CIVIC: { + (Ecu.transmission, 0x18da1ef1, None): [ + b'28101-5CG-A040\x00\x00', + b'28101-5CG-A050\x00\x00', + b'28101-5CG-A070\x00\x00', + b'28101-5CG-A080\x00\x00', + b'28101-5CG-A320\x00\x00', + b'28101-5CG-A810\x00\x00', + b'28101-5CG-A820\x00\x00', + b'28101-5DJ-A040\x00\x00', + b'28101-5DJ-A060\x00\x00', + b'28101-5DJ-A510\x00\x00', + ], + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-TBA-A540\x00\x00', + b'57114-TBA-A550\x00\x00', + b'57114-TBA-A560\x00\x00', + b'57114-TBA-A570\x00\x00', + b'57114-TEA-Q220\x00\x00', + ], + (Ecu.eps, 0x18da30f1, None): [ + b'39990-TBA,A030\x00\x00', + b'39990-TBA-A030\x00\x00', + b'39990-TBG-A030\x00\x00', + b'39990-TEA-T020\x00\x00', + b'39990-TEG-A010\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-TBA-A030\x00\x00', + b'77959-TBA-A040\x00\x00', + b'77959-TBG-A020\x00\x00', + b'77959-TBG-A030\x00\x00', + b'77959-TEA-Q820\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36161-TBA-A020\x00\x00', + b'36161-TBA-A030\x00\x00', + b'36161-TBA-A040\x00\x00', + b'36161-TBC-A020\x00\x00', + b'36161-TBC-A030\x00\x00', + b'36161-TED-Q320\x00\x00', + b'36161-TEG-A010\x00\x00', + b'36161-TEG-A020\x00\x00', + ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-TBA-A010\x00\x00', + b'38897-TBA-A020\x00\x00', + ], + }, + CAR.HONDA_CIVIC_BOSCH: { + (Ecu.transmission, 0x18da1ef1, None): [ + b'28101-5CG-A920\x00\x00', + b'28101-5CG-AB10\x00\x00', + b'28101-5CG-C110\x00\x00', + b'28101-5CG-C220\x00\x00', + b'28101-5CG-C320\x00\x00', + b'28101-5CG-G020\x00\x00', + b'28101-5CG-L020\x00\x00', + b'28101-5CK-A130\x00\x00', + b'28101-5CK-A140\x00\x00', + b'28101-5CK-A150\x00\x00', + b'28101-5CK-C130\x00\x00', + b'28101-5CK-C140\x00\x00', + b'28101-5CK-C150\x00\x00', + b'28101-5CK-G210\x00\x00', + b'28101-5CK-J710\x00\x00', + b'28101-5CK-Q610\x00\x00', + b'28101-5DJ-A610\x00\x00', + b'28101-5DJ-A710\x00\x00', + b'28101-5DV-E330\x00\x00', + b'28101-5DV-E610\x00\x00', + b'28101-5DV-E820\x00\x00', + ], + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-TBG-A330\x00\x00', + b'57114-TBG-A340\x00\x00', + b'57114-TBG-A350\x00\x00', + b'57114-TGG-A340\x00\x00', + b'57114-TGG-C320\x00\x00', + b'57114-TGG-G320\x00\x00', + b'57114-TGG-L320\x00\x00', + b'57114-TGG-L330\x00\x00', + b'57114-TGH-L130\x00\x00', + b'57114-TGK-T320\x00\x00', + b'57114-TGL-G330\x00\x00', + ], + (Ecu.eps, 0x18da30f1, None): [ + b'39990-TBA-C020\x00\x00', + b'39990-TBA-C120\x00\x00', + b'39990-TEA-T820\x00\x00', + b'39990-TEZ-T020\x00\x00', + b'39990-TGG,A020\x00\x00', + b'39990-TGG,A120\x00\x00', + b'39990-TGG-A020\x00\x00', + b'39990-TGG-A120\x00\x00', + b'39990-TGG-J510\x00\x00', + b'39990-TGH-J530\x00\x00', + b'39990-TGL-E130\x00\x00', + b'39990-TGN-E120\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-TBA-A060\x00\x00', + b'77959-TBG-A050\x00\x00', + b'77959-TEA-G020\x00\x00', + b'77959-TGG-A020\x00\x00', + b'77959-TGG-A030\x00\x00', + b'77959-TGG-E010\x00\x00', + b'77959-TGG-G010\x00\x00', + b'77959-TGG-G110\x00\x00', + b'77959-TGG-J320\x00\x00', + b'77959-TGG-Z820\x00\x00', + b'77959-TGH-J110\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36802-TBA-A150\x00\x00', + b'36802-TBA-A160\x00\x00', + b'36802-TFJ-G060\x00\x00', + b'36802-TGG-A050\x00\x00', + b'36802-TGG-A060\x00\x00', + b'36802-TGG-A070\x00\x00', + b'36802-TGG-A130\x00\x00', + b'36802-TGG-G040\x00\x00', + b'36802-TGG-G130\x00\x00', + b'36802-TGH-A140\x00\x00', + b'36802-TGK-Q120\x00\x00', + b'36802-TGL-G040\x00\x00', + ], + (Ecu.fwdCamera, 0x18dab5f1, None): [ + b'36161-TBA-A130\x00\x00', + b'36161-TBA-A140\x00\x00', + b'36161-TFJ-G070\x00\x00', + b'36161-TGG-A060\x00\x00', + b'36161-TGG-A080\x00\x00', + b'36161-TGG-A120\x00\x00', + b'36161-TGG-G050\x00\x00', + b'36161-TGG-G070\x00\x00', + b'36161-TGG-G130\x00\x00', + b'36161-TGG-G140\x00\x00', + b'36161-TGH-A140\x00\x00', + b'36161-TGK-Q120\x00\x00', + b'36161-TGL-G050\x00\x00', + b'36161-TGL-G070\x00\x00', + ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-TBA-A020\x00\x00', + b'38897-TBA-A110\x00\x00', + b'38897-TGH-A010\x00\x00', + ], + (Ecu.electricBrakeBooster, 0x18da2bf1, None): [ + b'39494-TGL-G030\x00\x00', + ], + }, + CAR.HONDA_CIVIC_BOSCH_DIESEL: { + (Ecu.transmission, 0x18da1ef1, None): [ + b'28101-59Y-G220\x00\x00', + b'28101-59Y-G620\x00\x00', + ], + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-TGN-E320\x00\x00', + ], + (Ecu.eps, 0x18da30f1, None): [ + b'39990-TFK-G020\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-TFK-G210\x00\x00', + b'77959-TGN-G220\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36802-TFK-G130\x00\x00', + b'36802-TGN-G130\x00\x00', + ], + (Ecu.shiftByWire, 0x18da0bf1, None): [ + b'54008-TGN-E010\x00\x00', + ], + (Ecu.fwdCamera, 0x18dab5f1, None): [ + b'36161-TFK-G130\x00\x00', + b'36161-TGN-G130\x00\x00', + ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-TBA-A020\x00\x00', + ], + }, + CAR.HONDA_CRV: { + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-T1W-A230\x00\x00', + b'57114-T1W-A240\x00\x00', + b'57114-TFF-A940\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-T0A-A230\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36161-T1W-A830\x00\x00', + b'36161-T1W-C830\x00\x00', + b'36161-T1X-A830\x00\x00', + ], + }, + CAR.HONDA_CRV_5G: { + (Ecu.transmission, 0x18da1ef1, None): [ + b'28101-5RG-A020\x00\x00', + b'28101-5RG-A030\x00\x00', + b'28101-5RG-A040\x00\x00', + b'28101-5RG-A120\x00\x00', + b'28101-5RG-A220\x00\x00', + b'28101-5RH-A020\x00\x00', + b'28101-5RH-A030\x00\x00', + b'28101-5RH-A040\x00\x00', + b'28101-5RH-A120\x00\x00', + b'28101-5RH-A220\x00\x00', + b'28101-5RL-Q010\x00\x00', + b'28101-5RM-F010\x00\x00', + b'28101-5RM-K010\x00\x00', + ], + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-TLA-A040\x00\x00', + b'57114-TLA-A050\x00\x00', + b'57114-TLA-A060\x00\x00', + b'57114-TLB-A830\x00\x00', + b'57114-TMC-Z040\x00\x00', + b'57114-TMC-Z050\x00\x00', + ], + (Ecu.eps, 0x18da30f1, None): [ + b'39990-TLA,A040\x00\x00', + b'39990-TLA-A040\x00\x00', + b'39990-TLA-A110\x00\x00', + b'39990-TLA-A220\x00\x00', + b'39990-TME-T030\x00\x00', + b'39990-TME-T120\x00\x00', + b'39990-TMT-T010\x00\x00', + ], + (Ecu.electricBrakeBooster, 0x18da2bf1, None): [ + b'46114-TLA-A040\x00\x00', + b'46114-TLA-A050\x00\x00', + b'46114-TLA-A930\x00\x00', + b'46114-TMC-U020\x00\x00', + ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-TLA-A010\x00\x00', + b'38897-TLA-A110\x00\x00', + b'38897-TNY-G010\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36802-TLA-A040\x00\x00', + b'36802-TLA-A050\x00\x00', + b'36802-TLA-A060\x00\x00', + b'36802-TLA-A070\x00\x00', + b'36802-TMC-Q040\x00\x00', + b'36802-TMC-Q070\x00\x00', + b'36802-TNY-A030\x00\x00', + ], + (Ecu.fwdCamera, 0x18dab5f1, None): [ + b'36161-TLA-A060\x00\x00', + b'36161-TLA-A070\x00\x00', + b'36161-TLA-A080\x00\x00', + b'36161-TMC-Q020\x00\x00', + b'36161-TMC-Q030\x00\x00', + b'36161-TMC-Q040\x00\x00', + b'36161-TNY-A020\x00\x00', + b'36161-TNY-A030\x00\x00', + b'36161-TNY-A040\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-TLA-A240\x00\x00', + b'77959-TLA-A250\x00\x00', + b'77959-TLA-A320\x00\x00', + b'77959-TLA-A410\x00\x00', + b'77959-TLA-A420\x00\x00', + b'77959-TLA-Q040\x00\x00', + b'77959-TLA-Z040\x00\x00', + b'77959-TMM-F040\x00\x00', + ], + }, + CAR.HONDA_CRV_EU: { + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-T1V-G920\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36161-T1V-G520\x00\x00', + ], + (Ecu.shiftByWire, 0x18da0bf1, None): [ + b'54008-T1V-G010\x00\x00', + ], + (Ecu.transmission, 0x18da1ef1, None): [ + b'28101-5LH-E120\x00\x00', + b'28103-5LH-E100\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-T1G-G940\x00\x00', + ], + }, + CAR.HONDA_CRV_HYBRID: { + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-TMB-H030\x00\x00', + b'57114-TPA-G020\x00\x00', + b'57114-TPG-A020\x00\x00', + ], + (Ecu.eps, 0x18da30f1, None): [ + b'39990-TMA-H020\x00\x00', + b'39990-TPA-G030\x00\x00', + b'39990-TPG-A020\x00\x00', + ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-TMA-H110\x00\x00', + b'38897-TPG-A110\x00\x00', + b'38897-TPG-A210\x00\x00', + ], + (Ecu.shiftByWire, 0x18da0bf1, None): [ + b'54008-TMB-H510\x00\x00', + b'54008-TMB-H610\x00\x00', + ], + (Ecu.fwdCamera, 0x18dab5f1, None): [ + b'36161-TMB-H040\x00\x00', + b'36161-TPA-E050\x00\x00', + b'36161-TPG-A030\x00\x00', + b'36161-TPG-A040\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36802-TMB-H040\x00\x00', + b'36802-TPA-E040\x00\x00', + b'36802-TPG-A020\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-TLA-C320\x00\x00', + b'77959-TLA-C410\x00\x00', + b'77959-TLA-C420\x00\x00', + b'77959-TLA-G220\x00\x00', + b'77959-TLA-H240\x00\x00', + ], + }, + CAR.HONDA_FIT: { + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-T5R-L020\x00\x00', + b'57114-T5R-L220\x00\x00', + ], + (Ecu.eps, 0x18da30f1, None): [ + b'39990-T5R-C020\x00\x00', + b'39990-T5R-C030\x00\x00', + ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-T5A-J010\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36161-T5R-A040\x00\x00', + b'36161-T5R-A240\x00\x00', + b'36161-T5R-A520\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-T5R-A230\x00\x00', + ], + }, + CAR.HONDA_FREED: { + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-TDK-J010\x00\x00', + ], + (Ecu.eps, 0x18da30f1, None): [ + b'39990-TDK-J050\x00\x00', + b'39990-TDK-N020\x00\x00', + ], + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-TDK-J120\x00\x00', + b'57114-TDK-J330\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36161-TDK-J070\x00\x00', + b'36161-TDK-J080\x00\x00', + b'36161-TDK-J530\x00\x00', + ], + }, + CAR.HONDA_ODYSSEY: { + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-THR-A010\x00\x00', + b'38897-THR-A020\x00\x00', + ], + (Ecu.eps, 0x18da30f1, None): [ + b'39990-THR-A020\x00\x00', + b'39990-THR-A030\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-THR-A010\x00\x00', + b'77959-THR-A110\x00\x00', + b'77959-THR-X010\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36161-THR-A020\x00\x00', + b'36161-THR-A030\x00\x00', + b'36161-THR-A110\x00\x00', + b'36161-THR-A720\x00\x00', + b'36161-THR-A730\x00\x00', + b'36161-THR-A810\x00\x00', + b'36161-THR-A910\x00\x00', + b'36161-THR-C010\x00\x00', + b'36161-THR-D110\x00\x00', + b'36161-THR-K020\x00\x00', + ], + (Ecu.transmission, 0x18da1ef1, None): [ + b'28101-5NZ-A110\x00\x00', + b'28101-5NZ-A310\x00\x00', + b'28101-5NZ-C310\x00\x00', + b'28102-5MX-A001\x00\x00', + b'28102-5MX-A600\x00\x00', + b'28102-5MX-A610\x00\x00', + b'28102-5MX-A700\x00\x00', + b'28102-5MX-A710\x00\x00', + b'28102-5MX-A900\x00\x00', + b'28102-5MX-A910\x00\x00', + b'28102-5MX-C001\x00\x00', + b'28102-5MX-C910\x00\x00', + b'28102-5MX-D001\x00\x00', + b'28102-5MX-D710\x00\x00', + b'28102-5MX-K610\x00\x00', + b'28103-5NZ-A100\x00\x00', + b'28103-5NZ-A300\x00\x00', + ], + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-THR-A040\x00\x00', + b'57114-THR-A110\x00\x00', + ], + (Ecu.shiftByWire, 0x18da0bf1, None): [ + b'54008-THR-A020\x00\x00', + ], + }, + CAR.HONDA_ODYSSEY_CHN: { + (Ecu.eps, 0x18da30f1, None): [ + b'39990-T6D-H220\x00\x00', + ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-T6A-J010\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36161-T6A-P040\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-T6A-P110\x00\x00', + ], + }, + CAR.HONDA_PILOT: { + (Ecu.shiftByWire, 0x18da0bf1, None): [ + b'54008-TG7-A520\x00\x00', + b'54008-TG7-A530\x00\x00', + ], + (Ecu.transmission, 0x18da1ef1, None): [ + b'28101-5EY-A040\x00\x00', + b'28101-5EY-A050\x00\x00', + b'28101-5EY-A100\x00\x00', + b'28101-5EY-A430\x00\x00', + b'28101-5EY-A500\x00\x00', + b'28101-5EZ-A050\x00\x00', + b'28101-5EZ-A060\x00\x00', + b'28101-5EZ-A100\x00\x00', + b'28101-5EZ-A210\x00\x00', + b'28101-5EZ-A330\x00\x00', + b'28101-5EZ-A430\x00\x00', + b'28101-5EZ-A500\x00\x00', + b'28101-5EZ-A600\x00\x00', + b'28101-5EZ-A700\x00\x00', + b'28103-5EY-A110\x00\x00', + ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-TG7-A030\x00\x00', + b'38897-TG7-A040\x00\x00', + b'38897-TG7-A110\x00\x00', + b'38897-TG7-A210\x00\x00', + ], + (Ecu.eps, 0x18da30f1, None): [ + b'39990-TG7-A030\x00\x00', + b'39990-TG7-A040\x00\x00', + b'39990-TG7-A060\x00\x00', + b'39990-TG7-A070\x00\x00', + b'39990-TGS-A230\x00\x00', + b'39990-TGS-A320\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36161-TG7-A310\x00\x00', + b'36161-TG7-A520\x00\x00', + b'36161-TG7-A630\x00\x00', + b'36161-TG7-A720\x00\x00', + b'36161-TG7-A820\x00\x00', + b'36161-TG7-A930\x00\x00', + b'36161-TG7-C520\x00\x00', + b'36161-TG7-D520\x00\x00', + b'36161-TG7-D630\x00\x00', + b'36161-TG7-Y630\x00\x00', + b'36161-TG8-A410\x00\x00', + b'36161-TG8-A520\x00\x00', + b'36161-TG8-A630\x00\x00', + b'36161-TG8-A720\x00\x00', + b'36161-TG8-A830\x00\x00', + b'36161-TGS-A030\x00\x00', + b'36161-TGS-A130\x00\x00', + b'36161-TGS-A220\x00\x00', + b'36161-TGS-A320\x00\x00', + b'36161-TGT-A030\x00\x00', + b'36161-TGT-A130\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-TG7-A020\x00\x00', + b'77959-TG7-A110\x00\x00', + b'77959-TG7-A210\x00\x00', + b'77959-TG7-Y210\x00\x00', + b'77959-TGS-A010\x00\x00', + b'77959-TGS-A110\x00\x00', + ], + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-TG7-A130\x00\x00', + b'57114-TG7-A140\x00\x00', + b'57114-TG7-A230\x00\x00', + b'57114-TG7-A240\x00\x00', + b'57114-TG7-A630\x00\x00', + b'57114-TG7-A730\x00\x00', + b'57114-TG8-A140\x00\x00', + b'57114-TG8-A230\x00\x00', + b'57114-TG8-A240\x00\x00', + b'57114-TG8-A630\x00\x00', + b'57114-TG8-A730\x00\x00', + b'57114-TGS-A530\x00\x00', + b'57114-TGT-A530\x00\x00', + ], + }, + CAR.ACURA_RDX: { + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-TX4-A220\x00\x00', + b'57114-TX5-A220\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36161-TX4-A030\x00\x00', + b'36161-TX5-A030\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-TX4-B010\x00\x00', + b'77959-TX4-C010\x00\x00', + b'77959-TX4-C020\x00\x00', + ], + }, + CAR.ACURA_RDX_3G: { + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-TJB-A030\x00\x00', + b'57114-TJB-A040\x00\x00', + b'57114-TJB-A120\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36802-TJB-A040\x00\x00', + b'36802-TJB-A050\x00\x00', + b'36802-TJB-A540\x00\x00', + ], + (Ecu.fwdCamera, 0x18dab5f1, None): [ + b'36161-TJB-A040\x00\x00', + b'36161-TJB-A530\x00\x00', + ], + (Ecu.shiftByWire, 0x18da0bf1, None): [ + b'54008-TJB-A520\x00\x00', + b'54008-TJB-A530\x00\x00', + ], + (Ecu.transmission, 0x18da1ef1, None): [ + b'28102-5YK-A610\x00\x00', + b'28102-5YK-A620\x00\x00', + b'28102-5YK-A630\x00\x00', + b'28102-5YK-A700\x00\x00', + b'28102-5YK-A711\x00\x00', + b'28102-5YK-A800\x00\x00', + b'28102-5YL-A620\x00\x00', + b'28102-5YL-A700\x00\x00', + b'28102-5YL-A711\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-TJB-A040\x00\x00', + b'77959-TJB-A120\x00\x00', + b'77959-TJB-A210\x00\x00', + ], + (Ecu.electricBrakeBooster, 0x18da2bf1, None): [ + b'46114-TJB-A040\x00\x00', + b'46114-TJB-A050\x00\x00', + b'46114-TJB-A060\x00\x00', + b'46114-TJB-A120\x00\x00', + ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-TJB-A040\x00\x00', + b'38897-TJB-A110\x00\x00', + b'38897-TJB-A120\x00\x00', + b'38897-TJB-A220\x00\x00', + ], + (Ecu.eps, 0x18da30f1, None): [ + b'39990-TJB-A030\x00\x00', + b'39990-TJB-A040\x00\x00', + b'39990-TJB-A070\x00\x00', + b'39990-TJB-A130\x00\x00', + ], + }, + CAR.HONDA_RIDGELINE: { + (Ecu.eps, 0x18da30f1, None): [ + b'39990-T6Z-A020\x00\x00', + b'39990-T6Z-A030\x00\x00', + b'39990-T6Z-A050\x00\x00', + b'39990-T6Z-A110\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36161-T6Z-A020\x00\x00', + b'36161-T6Z-A310\x00\x00', + b'36161-T6Z-A420\x00\x00', + b'36161-T6Z-A520\x00\x00', + b'36161-T6Z-A620\x00\x00', + b'36161-T6Z-A720\x00\x00', + b'36161-TJZ-A120\x00\x00', + ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-T6Z-A010\x00\x00', + b'38897-T6Z-A110\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-T6Z-A020\x00\x00', + ], + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-T6Z-A120\x00\x00', + b'57114-T6Z-A130\x00\x00', + b'57114-T6Z-A520\x00\x00', + b'57114-T6Z-A610\x00\x00', + b'57114-TJZ-A520\x00\x00', + ], + }, + CAR.HONDA_INSIGHT: { + (Ecu.eps, 0x18da30f1, None): [ + b'39990-TXM-A040\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36802-TXM-A070\x00\x00', + b'36802-TXM-A080\x00\x00', + ], + (Ecu.fwdCamera, 0x18dab5f1, None): [ + b'36161-TXM-A050\x00\x00', + b'36161-TXM-A060\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-TXM-A230\x00\x00', + ], + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-TXM-A030\x00\x00', + b'57114-TXM-A040\x00\x00', + ], + (Ecu.shiftByWire, 0x18da0bf1, None): [ + b'54008-TWA-A910\x00\x00', + ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-TXM-A020\x00\x00', + ], + }, + CAR.HONDA_HRV: { + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-T7A-A010\x00\x00', + b'38897-T7A-A110\x00\x00', + ], + (Ecu.eps, 0x18da30f1, None): [ + b'39990-THX-A020\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36161-T7A-A040\x00\x00', + b'36161-T7A-A140\x00\x00', + b'36161-T7A-A240\x00\x00', + b'36161-T7A-C440\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-T7A-A230\x00\x00', + ], + }, + CAR.HONDA_HRV_3G: { + (Ecu.eps, 0x18da30f1, None): [ + b'39990-3M0-G110\x00\x00', + b'39990-3W0-A030\x00\x00', + ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-3M0-M110\x00\x00', + b'38897-3W1-A010\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-3M0-K840\x00\x00', + b'77959-3V0-A820\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'8S102-3M6-P030\x00\x00', + b'8S102-3W0-A060\x00\x00', + b'8S102-3W0-AB10\x00\x00', + ], + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-3M6-M010\x00\x00', + b'57114-3W0-A040\x00\x00', + ], + (Ecu.transmission, 0x18da1ef1, None): [ + b'28101-6EH-A010\x00\x00', + b'28101-6JC-M310\x00\x00', + ], + (Ecu.electricBrakeBooster, 0x18da2bf1, None): [ + b'46114-3W0-A020\x00\x00', + ], + }, + CAR.ACURA_ILX: { + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-TX6-A010\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36161-TV9-A140\x00\x00', + b'36161-TX6-A030\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-TX6-A230\x00\x00', + b'77959-TX6-C210\x00\x00', + ], + }, + CAR.HONDA_E: { + (Ecu.eps, 0x18da30f1, None): [ + b'39990-TYF-N030\x00\x00', + ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-TYF-E140\x00\x00', + ], + (Ecu.shiftByWire, 0x18da0bf1, None): [ + b'54008-TYF-E010\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-TYF-G430\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36802-TYF-E030\x00\x00', + ], + (Ecu.fwdCamera, 0x18dab5f1, None): [ + b'36161-TYF-E020\x00\x00', + ], + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-TYF-E030\x00\x00', + ], + }, + CAR.HONDA_CIVIC_2022: { + (Ecu.eps, 0x18da30f1, None): [ + b'39990-T24-T120\x00\x00', + b'39990-T39-A130\x00\x00', + b'39990-T43-J020\x00\x00', + ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-T20-A020\x00\x00', + b'38897-T20-A210\x00\x00', + b'38897-T20-A310\x00\x00', + b'38897-T20-A510\x00\x00', + b'38897-T21-A010\x00\x00', + b'38897-T24-Z120\x00\x00', + ], + (Ecu.srs, 0x18da53f1, None): [ + b'77959-T20-A970\x00\x00', + b'77959-T20-A980\x00\x00', + b'77959-T20-M820\x00\x00', + b'77959-T47-A940\x00\x00', + b'77959-T47-A950\x00\x00', + ], + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36161-T20-A060\x00\x00', + b'36161-T20-A070\x00\x00', + b'36161-T20-A080\x00\x00', + b'36161-T24-T070\x00\x00', + b'36161-T47-A070\x00\x00', + ], + (Ecu.vsa, 0x18da28f1, None): [ + b'57114-T20-AB40\x00\x00', + b'57114-T24-TB30\x00\x00', + b'57114-T43-JB30\x00\x00', + ], + (Ecu.transmission, 0x18da1ef1, None): [ + b'28101-65D-A020\x00\x00', + b'28101-65D-A120\x00\x00', + b'28101-65H-A020\x00\x00', + b'28101-65H-A120\x00\x00', + b'28101-65J-N010\x00\x00', + ], + }, +} diff --git a/car/honda/hondacan.py b/car/honda/hondacan.py new file mode 100644 index 0000000000..1be496d951 --- /dev/null +++ b/car/honda/hondacan.py @@ -0,0 +1,211 @@ +from openpilot.common.conversions import Conversions as CV +from openpilot.selfdrive.car import CanBusBase +from openpilot.selfdrive.car.honda.values import HondaFlags, HONDA_BOSCH, HONDA_BOSCH_RADARLESS, CAR, CarControllerParams + +# CAN bus layout with relay +# 0 = ACC-CAN - radar side +# 1 = F-CAN B - powertrain +# 2 = ACC-CAN - camera side +# 3 = F-CAN A - OBDII port + + +class CanBus(CanBusBase): + def __init__(self, CP=None, fingerprint=None) -> None: + # use fingerprint if specified + super().__init__(CP if fingerprint is None else None, fingerprint) + + if CP.carFingerprint in (HONDA_BOSCH - HONDA_BOSCH_RADARLESS): + self._pt, self._radar = self.offset + 1, self.offset + else: + self._pt, self._radar = self.offset, self.offset + 1 + + @property + def pt(self) -> int: + return self._pt + + @property + def radar(self) -> int: + return self._radar + + @property + def camera(self) -> int: + return self.offset + 2 + + +def get_lkas_cmd_bus(CAN, car_fingerprint, radar_disabled=False): + no_radar = car_fingerprint in HONDA_BOSCH_RADARLESS + if radar_disabled or no_radar: + # when radar is disabled, steering commands are sent directly to powertrain bus + return CAN.pt + # normally steering commands are sent to radar, which forwards them to powertrain bus + return 0 + + +def get_cruise_speed_conversion(car_fingerprint: str, is_metric: bool) -> float: + # on certain cars, CRUISE_SPEED changes to imperial with car's unit setting + return CV.MPH_TO_MS if car_fingerprint in HONDA_BOSCH_RADARLESS and not is_metric else CV.KPH_TO_MS + + +def create_brake_command(packer, CAN, apply_brake, pump_on, pcm_override, pcm_cancel_cmd, fcw, car_fingerprint, stock_brake): + # TODO: do we loose pressure if we keep pump off for long? + brakelights = apply_brake > 0 + brake_rq = apply_brake > 0 + pcm_fault_cmd = False + + values = { + "COMPUTER_BRAKE": apply_brake, + "BRAKE_PUMP_REQUEST": pump_on, + "CRUISE_OVERRIDE": pcm_override, + "CRUISE_FAULT_CMD": pcm_fault_cmd, + "CRUISE_CANCEL_CMD": pcm_cancel_cmd, + "COMPUTER_BRAKE_REQUEST": brake_rq, + "SET_ME_1": 1, + "BRAKE_LIGHTS": brakelights, + "CHIME": stock_brake["CHIME"] if fcw else 0, # send the chime for stock fcw + "FCW": fcw << 1, # TODO: Why are there two bits for fcw? + "AEB_REQ_1": 0, + "AEB_REQ_2": 0, + "AEB_STATUS": 0, + } + return packer.make_can_msg("BRAKE_COMMAND", CAN.pt, values) + + +def create_acc_commands(packer, CAN, enabled, active, accel, gas, stopping_counter, car_fingerprint): + commands = [] + min_gas_accel = CarControllerParams.BOSCH_GAS_LOOKUP_BP[0] + + control_on = 5 if enabled else 0 + gas_command = gas if active and accel > min_gas_accel else -30000 + accel_command = accel if active else 0 + braking = 1 if active and accel < min_gas_accel else 0 + standstill = 1 if active and stopping_counter > 0 else 0 + standstill_release = 1 if active and stopping_counter == 0 else 0 + + # common ACC_CONTROL values + acc_control_values = { + 'ACCEL_COMMAND': accel_command, + 'STANDSTILL': standstill, + } + + if car_fingerprint in HONDA_BOSCH_RADARLESS: + acc_control_values.update({ + "CONTROL_ON": enabled, + "IDLESTOP_ALLOW": stopping_counter > 200, # allow idle stop after 4 seconds (50 Hz) + }) + else: + acc_control_values.update({ + # setting CONTROL_ON causes car to set POWERTRAIN_DATA->ACC_STATUS = 1 + "CONTROL_ON": control_on, + "GAS_COMMAND": gas_command, # used for gas + "BRAKE_LIGHTS": braking, + "BRAKE_REQUEST": braking, + "STANDSTILL_RELEASE": standstill_release, + }) + acc_control_on_values = { + "SET_TO_3": 0x03, + "CONTROL_ON": enabled, + "SET_TO_FF": 0xff, + "SET_TO_75": 0x75, + "SET_TO_30": 0x30, + } + commands.append(packer.make_can_msg("ACC_CONTROL_ON", CAN.pt, acc_control_on_values)) + + commands.append(packer.make_can_msg("ACC_CONTROL", CAN.pt, acc_control_values)) + return commands + + +def create_steering_control(packer, CAN, apply_steer, lkas_active, car_fingerprint, radar_disabled): + values = { + "STEER_TORQUE": apply_steer if lkas_active else 0, + "STEER_TORQUE_REQUEST": lkas_active, + } + bus = get_lkas_cmd_bus(CAN, car_fingerprint, radar_disabled) + return packer.make_can_msg("STEERING_CONTROL", bus, values) + + +def create_bosch_supplemental_1(packer, CAN, car_fingerprint): + # non-active params + values = { + "SET_ME_X04": 0x04, + "SET_ME_X80": 0x80, + "SET_ME_X10": 0x10, + } + bus = get_lkas_cmd_bus(CAN, car_fingerprint) + return packer.make_can_msg("BOSCH_SUPPLEMENTAL_1", bus, values) + + +def create_ui_commands(packer, CAN, CP, enabled, pcm_speed, hud, is_metric, acc_hud, lkas_hud): + commands = [] + radar_disabled = CP.carFingerprint in (HONDA_BOSCH - HONDA_BOSCH_RADARLESS) and CP.openpilotLongitudinalControl + bus_lkas = get_lkas_cmd_bus(CAN, CP.carFingerprint, radar_disabled) + + if CP.openpilotLongitudinalControl: + acc_hud_values = { + 'CRUISE_SPEED': hud.v_cruise, + 'ENABLE_MINI_CAR': 1 if enabled else 0, + # only moves the lead car without ACC_ON + 'HUD_DISTANCE': (hud.lead_distance_bars + 1) % 4, # wraps to 0 at 4 bars + 'IMPERIAL_UNIT': int(not is_metric), + 'HUD_LEAD': 2 if enabled and hud.lead_visible else 1 if enabled else 0, + 'SET_ME_X01_2': 1, + } + + if CP.carFingerprint in HONDA_BOSCH: + acc_hud_values['ACC_ON'] = int(enabled) + acc_hud_values['FCM_OFF'] = 1 + acc_hud_values['FCM_OFF_2'] = 1 + else: + # Shows the distance bars, TODO: stock camera shows updates temporarily while disabled + acc_hud_values['ACC_ON'] = int(enabled) + acc_hud_values['PCM_SPEED'] = pcm_speed * CV.MS_TO_KPH + acc_hud_values['PCM_GAS'] = hud.pcm_accel + acc_hud_values['SET_ME_X01'] = 1 + acc_hud_values['FCM_OFF'] = acc_hud['FCM_OFF'] + acc_hud_values['FCM_OFF_2'] = acc_hud['FCM_OFF_2'] + acc_hud_values['FCM_PROBLEM'] = acc_hud['FCM_PROBLEM'] + acc_hud_values['ICONS'] = acc_hud['ICONS'] + commands.append(packer.make_can_msg("ACC_HUD", CAN.pt, acc_hud_values)) + + lkas_hud_values = { + 'SET_ME_X41': 0x41, + 'STEERING_REQUIRED': hud.steer_required, + 'SOLID_LANES': hud.lanes_visible, + 'BEEP': 0, + } + + if CP.carFingerprint in HONDA_BOSCH_RADARLESS: + lkas_hud_values['LANE_LINES'] = 3 + lkas_hud_values['DASHED_LANES'] = hud.lanes_visible + # car likely needs to see LKAS_PROBLEM fall within a specific time frame, so forward from camera + lkas_hud_values['LKAS_PROBLEM'] = lkas_hud['LKAS_PROBLEM'] + + if not (CP.flags & HondaFlags.BOSCH_EXT_HUD): + lkas_hud_values['SET_ME_X48'] = 0x48 + + if CP.flags & HondaFlags.BOSCH_EXT_HUD and not CP.openpilotLongitudinalControl: + commands.append(packer.make_can_msg('LKAS_HUD_A', bus_lkas, lkas_hud_values)) + commands.append(packer.make_can_msg('LKAS_HUD_B', bus_lkas, lkas_hud_values)) + else: + commands.append(packer.make_can_msg('LKAS_HUD', bus_lkas, lkas_hud_values)) + + if radar_disabled: + radar_hud_values = { + 'CMBS_OFF': 0x01, + 'SET_TO_1': 0x01, + } + commands.append(packer.make_can_msg('RADAR_HUD', CAN.pt, radar_hud_values)) + + if CP.carFingerprint == CAR.HONDA_CIVIC_BOSCH: + commands.append(packer.make_can_msg("LEGACY_BRAKE_COMMAND", CAN.pt, {})) + + return commands + + +def spam_buttons_command(packer, CAN, button_val, car_fingerprint): + values = { + 'CRUISE_BUTTONS': button_val, + 'CRUISE_SETTING': 0, + } + # send buttons to camera on radarless cars + bus = CAN.camera if car_fingerprint in HONDA_BOSCH_RADARLESS else CAN.pt + return packer.make_can_msg("SCM_BUTTONS", bus, values) diff --git a/car/honda/interface.py b/car/honda/interface.py new file mode 100755 index 0000000000..2026c385c2 --- /dev/null +++ b/car/honda/interface.py @@ -0,0 +1,259 @@ +#!/usr/bin/env python3 +from cereal import car +from panda import Panda +from openpilot.common.conversions import Conversions as CV +from openpilot.common.numpy_fast import interp +from openpilot.selfdrive.car.honda.hondacan import CanBus +from openpilot.selfdrive.car.honda.values import CarControllerParams, CruiseButtons, CruiseSettings, HondaFlags, CAR, HONDA_BOSCH, \ + HONDA_NIDEC_ALT_SCM_MESSAGES, HONDA_BOSCH_RADARLESS +from openpilot.selfdrive.car import create_button_events, get_safety_config +from openpilot.selfdrive.car.interfaces import CarInterfaceBase +from openpilot.selfdrive.car.disable_ecu import disable_ecu + + +ButtonType = car.CarState.ButtonEvent.Type +EventName = car.CarEvent.EventName +TransmissionType = car.CarParams.TransmissionType +BUTTONS_DICT = {CruiseButtons.RES_ACCEL: ButtonType.accelCruise, CruiseButtons.DECEL_SET: ButtonType.decelCruise, + CruiseButtons.MAIN: ButtonType.altButton3, CruiseButtons.CANCEL: ButtonType.cancel} +SETTINGS_BUTTONS_DICT = {CruiseSettings.DISTANCE: ButtonType.gapAdjustCruise, CruiseSettings.LKAS: ButtonType.altButton1} + + +class CarInterface(CarInterfaceBase): + @staticmethod + def get_pid_accel_limits(CP, current_speed, cruise_speed): + if CP.carFingerprint in HONDA_BOSCH: + return CarControllerParams.BOSCH_ACCEL_MIN, CarControllerParams.BOSCH_ACCEL_MAX + else: + # NIDECs don't allow acceleration near cruise_speed, + # so limit limits of pid to prevent windup + ACCEL_MAX_VALS = [CarControllerParams.NIDEC_ACCEL_MAX, 0.2] + ACCEL_MAX_BP = [cruise_speed - 2., cruise_speed - .2] + return CarControllerParams.NIDEC_ACCEL_MIN, interp(current_speed, ACCEL_MAX_BP, ACCEL_MAX_VALS) + + @staticmethod + def _get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs): + ret.carName = "honda" + + CAN = CanBus(ret, fingerprint) + + if candidate in HONDA_BOSCH: + ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.hondaBosch)] + ret.radarUnavailable = True + # Disable the radar and let openpilot control longitudinal + # WARNING: THIS DISABLES AEB! + # If Bosch radarless, this blocks ACC messages from the camera + ret.experimentalLongitudinalAvailable = True + ret.openpilotLongitudinalControl = experimental_long + ret.pcmCruise = not ret.openpilotLongitudinalControl + else: + ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.hondaNidec)] + ret.openpilotLongitudinalControl = True + + ret.pcmCruise = True + + if candidate == CAR.HONDA_CRV_5G: + ret.enableBsm = 0x12f8bfa7 in fingerprint[CAN.radar] + + # Detect Bosch cars with new HUD msgs + if any(0x33DA in f for f in fingerprint.values()): + ret.flags |= HondaFlags.BOSCH_EXT_HUD.value + + # Accord ICE 1.5T CVT has different gearbox message + if candidate == CAR.HONDA_ACCORD and 0x191 in fingerprint[CAN.pt]: + ret.transmissionType = TransmissionType.cvt + + # Certain Hondas have an extra steering sensor at the bottom of the steering rack, + # which improves controls quality as it removes the steering column torsion from feedback. + # Tire stiffness factor fictitiously lower if it includes the steering column torsion effect. + # For modeling details, see p.198-200 in "The Science of Vehicle Dynamics (2014), M. Guiggiani" + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0], [0]] + ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] + ret.lateralTuning.pid.kf = 0.00006 # conservative feed-forward + + if candidate in HONDA_BOSCH: + ret.longitudinalTuning.kpV = [0.25] + ret.longitudinalTuning.kiV = [0.05] + ret.longitudinalActuatorDelayUpperBound = 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: + # default longitudinal tuning for all hondas + ret.longitudinalTuning.kpBP = [0., 5., 35.] + ret.longitudinalTuning.kpV = [1.2, 0.8, 0.5] + ret.longitudinalTuning.kiBP = [0., 35.] + ret.longitudinalTuning.kiV = [0.18, 0.12] + + eps_modified = False + for fw in car_fw: + if fw.ecu == "eps" and b"," in fw.fwVersion: + eps_modified = True + + if candidate == CAR.HONDA_CIVIC: + if eps_modified: + # stock request input values: 0x0000, 0x00DE, 0x014D, 0x01EF, 0x0290, 0x0377, 0x0454, 0x0610, 0x06EE + # stock request output values: 0x0000, 0x0917, 0x0DC5, 0x1017, 0x119F, 0x140B, 0x1680, 0x1680, 0x1680 + # modified request output values: 0x0000, 0x0917, 0x0DC5, 0x1017, 0x119F, 0x140B, 0x1680, 0x2880, 0x3180 + # stock filter output values: 0x009F, 0x0108, 0x0108, 0x0108, 0x0108, 0x0108, 0x0108, 0x0108, 0x0108 + # modified filter output values: 0x009F, 0x0108, 0x0108, 0x0108, 0x0108, 0x0108, 0x0108, 0x0400, 0x0480 + # note: max request allowed is 4096, but request is capped at 3840 in firmware, so modifications result in 2x max + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 2560, 8000], [0, 2560, 3840]] + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.3], [0.1]] + else: + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 2560], [0, 2560]] + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[1.1], [0.33]] + + elif candidate in (CAR.HONDA_CIVIC_BOSCH, CAR.HONDA_CIVIC_BOSCH_DIESEL, CAR.HONDA_CIVIC_2022): + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.8], [0.24]] + + elif candidate == CAR.HONDA_ACCORD: + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end + + if eps_modified: + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.3], [0.09]] + else: + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.18]] + + elif candidate == CAR.ACURA_ILX: + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 3840], [0, 3840]] # TODO: determine if there is a dead zone at the top end + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.8], [0.24]] + + elif candidate in (CAR.HONDA_CRV, CAR.HONDA_CRV_EU): + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 1000], [0, 1000]] # TODO: determine if there is a dead zone at the top end + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.8], [0.24]] + ret.wheelSpeedFactor = 1.025 + + elif candidate == CAR.HONDA_CRV_5G: + if eps_modified: + # stock request input values: 0x0000, 0x00DB, 0x01BB, 0x0296, 0x0377, 0x0454, 0x0532, 0x0610, 0x067F + # stock request output values: 0x0000, 0x0500, 0x0A15, 0x0E6D, 0x1100, 0x1200, 0x129A, 0x134D, 0x1400 + # modified request output values: 0x0000, 0x0500, 0x0A15, 0x0E6D, 0x1100, 0x1200, 0x1ACD, 0x239A, 0x2800 + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 2560, 10000], [0, 2560, 3840]] + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.21], [0.07]] + else: + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 3840], [0, 3840]] + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.64], [0.192]] + ret.wheelSpeedFactor = 1.025 + + elif candidate == CAR.HONDA_CRV_HYBRID: + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.18]] + ret.wheelSpeedFactor = 1.025 + + elif candidate == CAR.HONDA_FIT: + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2], [0.05]] + + elif candidate == CAR.HONDA_FREED: + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2], [0.05]] + + elif candidate in (CAR.HONDA_HRV, CAR.HONDA_HRV_3G): + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] + if candidate == CAR.HONDA_HRV: + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.16], [0.025]] + ret.wheelSpeedFactor = 1.025 + else: + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.8], [0.24]] # TODO: can probably use some tuning + + elif candidate == CAR.ACURA_RDX: + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 1000], [0, 1000]] # TODO: determine if there is a dead zone at the top end + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.8], [0.24]] + + elif candidate == CAR.ACURA_RDX_3G: + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 3840], [0, 3840]] + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2], [0.06]] + + elif candidate in (CAR.HONDA_ODYSSEY, CAR.HONDA_ODYSSEY_CHN): + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.28], [0.08]] + if candidate == CAR.HONDA_ODYSSEY_CHN: + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 32767], [0, 32767]] # TODO: determine if there is a dead zone at the top end + else: + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end + + elif candidate == CAR.HONDA_PILOT: + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.38], [0.11]] + + elif candidate == CAR.HONDA_RIDGELINE: + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.38], [0.11]] + + elif candidate == CAR.HONDA_INSIGHT: + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.18]] + + elif candidate == CAR.HONDA_E: + ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.18]] # TODO: can probably use some tuning + + else: + raise ValueError(f"unsupported car {candidate}") + + # These cars use alternate user brake msg (0x1BE) + # TODO: Only detect feature for Accord/Accord Hybrid, not all Bosch DBCs have BRAKE_MODULE + if 0x1BE in fingerprint[CAN.pt] and candidate in (CAR.HONDA_ACCORD, CAR.HONDA_HRV_3G): + ret.flags |= HondaFlags.BOSCH_ALT_BRAKE.value + + if ret.flags & HondaFlags.BOSCH_ALT_BRAKE: + ret.safetyConfigs[0].safetyParam |= Panda.FLAG_HONDA_ALT_BRAKE + + # These cars use alternate SCM messages (SCM_FEEDBACK AND SCM_BUTTON) + if candidate in HONDA_NIDEC_ALT_SCM_MESSAGES: + ret.safetyConfigs[0].safetyParam |= Panda.FLAG_HONDA_NIDEC_ALT + + if ret.openpilotLongitudinalControl and candidate in HONDA_BOSCH: + ret.safetyConfigs[0].safetyParam |= Panda.FLAG_HONDA_BOSCH_LONG + + if candidate in HONDA_BOSCH_RADARLESS: + ret.safetyConfigs[0].safetyParam |= Panda.FLAG_HONDA_RADARLESS + + # min speed to enable ACC. if car can do stop and go, then set enabling speed + # to a negative value, so it won't matter. Otherwise, add 0.5 mph margin to not + # conflict with PCM acc + ret.autoResumeSng = candidate in (HONDA_BOSCH | {CAR.HONDA_CIVIC}) + ret.minEnableSpeed = -1. if ret.autoResumeSng else 25.5 * CV.MPH_TO_MS + + ret.steerActuatorDelay = 0.1 + ret.steerLimitTimer = 0.8 + + return ret + + @staticmethod + def init(CP, logcan, sendcan): + if CP.carFingerprint in (HONDA_BOSCH - HONDA_BOSCH_RADARLESS) and CP.openpilotLongitudinalControl: + disable_ecu(logcan, sendcan, bus=1, addr=0x18DAB0F1, com_cont_req=b'\x28\x83\x03') + + # returns a car.CarState + def _update(self, c): + ret = self.CS.update(self.cp, self.cp_cam, self.cp_body) + + ret.buttonEvents = [ + *create_button_events(self.CS.cruise_buttons, self.CS.prev_cruise_buttons, BUTTONS_DICT), + *create_button_events(self.CS.cruise_setting, self.CS.prev_cruise_setting, SETTINGS_BUTTONS_DICT), + ] + + # events + events = self.create_common_events(ret, pcm_enable=False) + if self.CP.pcmCruise and ret.vEgo < self.CP.minEnableSpeed: + events.add(EventName.belowEngageSpeed) + + if self.CP.pcmCruise: + # we engage when pcm is active (rising edge) + if ret.cruiseState.enabled and not self.CS.out.cruiseState.enabled: + events.add(EventName.pcmEnable) + elif not ret.cruiseState.enabled and (c.actuators.accel >= 0. or not self.CP.openpilotLongitudinalControl): + # it can happen that car cruise disables while comma system is enabled: need to + # keep braking if needed or if the speed is very low + if ret.vEgo < self.CP.minEnableSpeed + 2.: + # non loud alert if cruise disables below 25mph as expected (+ a little margin) + events.add(EventName.speedTooLow) + else: + events.add(EventName.cruiseDisabled) + if self.CS.CP.minEnableSpeed > 0 and ret.vEgo < 0.001: + events.add(EventName.manualRestart) + + ret.events = events.to_msg() + + return ret diff --git a/car/honda/radar_interface.py b/car/honda/radar_interface.py new file mode 100755 index 0000000000..8090f8e03e --- /dev/null +++ b/car/honda/radar_interface.py @@ -0,0 +1,84 @@ +#!/usr/bin/env python3 +from cereal import car +from opendbc.can.parser import CANParser +from openpilot.selfdrive.car.interfaces import RadarInterfaceBase +from openpilot.selfdrive.car.honda.values import DBC + + +def _create_nidec_can_parser(car_fingerprint): + radar_messages = [0x400] + list(range(0x430, 0x43A)) + list(range(0x440, 0x446)) + messages = [(m, 20) for m in radar_messages] + return CANParser(DBC[car_fingerprint]['radar'], messages, 1) + + +class RadarInterface(RadarInterfaceBase): + def __init__(self, CP): + super().__init__(CP) + self.track_id = 0 + self.radar_fault = False + self.radar_wrong_config = False + self.radar_off_can = CP.radarUnavailable + self.radar_ts = CP.radarTimeStep + + self.delay = int(round(0.1 / CP.radarTimeStep)) # 0.1s delay of radar + + # Nidec + if self.radar_off_can: + self.rcp = None + else: + self.rcp = _create_nidec_can_parser(CP.carFingerprint) + self.trigger_msg = 0x445 + self.updated_messages = set() + + def update(self, can_strings): + # in Bosch radar and we are only steering for now, so sleep 0.05s to keep + # radard at 20Hz and return no points + if self.radar_off_can: + return super().update(None) + + vls = self.rcp.update_strings(can_strings) + self.updated_messages.update(vls) + + if self.trigger_msg not in self.updated_messages: + return None + + rr = self._update(self.updated_messages) + self.updated_messages.clear() + return rr + + def _update(self, updated_messages): + ret = car.RadarData.new_message() + + for ii in sorted(updated_messages): + cpt = self.rcp.vl[ii] + if ii == 0x400: + # check for radar faults + self.radar_fault = cpt['RADAR_STATE'] != 0x79 + self.radar_wrong_config = cpt['RADAR_STATE'] == 0x69 + elif cpt['LONG_DIST'] < 255: + if ii not in self.pts or cpt['NEW_TRACK']: + self.pts[ii] = car.RadarData.RadarPoint.new_message() + self.pts[ii].trackId = self.track_id + self.track_id += 1 + self.pts[ii].dRel = cpt['LONG_DIST'] # from front of car + self.pts[ii].yRel = -cpt['LAT_DIST'] # in car frame's y axis, left is positive + self.pts[ii].vRel = cpt['REL_SPEED'] + self.pts[ii].aRel = float('nan') + self.pts[ii].yvRel = float('nan') + self.pts[ii].measured = True + else: + if ii in self.pts: + del self.pts[ii] + + errors = [] + if not self.rcp.can_valid: + errors.append("canError") + if self.radar_fault: + errors.append("fault") + if self.radar_wrong_config: + errors.append("wrongConfig") + ret.errors = errors + + ret.points = list(self.pts.values()) + + return ret diff --git a/car/honda/tests/__init__.py b/car/honda/tests/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/car/honda/tests/test_honda.py b/car/honda/tests/test_honda.py new file mode 100644 index 0000000000..b8ad7872b2 --- /dev/null +++ b/car/honda/tests/test_honda.py @@ -0,0 +1,14 @@ +import re + +from openpilot.selfdrive.car.honda.fingerprints import FW_VERSIONS + +HONDA_FW_VERSION_RE = br"[A-Z0-9]{5}-[A-Z0-9]{3}(-|,)[A-Z0-9]{4}(\x00){2}$" + + +class TestHondaFingerprint: + def test_fw_version_format(self): + # Asserts all FW versions follow an expected format + for fw_by_ecu in FW_VERSIONS.values(): + for fws in fw_by_ecu.values(): + for fw in fws: + assert re.match(HONDA_FW_VERSION_RE, fw) is not None, fw diff --git a/car/honda/values.py b/car/honda/values.py new file mode 100644 index 0000000000..c3005c667c --- /dev/null +++ b/car/honda/values.py @@ -0,0 +1,331 @@ +from dataclasses import dataclass +from enum import Enum, IntFlag + +from cereal import car +from openpilot.common.conversions import Conversions as CV +from panda.python import uds +from openpilot.selfdrive.car import CarSpecs, PlatformConfig, Platforms, dbc_dict +from openpilot.selfdrive.car.docs_definitions import CarFootnote, CarHarness, CarDocs, CarParts, Column +from openpilot.selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries, p16 + +Ecu = car.CarParams.Ecu +VisualAlert = car.CarControl.HUDControl.VisualAlert + + +class CarControllerParams: + # Allow small margin below -3.5 m/s^2 from ISO 15622:2018 since we + # perform the closed loop control, and might need some + # to apply some more braking if we're on a downhill slope. + # Our controller should still keep the 2 second average above + # -3.5 m/s^2 as per planner limits + NIDEC_ACCEL_MIN = -4.0 # m/s^2 + NIDEC_ACCEL_MAX = 1.6 # m/s^2, lower than 2.0 m/s^2 for tuning reasons + + NIDEC_ACCEL_LOOKUP_BP = [-1., 0., .6] + NIDEC_ACCEL_LOOKUP_V = [-4.8, 0., 2.0] + + NIDEC_MAX_ACCEL_V = [0.5, 2.4, 1.4, 0.6] + NIDEC_MAX_ACCEL_BP = [0.0, 4.0, 10., 20.] + + NIDEC_GAS_MAX = 198 # 0xc6 + NIDEC_BRAKE_MAX = 1024 // 4 + + BOSCH_ACCEL_MIN = -3.5 # m/s^2 + BOSCH_ACCEL_MAX = 2.0 # m/s^2 + + BOSCH_GAS_LOOKUP_BP = [-0.2, 2.0] # 2m/s^2 + BOSCH_GAS_LOOKUP_V = [0, 1600] + + def __init__(self, CP): + self.STEER_MAX = CP.lateralParams.torqueBP[-1] + # mirror of list (assuming first item is zero) for interp of signed request values + assert(CP.lateralParams.torqueBP[0] == 0) + assert(CP.lateralParams.torqueBP[0] == 0) + self.STEER_LOOKUP_BP = [v * -1 for v in CP.lateralParams.torqueBP][1:][::-1] + list(CP.lateralParams.torqueBP) + self.STEER_LOOKUP_V = [v * -1 for v in CP.lateralParams.torqueV][1:][::-1] + list(CP.lateralParams.torqueV) + + +class HondaFlags(IntFlag): + # Detected flags + # Bosch models with alternate set of LKAS_HUD messages + BOSCH_EXT_HUD = 1 + BOSCH_ALT_BRAKE = 2 + + # Static flags + BOSCH = 4 + BOSCH_RADARLESS = 8 + + NIDEC = 16 + NIDEC_ALT_PCM_ACCEL = 32 + NIDEC_ALT_SCM_MESSAGES = 64 + + +# Car button codes +class CruiseButtons: + RES_ACCEL = 4 + DECEL_SET = 3 + CANCEL = 2 + MAIN = 1 + + +class CruiseSettings: + DISTANCE = 3 + LKAS = 1 + + +# See dbc files for info on values +VISUAL_HUD = { + VisualAlert.none: 0, + VisualAlert.fcw: 1, + VisualAlert.steerRequired: 1, + VisualAlert.ldw: 1, + VisualAlert.brakePressed: 10, + VisualAlert.wrongGear: 6, + VisualAlert.seatbeltUnbuckled: 5, + VisualAlert.speedTooHigh: 8 +} + + +@dataclass +class HondaCarDocs(CarDocs): + package: str = "Honda Sensing" + + def init_make(self, CP: car.CarParams): + if CP.flags & HondaFlags.BOSCH: + self.car_parts = CarParts.common([CarHarness.bosch_b]) if CP.flags & HondaFlags.BOSCH_RADARLESS else CarParts.common([CarHarness.bosch_a]) + else: + self.car_parts = CarParts.common([CarHarness.nidec]) + + +class Footnote(Enum): + CIVIC_DIESEL = CarFootnote( + "2019 Honda Civic 1.6L Diesel Sedan does not have ALC below 12mph.", + Column.FSR_STEERING) + + +class HondaBoschPlatformConfig(PlatformConfig): + def init(self): + self.flags |= HondaFlags.BOSCH + + +class HondaNidecPlatformConfig(PlatformConfig): + def init(self): + self.flags |= HondaFlags.NIDEC + + +class CAR(Platforms): + # Bosch Cars + HONDA_ACCORD = HondaBoschPlatformConfig( + [ + HondaCarDocs("Honda Accord 2018-22", "All", video_link="https://www.youtube.com/watch?v=mrUwlj3Mi58", min_steer_speed=3. * CV.MPH_TO_MS), + HondaCarDocs("Honda Inspire 2018", "All", min_steer_speed=3. * CV.MPH_TO_MS), + HondaCarDocs("Honda Accord Hybrid 2018-22", "All", min_steer_speed=3. * CV.MPH_TO_MS), + ], + # steerRatio: 11.82 is spec end-to-end + CarSpecs(mass=3279 * CV.LB_TO_KG, wheelbase=2.83, steerRatio=16.33, centerToFrontRatio=0.39, tireStiffnessFactor=0.8467), + dbc_dict('honda_accord_2018_can_generated', None), + ) + HONDA_CIVIC_BOSCH = HondaBoschPlatformConfig( + [ + HondaCarDocs("Honda Civic 2019-21", "All", video_link="https://www.youtube.com/watch?v=4Iz1Mz5LGF8", + footnotes=[Footnote.CIVIC_DIESEL], min_steer_speed=2. * CV.MPH_TO_MS), + HondaCarDocs("Honda Civic Hatchback 2017-21", min_steer_speed=12. * CV.MPH_TO_MS), + ], + CarSpecs(mass=1326, wheelbase=2.7, steerRatio=15.38, centerToFrontRatio=0.4), # steerRatio: 10.93 is end-to-end spec + dbc_dict('honda_civic_hatchback_ex_2017_can_generated', None), + ) + HONDA_CIVIC_BOSCH_DIESEL = HondaBoschPlatformConfig( + [], # don't show in docs + HONDA_CIVIC_BOSCH.specs, + dbc_dict('honda_accord_2018_can_generated', None), + ) + HONDA_CIVIC_2022 = HondaBoschPlatformConfig( + [ + HondaCarDocs("Honda Civic 2022-23", "All", video_link="https://youtu.be/ytiOT5lcp6Q"), + HondaCarDocs("Honda Civic Hatchback 2022-23", "All", video_link="https://youtu.be/ytiOT5lcp6Q"), + ], + HONDA_CIVIC_BOSCH.specs, + dbc_dict('honda_civic_ex_2022_can_generated', None), + flags=HondaFlags.BOSCH_RADARLESS, + ) + HONDA_CRV_5G = HondaBoschPlatformConfig( + [HondaCarDocs("Honda CR-V 2017-22", min_steer_speed=12. * CV.MPH_TO_MS)], + # steerRatio: 12.3 is spec end-to-end + CarSpecs(mass=3410 * CV.LB_TO_KG, wheelbase=2.66, steerRatio=16.0, centerToFrontRatio=0.41, tireStiffnessFactor=0.677), + dbc_dict('honda_crv_ex_2017_can_generated', None, body_dbc='honda_crv_ex_2017_body_generated'), + flags=HondaFlags.BOSCH_ALT_BRAKE, + ) + HONDA_CRV_HYBRID = HondaBoschPlatformConfig( + [HondaCarDocs("Honda CR-V Hybrid 2017-21", min_steer_speed=12. * CV.MPH_TO_MS)], + # mass: mean of 4 models in kg, steerRatio: 12.3 is spec end-to-end + CarSpecs(mass=1667, wheelbase=2.66, steerRatio=16, centerToFrontRatio=0.41, tireStiffnessFactor=0.677), + dbc_dict('honda_accord_2018_can_generated', None), + ) + HONDA_HRV_3G = HondaBoschPlatformConfig( + [HondaCarDocs("Honda HR-V 2023", "All")], + CarSpecs(mass=3125 * CV.LB_TO_KG, wheelbase=2.61, steerRatio=15.2, centerToFrontRatio=0.41, tireStiffnessFactor=0.5), + dbc_dict('honda_civic_ex_2022_can_generated', None), + flags=HondaFlags.BOSCH_RADARLESS, + ) + ACURA_RDX_3G = HondaBoschPlatformConfig( + [HondaCarDocs("Acura RDX 2019-22", "All", min_steer_speed=3. * CV.MPH_TO_MS)], + CarSpecs(mass=4068 * CV.LB_TO_KG, wheelbase=2.75, steerRatio=11.95, centerToFrontRatio=0.41, tireStiffnessFactor=0.677), # as spec + dbc_dict('acura_rdx_2020_can_generated', None), + flags=HondaFlags.BOSCH_ALT_BRAKE, + ) + HONDA_INSIGHT = HondaBoschPlatformConfig( + [HondaCarDocs("Honda Insight 2019-22", "All", min_steer_speed=3. * CV.MPH_TO_MS)], + CarSpecs(mass=2987 * CV.LB_TO_KG, wheelbase=2.7, steerRatio=15.0, centerToFrontRatio=0.39, tireStiffnessFactor=0.82), # as spec + dbc_dict('honda_insight_ex_2019_can_generated', None), + ) + HONDA_E = HondaBoschPlatformConfig( + [HondaCarDocs("Honda e 2020", "All", min_steer_speed=3. * CV.MPH_TO_MS)], + CarSpecs(mass=3338.8 * CV.LB_TO_KG, wheelbase=2.5, centerToFrontRatio=0.5, steerRatio=16.71, tireStiffnessFactor=0.82), + dbc_dict('acura_rdx_2020_can_generated', None), + ) + + # Nidec Cars + ACURA_ILX = HondaNidecPlatformConfig( + [HondaCarDocs("Acura ILX 2016-19", "AcuraWatch Plus", min_steer_speed=25. * CV.MPH_TO_MS)], + CarSpecs(mass=3095 * CV.LB_TO_KG, wheelbase=2.67, steerRatio=18.61, centerToFrontRatio=0.37, tireStiffnessFactor=0.72), # 15.3 is spec end-to-end + dbc_dict('acura_ilx_2016_can_generated', 'acura_ilx_2016_nidec'), + flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, + ) + HONDA_CRV = HondaNidecPlatformConfig( + [HondaCarDocs("Honda CR-V 2015-16", "Touring Trim", min_steer_speed=12. * CV.MPH_TO_MS)], + CarSpecs(mass=3572 * CV.LB_TO_KG, wheelbase=2.62, steerRatio=16.89, centerToFrontRatio=0.41, tireStiffnessFactor=0.444), # as spec + dbc_dict('honda_crv_touring_2016_can_generated', 'acura_ilx_2016_nidec'), + flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, + ) + HONDA_CRV_EU = HondaNidecPlatformConfig( + [], # Euro version of CRV Touring, don't show in docs + HONDA_CRV.specs, + dbc_dict('honda_crv_executive_2016_can_generated', 'acura_ilx_2016_nidec'), + flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, + ) + HONDA_FIT = HondaNidecPlatformConfig( + [HondaCarDocs("Honda Fit 2018-20", min_steer_speed=12. * CV.MPH_TO_MS)], + CarSpecs(mass=2644 * CV.LB_TO_KG, wheelbase=2.53, steerRatio=13.06, centerToFrontRatio=0.39, tireStiffnessFactor=0.75), + dbc_dict('honda_fit_ex_2018_can_generated', 'acura_ilx_2016_nidec'), + flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, + ) + HONDA_FREED = HondaNidecPlatformConfig( + [HondaCarDocs("Honda Freed 2020", min_steer_speed=12. * CV.MPH_TO_MS)], + CarSpecs(mass=3086. * CV.LB_TO_KG, wheelbase=2.74, steerRatio=13.06, centerToFrontRatio=0.39, tireStiffnessFactor=0.75), # mostly copied from FIT + dbc_dict('honda_fit_ex_2018_can_generated', 'acura_ilx_2016_nidec'), + flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, + ) + HONDA_HRV = HondaNidecPlatformConfig( + [HondaCarDocs("Honda HR-V 2019-22", min_steer_speed=12. * CV.MPH_TO_MS)], + HONDA_HRV_3G.specs, + dbc_dict('honda_fit_ex_2018_can_generated', 'acura_ilx_2016_nidec'), + flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, + ) + HONDA_ODYSSEY = HondaNidecPlatformConfig( + [HondaCarDocs("Honda Odyssey 2018-20")], + CarSpecs(mass=1900, wheelbase=3.0, steerRatio=14.35, centerToFrontRatio=0.41, tireStiffnessFactor=0.82), + dbc_dict('honda_odyssey_exl_2018_generated', 'acura_ilx_2016_nidec'), + flags=HondaFlags.NIDEC_ALT_PCM_ACCEL, + ) + HONDA_ODYSSEY_CHN = HondaNidecPlatformConfig( + [], # Chinese version of Odyssey, don't show in docs + HONDA_ODYSSEY.specs, + dbc_dict('honda_odyssey_extreme_edition_2018_china_can_generated', 'acura_ilx_2016_nidec'), + flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, + ) + ACURA_RDX = HondaNidecPlatformConfig( + [HondaCarDocs("Acura RDX 2016-18", "AcuraWatch Plus", min_steer_speed=12. * CV.MPH_TO_MS)], + CarSpecs(mass=3925 * CV.LB_TO_KG, wheelbase=2.68, steerRatio=15.0, centerToFrontRatio=0.38, tireStiffnessFactor=0.444), # as spec + dbc_dict('acura_rdx_2018_can_generated', 'acura_ilx_2016_nidec'), + flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, + ) + HONDA_PILOT = HondaNidecPlatformConfig( + [ + HondaCarDocs("Honda Pilot 2016-22", min_steer_speed=12. * CV.MPH_TO_MS), + HondaCarDocs("Honda Passport 2019-23", "All", min_steer_speed=12. * CV.MPH_TO_MS), + ], + CarSpecs(mass=4278 * CV.LB_TO_KG, wheelbase=2.86, centerToFrontRatio=0.428, steerRatio=16.0, tireStiffnessFactor=0.444), # as spec + dbc_dict('acura_ilx_2016_can_generated', 'acura_ilx_2016_nidec'), + flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, + ) + HONDA_RIDGELINE = HondaNidecPlatformConfig( + [HondaCarDocs("Honda Ridgeline 2017-24", min_steer_speed=12. * CV.MPH_TO_MS)], + CarSpecs(mass=4515 * CV.LB_TO_KG, wheelbase=3.18, centerToFrontRatio=0.41, steerRatio=15.59, tireStiffnessFactor=0.444), # as spec + dbc_dict('acura_ilx_2016_can_generated', 'acura_ilx_2016_nidec'), + flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, + ) + HONDA_CIVIC = HondaNidecPlatformConfig( + [HondaCarDocs("Honda Civic 2016-18", min_steer_speed=12. * CV.MPH_TO_MS, video_link="https://youtu.be/-IkImTe1NYE")], + CarSpecs(mass=1326, wheelbase=2.70, centerToFrontRatio=0.4, steerRatio=15.38), # 10.93 is end-to-end spec + dbc_dict('honda_civic_touring_2016_can_generated', 'acura_ilx_2016_nidec'), + ) + + +HONDA_ALT_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ + p16(0xF112) +HONDA_ALT_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ + p16(0xF112) + +FW_QUERY_CONFIG = FwQueryConfig( + requests=[ + # Currently used to fingerprint + Request( + [StdQueries.UDS_VERSION_REQUEST], + [StdQueries.UDS_VERSION_RESPONSE], + bus=1, + ), + + # Data collection requests: + # Log manufacturer-specific identifier for current ECUs + Request( + [HONDA_ALT_VERSION_REQUEST], + [HONDA_ALT_VERSION_RESPONSE], + bus=1, + logging=True, + ), + # Nidec PT bus + Request( + [StdQueries.UDS_VERSION_REQUEST], + [StdQueries.UDS_VERSION_RESPONSE], + bus=0, + ), + # Bosch PT bus + Request( + [StdQueries.UDS_VERSION_REQUEST], + [StdQueries.UDS_VERSION_RESPONSE], + bus=1, + obd_multiplexing=False, + ), + ], + # We lose these ECUs without the comma power on these cars. + # Note that we still attempt to match with them when they are present + # This is or'd with (ALL_ECUS - ESSENTIAL_ECUS) from fw_versions.py + non_essential_ecus={ + Ecu.eps: [CAR.ACURA_RDX_3G, CAR.HONDA_ACCORD, CAR.HONDA_CIVIC_2022, CAR.HONDA_E, CAR.HONDA_HRV_3G], + Ecu.vsa: [CAR.ACURA_RDX_3G, CAR.HONDA_ACCORD, CAR.HONDA_CIVIC, CAR.HONDA_CIVIC_BOSCH, CAR.HONDA_CIVIC_2022, CAR.HONDA_CRV_5G, CAR.HONDA_CRV_HYBRID, + CAR.HONDA_E, CAR.HONDA_HRV_3G, CAR.HONDA_INSIGHT], + }, + extra_ecus=[ + (Ecu.combinationMeter, 0x18da60f1, None), + (Ecu.programmedFuelInjection, 0x18da10f1, None), + # The only other ECU on PT bus accessible by camera on radarless Civic + # This is likely a manufacturer-specific sub-address implementation: the camera responds to this and 0x18dab0f1 + # Unclear what the part number refers to: 8S103 is 'Camera Set Mono', while 36160 is 'Camera Monocular - Honda' + # TODO: add query back, camera does not support querying both in parallel and 0x18dab0f1 often fails to respond + # (Ecu.unknown, 0x18DAB3F1, None), + ], +) + +STEER_THRESHOLD = { + # default is 1200, overrides go here + CAR.ACURA_RDX: 400, + CAR.HONDA_CRV_EU: 400, +} + +HONDA_NIDEC_ALT_PCM_ACCEL = CAR.with_flags(HondaFlags.NIDEC_ALT_PCM_ACCEL) +HONDA_NIDEC_ALT_SCM_MESSAGES = CAR.with_flags(HondaFlags.NIDEC_ALT_SCM_MESSAGES) +HONDA_BOSCH = CAR.with_flags(HondaFlags.BOSCH) +HONDA_BOSCH_RADARLESS = CAR.with_flags(HondaFlags.BOSCH_RADARLESS) + + +DBC = CAR.create_dbc_map() diff --git a/car/hyundai/__init__.py b/car/hyundai/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/car/hyundai/carcontroller.py b/car/hyundai/carcontroller.py new file mode 100644 index 0000000000..4038ddcca9 --- /dev/null +++ b/car/hyundai/carcontroller.py @@ -0,0 +1,208 @@ +from cereal import car +from openpilot.common.conversions import Conversions as CV +from openpilot.common.numpy_fast import clip +from openpilot.common.realtime import DT_CTRL +from opendbc.can.packer import CANPacker +from openpilot.selfdrive.car import apply_driver_steer_torque_limits, common_fault_avoidance +from openpilot.selfdrive.car.hyundai import hyundaicanfd, hyundaican +from openpilot.selfdrive.car.hyundai.hyundaicanfd import CanBus +from openpilot.selfdrive.car.hyundai.values import HyundaiFlags, Buttons, CarControllerParams, CANFD_CAR, CAR +from openpilot.selfdrive.car.interfaces import CarControllerBase + +VisualAlert = car.CarControl.HUDControl.VisualAlert +LongCtrlState = car.CarControl.Actuators.LongControlState + +# EPS faults if you apply torque while the steering angle is above 90 degrees for more than 1 second +# All slightly below EPS thresholds to avoid fault +MAX_ANGLE = 85 +MAX_ANGLE_FRAMES = 89 +MAX_ANGLE_CONSECUTIVE_FRAMES = 2 + + +def process_hud_alert(enabled, fingerprint, hud_control): + sys_warning = (hud_control.visualAlert in (VisualAlert.steerRequired, VisualAlert.ldw)) + + # initialize to no line visible + # TODO: this is not accurate for all cars + sys_state = 1 + if hud_control.leftLaneVisible and hud_control.rightLaneVisible or sys_warning: # HUD alert only display when LKAS status is active + sys_state = 3 if enabled or sys_warning else 4 + elif hud_control.leftLaneVisible: + sys_state = 5 + elif hud_control.rightLaneVisible: + sys_state = 6 + + # initialize to no warnings + left_lane_warning = 0 + right_lane_warning = 0 + if hud_control.leftLaneDepart: + left_lane_warning = 1 if fingerprint in (CAR.GENESIS_G90, CAR.GENESIS_G80) else 2 + if hud_control.rightLaneDepart: + right_lane_warning = 1 if fingerprint in (CAR.GENESIS_G90, CAR.GENESIS_G80) else 2 + + return sys_warning, sys_state, left_lane_warning, right_lane_warning + + +class CarController(CarControllerBase): + def __init__(self, dbc_name, CP, VM): + self.CP = CP + self.CAN = CanBus(CP) + self.params = CarControllerParams(CP) + self.packer = CANPacker(dbc_name) + self.angle_limit_counter = 0 + self.frame = 0 + + self.accel_last = 0 + self.apply_steer_last = 0 + self.car_fingerprint = CP.carFingerprint + self.last_button_frame = 0 + + def update(self, CC, CS, now_nanos): + actuators = CC.actuators + hud_control = CC.hudControl + + # steering torque + new_steer = int(round(actuators.steer * self.params.STEER_MAX)) + apply_steer = apply_driver_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.params) + + # >90 degree steering fault prevention + self.angle_limit_counter, apply_steer_req = common_fault_avoidance(abs(CS.out.steeringAngleDeg) >= MAX_ANGLE, CC.latActive, + self.angle_limit_counter, MAX_ANGLE_FRAMES, + MAX_ANGLE_CONSECUTIVE_FRAMES) + + if not CC.latActive: + apply_steer = 0 + + # Hold torque with induced temporary fault when cutting the actuation bit + torque_fault = CC.latActive and not apply_steer_req + + self.apply_steer_last = apply_steer + + # accel + longitudinal + accel = clip(actuators.accel, CarControllerParams.ACCEL_MIN, CarControllerParams.ACCEL_MAX) + stopping = actuators.longControlState == LongCtrlState.stopping + set_speed_in_units = hud_control.setSpeed * (CV.MS_TO_KPH if CS.is_metric else CV.MS_TO_MPH) + + # HUD messages + sys_warning, sys_state, left_lane_warning, right_lane_warning = process_hud_alert(CC.enabled, self.car_fingerprint, + hud_control) + + can_sends = [] + + # *** common hyundai stuff *** + + # tester present - w/ no response (keeps relevant ECU disabled) + if self.frame % 100 == 0 and not (self.CP.flags & HyundaiFlags.CANFD_CAMERA_SCC.value) and self.CP.openpilotLongitudinalControl: + # for longitudinal control, either radar or ADAS driving ECU + addr, bus = 0x7d0, 0 + if self.CP.flags & HyundaiFlags.CANFD_HDA2.value: + addr, bus = 0x730, self.CAN.ECAN + can_sends.append([addr, 0, b"\x02\x3E\x80\x00\x00\x00\x00\x00", bus]) + + # for blinkers + if self.CP.flags & HyundaiFlags.ENABLE_BLINKERS: + can_sends.append([0x7b1, 0, b"\x02\x3E\x80\x00\x00\x00\x00\x00", self.CAN.ECAN]) + + # CAN-FD platforms + if self.CP.carFingerprint in CANFD_CAR: + hda2 = self.CP.flags & HyundaiFlags.CANFD_HDA2 + hda2_long = hda2 and self.CP.openpilotLongitudinalControl + + # steering control + can_sends.extend(hyundaicanfd.create_steering_messages(self.packer, self.CP, self.CAN, CC.enabled, apply_steer_req, apply_steer)) + + # prevent LFA from activating on HDA2 by sending "no lane lines detected" to ADAS ECU + if self.frame % 5 == 0 and hda2: + can_sends.append(hyundaicanfd.create_suppress_lfa(self.packer, self.CAN, CS.hda2_lfa_block_msg, + self.CP.flags & HyundaiFlags.CANFD_HDA2_ALT_STEERING)) + + # LFA and HDA icons + if self.frame % 5 == 0 and (not hda2 or hda2_long): + can_sends.append(hyundaicanfd.create_lfahda_cluster(self.packer, self.CAN, CC.enabled)) + + # blinkers + if hda2 and self.CP.flags & HyundaiFlags.ENABLE_BLINKERS: + can_sends.extend(hyundaicanfd.create_spas_messages(self.packer, self.CAN, self.frame, CC.leftBlinker, CC.rightBlinker)) + + if self.CP.openpilotLongitudinalControl: + if hda2: + can_sends.extend(hyundaicanfd.create_adrv_messages(self.packer, self.CAN, self.frame)) + if self.frame % 2 == 0: + can_sends.append(hyundaicanfd.create_acc_control(self.packer, self.CAN, CC.enabled, self.accel_last, accel, stopping, CC.cruiseControl.override, + set_speed_in_units, hud_control)) + self.accel_last = accel + else: + # button presses + can_sends.extend(self.create_button_messages(CC, CS, use_clu11=False)) + else: + can_sends.append(hyundaican.create_lkas11(self.packer, self.frame, self.CP, apply_steer, apply_steer_req, + torque_fault, CS.lkas11, sys_warning, sys_state, CC.enabled, + hud_control.leftLaneVisible, hud_control.rightLaneVisible, + left_lane_warning, right_lane_warning)) + + if not self.CP.openpilotLongitudinalControl: + can_sends.extend(self.create_button_messages(CC, CS, use_clu11=True)) + + if self.frame % 2 == 0 and self.CP.openpilotLongitudinalControl: + # TODO: unclear if this is needed + jerk = 3.0 if actuators.longControlState == LongCtrlState.pid else 1.0 + use_fca = self.CP.flags & HyundaiFlags.USE_FCA.value + can_sends.extend(hyundaican.create_acc_commands(self.packer, CC.enabled, accel, jerk, int(self.frame / 2), + hud_control, set_speed_in_units, stopping, + CC.cruiseControl.override, use_fca)) + + # 20 Hz LFA MFA message + if self.frame % 5 == 0 and self.CP.flags & HyundaiFlags.SEND_LFA.value: + can_sends.append(hyundaican.create_lfahda_mfc(self.packer, CC.enabled)) + + # 5 Hz ACC options + if self.frame % 20 == 0 and self.CP.openpilotLongitudinalControl: + can_sends.extend(hyundaican.create_acc_opt(self.packer)) + + # 2 Hz front radar options + if self.frame % 50 == 0 and self.CP.openpilotLongitudinalControl: + can_sends.append(hyundaican.create_frt_radar_opt(self.packer)) + + new_actuators = actuators.as_builder() + new_actuators.steer = apply_steer / self.params.STEER_MAX + new_actuators.steerOutputCan = apply_steer + new_actuators.accel = accel + + self.frame += 1 + return new_actuators, can_sends + + def create_button_messages(self, CC: car.CarControl, CS: car.CarState, use_clu11: bool): + can_sends = [] + if use_clu11: + if CC.cruiseControl.cancel: + can_sends.append(hyundaican.create_clu11(self.packer, self.frame, CS.clu11, Buttons.CANCEL, self.CP)) + elif CC.cruiseControl.resume: + # send resume at a max freq of 10Hz + if (self.frame - self.last_button_frame) * DT_CTRL > 0.1: + # send 25 messages at a time to increases the likelihood of resume being accepted + can_sends.extend([hyundaican.create_clu11(self.packer, self.frame, CS.clu11, Buttons.RES_ACCEL, self.CP)] * 25) + if (self.frame - self.last_button_frame) * DT_CTRL >= 0.15: + self.last_button_frame = self.frame + else: + if (self.frame - self.last_button_frame) * DT_CTRL > 0.25: + # cruise cancel + if CC.cruiseControl.cancel: + if self.CP.flags & HyundaiFlags.CANFD_ALT_BUTTONS: + can_sends.append(hyundaicanfd.create_acc_cancel(self.packer, self.CP, self.CAN, CS.cruise_info)) + self.last_button_frame = self.frame + else: + for _ in range(20): + can_sends.append(hyundaicanfd.create_buttons(self.packer, self.CP, self.CAN, CS.buttons_counter+1, Buttons.CANCEL)) + self.last_button_frame = self.frame + + # cruise standstill resume + elif CC.cruiseControl.resume: + if self.CP.flags & HyundaiFlags.CANFD_ALT_BUTTONS: + # TODO: resume for alt button cars + pass + else: + for _ in range(20): + can_sends.append(hyundaicanfd.create_buttons(self.packer, self.CP, self.CAN, CS.buttons_counter+1, Buttons.RES_ACCEL)) + self.last_button_frame = self.frame + + return can_sends diff --git a/car/hyundai/carstate.py b/car/hyundai/carstate.py new file mode 100644 index 0000000000..92c489cf34 --- /dev/null +++ b/car/hyundai/carstate.py @@ -0,0 +1,368 @@ +from collections import deque +import copy +import math + +from cereal import car +from openpilot.common.conversions import Conversions as CV +from opendbc.can.parser import CANParser +from opendbc.can.can_define import CANDefine +from openpilot.selfdrive.car.hyundai.hyundaicanfd import CanBus +from openpilot.selfdrive.car.hyundai.values import HyundaiFlags, CAR, DBC, CAN_GEARS, CAMERA_SCC_CAR, \ + CANFD_CAR, Buttons, CarControllerParams +from openpilot.selfdrive.car.interfaces import CarStateBase + +PREV_BUTTON_SAMPLES = 8 +CLUSTER_SAMPLE_RATE = 20 # frames +STANDSTILL_THRESHOLD = 12 * 0.03125 * CV.KPH_TO_MS + + +class CarState(CarStateBase): + def __init__(self, CP): + super().__init__(CP) + can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) + + self.cruise_buttons = deque([Buttons.NONE] * PREV_BUTTON_SAMPLES, maxlen=PREV_BUTTON_SAMPLES) + self.main_buttons = deque([Buttons.NONE] * PREV_BUTTON_SAMPLES, maxlen=PREV_BUTTON_SAMPLES) + + self.gear_msg_canfd = "GEAR_ALT" if CP.flags & HyundaiFlags.CANFD_ALT_GEARS else \ + "GEAR_ALT_2" if CP.flags & HyundaiFlags.CANFD_ALT_GEARS_2 else \ + "GEAR_SHIFTER" + if CP.carFingerprint in CANFD_CAR: + self.shifter_values = can_define.dv[self.gear_msg_canfd]["GEAR"] + elif self.CP.carFingerprint in CAN_GEARS["use_cluster_gears"]: + self.shifter_values = can_define.dv["CLU15"]["CF_Clu_Gear"] + elif self.CP.carFingerprint in CAN_GEARS["use_tcu_gears"]: + self.shifter_values = can_define.dv["TCU12"]["CUR_GR"] + else: # preferred and elect gear methods use same definition + self.shifter_values = can_define.dv["LVR12"]["CF_Lvr_Gear"] + + self.accelerator_msg_canfd = "ACCELERATOR" if CP.flags & HyundaiFlags.EV else \ + "ACCELERATOR_ALT" if CP.flags & HyundaiFlags.HYBRID else \ + "ACCELERATOR_BRAKE_ALT" + self.cruise_btns_msg_canfd = "CRUISE_BUTTONS_ALT" if CP.flags & HyundaiFlags.CANFD_ALT_BUTTONS else \ + "CRUISE_BUTTONS" + self.is_metric = False + self.buttons_counter = 0 + + self.cruise_info = {} + + # On some cars, CLU15->CF_Clu_VehicleSpeed can oscillate faster than the dash updates. Sample at 5 Hz + self.cluster_speed = 0 + self.cluster_speed_counter = CLUSTER_SAMPLE_RATE + + self.params = CarControllerParams(CP) + + def update(self, cp, cp_cam): + if self.CP.carFingerprint in CANFD_CAR: + return self.update_canfd(cp, cp_cam) + + ret = car.CarState.new_message() + cp_cruise = cp_cam if self.CP.carFingerprint in CAMERA_SCC_CAR else cp + self.is_metric = cp.vl["CLU11"]["CF_Clu_SPEED_UNIT"] == 0 + speed_conv = CV.KPH_TO_MS if self.is_metric else CV.MPH_TO_MS + + ret.doorOpen = any([cp.vl["CGW1"]["CF_Gway_DrvDrSw"], cp.vl["CGW1"]["CF_Gway_AstDrSw"], + cp.vl["CGW2"]["CF_Gway_RLDrSw"], cp.vl["CGW2"]["CF_Gway_RRDrSw"]]) + + ret.seatbeltUnlatched = cp.vl["CGW1"]["CF_Gway_DrvSeatBeltSw"] == 0 + + ret.wheelSpeeds = self.get_wheel_speeds( + cp.vl["WHL_SPD11"]["WHL_SPD_FL"], + cp.vl["WHL_SPD11"]["WHL_SPD_FR"], + cp.vl["WHL_SPD11"]["WHL_SPD_RL"], + cp.vl["WHL_SPD11"]["WHL_SPD_RR"], + ) + ret.vEgoRaw = (ret.wheelSpeeds.fl + ret.wheelSpeeds.fr + ret.wheelSpeeds.rl + ret.wheelSpeeds.rr) / 4. + ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) + ret.standstill = ret.wheelSpeeds.fl <= STANDSTILL_THRESHOLD and ret.wheelSpeeds.rr <= STANDSTILL_THRESHOLD + + self.cluster_speed_counter += 1 + if self.cluster_speed_counter > CLUSTER_SAMPLE_RATE: + self.cluster_speed = cp.vl["CLU15"]["CF_Clu_VehicleSpeed"] + self.cluster_speed_counter = 0 + + # Mimic how dash converts to imperial. + # Sorento is the only platform where CF_Clu_VehicleSpeed is already imperial when not is_metric + # TODO: CGW_USM1->CF_Gway_DrLockSoundRValue may describe this + if not self.is_metric and self.CP.carFingerprint not in (CAR.KIA_SORENTO,): + self.cluster_speed = math.floor(self.cluster_speed * CV.KPH_TO_MPH + CV.KPH_TO_MPH) + + ret.vEgoCluster = self.cluster_speed * speed_conv + + ret.steeringAngleDeg = cp.vl["SAS11"]["SAS_Angle"] + ret.steeringRateDeg = cp.vl["SAS11"]["SAS_Speed"] + ret.yawRate = cp.vl["ESP12"]["YAW_RATE"] + ret.leftBlinker, ret.rightBlinker = self.update_blinker_from_lamp( + 50, cp.vl["CGW1"]["CF_Gway_TurnSigLh"], cp.vl["CGW1"]["CF_Gway_TurnSigRh"]) + ret.steeringTorque = cp.vl["MDPS12"]["CR_Mdps_StrColTq"] + ret.steeringTorqueEps = cp.vl["MDPS12"]["CR_Mdps_OutTq"] + ret.steeringPressed = self.update_steering_pressed(abs(ret.steeringTorque) > self.params.STEER_THRESHOLD, 5) + ret.steerFaultTemporary = cp.vl["MDPS12"]["CF_Mdps_ToiUnavail"] != 0 or cp.vl["MDPS12"]["CF_Mdps_ToiFlt"] != 0 + + # cruise state + if self.CP.openpilotLongitudinalControl: + # These are not used for engage/disengage since openpilot keeps track of state using the buttons + ret.cruiseState.available = cp.vl["TCS13"]["ACCEnable"] == 0 + ret.cruiseState.enabled = cp.vl["TCS13"]["ACC_REQ"] == 1 + ret.cruiseState.standstill = False + ret.cruiseState.nonAdaptive = False + else: + ret.cruiseState.available = cp_cruise.vl["SCC11"]["MainMode_ACC"] == 1 + ret.cruiseState.enabled = cp_cruise.vl["SCC12"]["ACCMode"] != 0 + ret.cruiseState.standstill = cp_cruise.vl["SCC11"]["SCCInfoDisplay"] == 4. + ret.cruiseState.nonAdaptive = cp_cruise.vl["SCC11"]["SCCInfoDisplay"] == 2. # Shows 'Cruise Control' on dash + ret.cruiseState.speed = cp_cruise.vl["SCC11"]["VSetDis"] * speed_conv + + # TODO: Find brake pressure + ret.brake = 0 + ret.brakePressed = cp.vl["TCS13"]["DriverOverride"] == 2 # 2 includes regen braking by user on HEV/EV + ret.brakeHoldActive = cp.vl["TCS15"]["AVH_LAMP"] == 2 # 0 OFF, 1 ERROR, 2 ACTIVE, 3 READY + ret.parkingBrake = cp.vl["TCS13"]["PBRAKE_ACT"] == 1 + ret.espDisabled = cp.vl["TCS11"]["TCS_PAS"] == 1 + ret.accFaulted = cp.vl["TCS13"]["ACCEnable"] != 0 # 0 ACC CONTROL ENABLED, 1-3 ACC CONTROL DISABLED + + if self.CP.flags & (HyundaiFlags.HYBRID | HyundaiFlags.EV): + if self.CP.flags & HyundaiFlags.HYBRID: + ret.gas = cp.vl["E_EMS11"]["CR_Vcu_AccPedDep_Pos"] / 254. + else: + ret.gas = cp.vl["E_EMS11"]["Accel_Pedal_Pos"] / 254. + ret.gasPressed = ret.gas > 0 + else: + ret.gas = cp.vl["EMS12"]["PV_AV_CAN"] / 100. + ret.gasPressed = bool(cp.vl["EMS16"]["CF_Ems_AclAct"]) + + # Gear Selection via Cluster - For those Kia/Hyundai which are not fully discovered, we can use the Cluster Indicator for Gear Selection, + # as this seems to be standard over all cars, but is not the preferred method. + if self.CP.flags & (HyundaiFlags.HYBRID | HyundaiFlags.EV): + gear = cp.vl["ELECT_GEAR"]["Elect_Gear_Shifter"] + elif self.CP.carFingerprint in CAN_GEARS["use_cluster_gears"]: + gear = cp.vl["CLU15"]["CF_Clu_Gear"] + elif self.CP.carFingerprint in CAN_GEARS["use_tcu_gears"]: + gear = cp.vl["TCU12"]["CUR_GR"] + else: + gear = cp.vl["LVR12"]["CF_Lvr_Gear"] + + ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(gear)) + + if not self.CP.openpilotLongitudinalControl: + aeb_src = "FCA11" if self.CP.flags & HyundaiFlags.USE_FCA.value else "SCC12" + aeb_sig = "FCA_CmdAct" if self.CP.flags & HyundaiFlags.USE_FCA.value else "AEB_CmdAct" + aeb_warning = cp_cruise.vl[aeb_src]["CF_VSM_Warn"] != 0 + scc_warning = cp_cruise.vl["SCC12"]["TakeOverReq"] == 1 # sometimes only SCC system shows an FCW + aeb_braking = cp_cruise.vl[aeb_src]["CF_VSM_DecCmdAct"] != 0 or cp_cruise.vl[aeb_src][aeb_sig] != 0 + ret.stockFcw = (aeb_warning or scc_warning) and not aeb_braking + ret.stockAeb = aeb_warning and aeb_braking + + if self.CP.enableBsm: + ret.leftBlindspot = cp.vl["LCA11"]["CF_Lca_IndLeft"] != 0 + ret.rightBlindspot = cp.vl["LCA11"]["CF_Lca_IndRight"] != 0 + + # save the entire LKAS11 and CLU11 + self.lkas11 = copy.copy(cp_cam.vl["LKAS11"]) + self.clu11 = copy.copy(cp.vl["CLU11"]) + self.steer_state = cp.vl["MDPS12"]["CF_Mdps_ToiActive"] # 0 NOT ACTIVE, 1 ACTIVE + self.prev_cruise_buttons = self.cruise_buttons[-1] + self.cruise_buttons.extend(cp.vl_all["CLU11"]["CF_Clu_CruiseSwState"]) + self.main_buttons.extend(cp.vl_all["CLU11"]["CF_Clu_CruiseSwMain"]) + + return ret + + def update_canfd(self, cp, cp_cam): + ret = car.CarState.new_message() + + self.is_metric = cp.vl["CRUISE_BUTTONS_ALT"]["DISTANCE_UNIT"] != 1 + speed_factor = CV.KPH_TO_MS if self.is_metric else CV.MPH_TO_MS + + if self.CP.flags & (HyundaiFlags.EV | HyundaiFlags.HYBRID): + offset = 255. if self.CP.flags & HyundaiFlags.EV else 1023. + ret.gas = cp.vl[self.accelerator_msg_canfd]["ACCELERATOR_PEDAL"] / offset + ret.gasPressed = ret.gas > 1e-5 + else: + ret.gasPressed = bool(cp.vl[self.accelerator_msg_canfd]["ACCELERATOR_PEDAL_PRESSED"]) + + ret.brakePressed = cp.vl["TCS"]["DriverBraking"] == 1 + + ret.doorOpen = cp.vl["DOORS_SEATBELTS"]["DRIVER_DOOR"] == 1 + ret.seatbeltUnlatched = cp.vl["DOORS_SEATBELTS"]["DRIVER_SEATBELT"] == 0 + + gear = cp.vl[self.gear_msg_canfd]["GEAR"] + ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(gear)) + + # TODO: figure out positions + ret.wheelSpeeds = self.get_wheel_speeds( + cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_1"], + cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_2"], + cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_3"], + cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_4"], + ) + ret.vEgoRaw = (ret.wheelSpeeds.fl + ret.wheelSpeeds.fr + ret.wheelSpeeds.rl + ret.wheelSpeeds.rr) / 4. + ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) + ret.standstill = ret.wheelSpeeds.fl <= STANDSTILL_THRESHOLD and ret.wheelSpeeds.rr <= STANDSTILL_THRESHOLD + + ret.steeringRateDeg = cp.vl["STEERING_SENSORS"]["STEERING_RATE"] + ret.steeringAngleDeg = cp.vl["STEERING_SENSORS"]["STEERING_ANGLE"] * -1 + ret.steeringTorque = cp.vl["MDPS"]["STEERING_COL_TORQUE"] + ret.steeringTorqueEps = cp.vl["MDPS"]["STEERING_OUT_TORQUE"] + ret.steeringPressed = self.update_steering_pressed(abs(ret.steeringTorque) > self.params.STEER_THRESHOLD, 5) + ret.steerFaultTemporary = cp.vl["MDPS"]["LKA_FAULT"] != 0 + + # TODO: alt signal usage may be described by cp.vl['BLINKERS']['USE_ALT_LAMP'] + left_blinker_sig, right_blinker_sig = "LEFT_LAMP", "RIGHT_LAMP" + if self.CP.carFingerprint == CAR.HYUNDAI_KONA_EV_2ND_GEN: + left_blinker_sig, right_blinker_sig = "LEFT_LAMP_ALT", "RIGHT_LAMP_ALT" + ret.leftBlinker, ret.rightBlinker = self.update_blinker_from_lamp(50, cp.vl["BLINKERS"][left_blinker_sig], + cp.vl["BLINKERS"][right_blinker_sig]) + if self.CP.enableBsm: + ret.leftBlindspot = cp.vl["BLINDSPOTS_REAR_CORNERS"]["FL_INDICATOR"] != 0 + ret.rightBlindspot = cp.vl["BLINDSPOTS_REAR_CORNERS"]["FR_INDICATOR"] != 0 + + # cruise state + # CAN FD cars enable on main button press, set available if no TCS faults preventing engagement + ret.cruiseState.available = cp.vl["TCS"]["ACCEnable"] == 0 + if self.CP.openpilotLongitudinalControl: + # These are not used for engage/disengage since openpilot keeps track of state using the buttons + ret.cruiseState.enabled = cp.vl["TCS"]["ACC_REQ"] == 1 + ret.cruiseState.standstill = False + else: + cp_cruise_info = cp_cam if self.CP.flags & HyundaiFlags.CANFD_CAMERA_SCC else cp + ret.cruiseState.enabled = cp_cruise_info.vl["SCC_CONTROL"]["ACCMode"] in (1, 2) + ret.cruiseState.standstill = cp_cruise_info.vl["SCC_CONTROL"]["CRUISE_STANDSTILL"] == 1 + ret.cruiseState.speed = cp_cruise_info.vl["SCC_CONTROL"]["VSetDis"] * speed_factor + self.cruise_info = copy.copy(cp_cruise_info.vl["SCC_CONTROL"]) + + # Manual Speed Limit Assist is a feature that replaces non-adaptive cruise control on EV CAN FD platforms. + # It limits the vehicle speed, overridable by pressing the accelerator past a certain point. + # The car will brake, but does not respect positive acceleration commands in this mode + # TODO: find this message on ICE & HYBRID cars + cruise control signals (if exists) + if self.CP.flags & HyundaiFlags.EV: + ret.cruiseState.nonAdaptive = cp.vl["MANUAL_SPEED_LIMIT_ASSIST"]["MSLA_ENABLED"] == 1 + + self.prev_cruise_buttons = self.cruise_buttons[-1] + self.cruise_buttons.extend(cp.vl_all[self.cruise_btns_msg_canfd]["CRUISE_BUTTONS"]) + self.main_buttons.extend(cp.vl_all[self.cruise_btns_msg_canfd]["ADAPTIVE_CRUISE_MAIN_BTN"]) + self.buttons_counter = cp.vl[self.cruise_btns_msg_canfd]["COUNTER"] + ret.accFaulted = cp.vl["TCS"]["ACCEnable"] != 0 # 0 ACC CONTROL ENABLED, 1-3 ACC CONTROL DISABLED + + if self.CP.flags & HyundaiFlags.CANFD_HDA2: + self.hda2_lfa_block_msg = copy.copy(cp_cam.vl["CAM_0x362"] if self.CP.flags & HyundaiFlags.CANFD_HDA2_ALT_STEERING + else cp_cam.vl["CAM_0x2a4"]) + + return ret + + def get_can_parser(self, CP): + if CP.carFingerprint in CANFD_CAR: + return self.get_can_parser_canfd(CP) + + messages = [ + # address, frequency + ("MDPS12", 50), + ("TCS11", 100), + ("TCS13", 50), + ("TCS15", 10), + ("CLU11", 50), + ("CLU15", 5), + ("ESP12", 100), + ("CGW1", 10), + ("CGW2", 5), + ("CGW4", 5), + ("WHL_SPD11", 50), + ("SAS11", 100), + ] + + if not CP.openpilotLongitudinalControl and CP.carFingerprint not in CAMERA_SCC_CAR: + messages += [ + ("SCC11", 50), + ("SCC12", 50), + ] + if CP.flags & HyundaiFlags.USE_FCA.value: + messages.append(("FCA11", 50)) + + if CP.enableBsm: + messages.append(("LCA11", 50)) + + if CP.flags & (HyundaiFlags.HYBRID | HyundaiFlags.EV): + messages.append(("E_EMS11", 50)) + else: + messages += [ + ("EMS12", 100), + ("EMS16", 100), + ] + + if CP.flags & (HyundaiFlags.HYBRID | HyundaiFlags.EV): + messages.append(("ELECT_GEAR", 20)) + elif CP.carFingerprint in CAN_GEARS["use_cluster_gears"]: + pass + elif CP.carFingerprint in CAN_GEARS["use_tcu_gears"]: + messages.append(("TCU12", 100)) + else: + messages.append(("LVR12", 100)) + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, 0) + + @staticmethod + def get_cam_can_parser(CP): + if CP.carFingerprint in CANFD_CAR: + return CarState.get_cam_can_parser_canfd(CP) + + messages = [ + ("LKAS11", 100) + ] + + if not CP.openpilotLongitudinalControl and CP.carFingerprint in CAMERA_SCC_CAR: + messages += [ + ("SCC11", 50), + ("SCC12", 50), + ] + + if CP.flags & HyundaiFlags.USE_FCA.value: + messages.append(("FCA11", 50)) + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, 2) + + def get_can_parser_canfd(self, CP): + messages = [ + (self.gear_msg_canfd, 100), + (self.accelerator_msg_canfd, 100), + ("WHEEL_SPEEDS", 100), + ("STEERING_SENSORS", 100), + ("MDPS", 100), + ("TCS", 50), + ("CRUISE_BUTTONS_ALT", 50), + ("BLINKERS", 4), + ("DOORS_SEATBELTS", 4), + ] + + if CP.flags & HyundaiFlags.EV: + messages += [ + ("MANUAL_SPEED_LIMIT_ASSIST", 10), + ] + + if not (CP.flags & HyundaiFlags.CANFD_ALT_BUTTONS): + messages += [ + ("CRUISE_BUTTONS", 50) + ] + + if CP.enableBsm: + messages += [ + ("BLINDSPOTS_REAR_CORNERS", 20), + ] + + if not (CP.flags & HyundaiFlags.CANFD_CAMERA_SCC.value) and not CP.openpilotLongitudinalControl: + messages += [ + ("SCC_CONTROL", 50), + ] + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus(CP).ECAN) + + @staticmethod + def get_cam_can_parser_canfd(CP): + messages = [] + if CP.flags & HyundaiFlags.CANFD_HDA2: + block_lfa_msg = "CAM_0x362" if CP.flags & HyundaiFlags.CANFD_HDA2_ALT_STEERING else "CAM_0x2a4" + messages += [(block_lfa_msg, 20)] + elif CP.flags & HyundaiFlags.CANFD_CAMERA_SCC: + messages += [ + ("SCC_CONTROL", 50), + ] + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus(CP).CAM) diff --git a/car/hyundai/fingerprints.py b/car/hyundai/fingerprints.py new file mode 100644 index 0000000000..d115283dd5 --- /dev/null +++ b/car/hyundai/fingerprints.py @@ -0,0 +1,1160 @@ +# ruff: noqa: E501 +from cereal import car +from openpilot.selfdrive.car.hyundai.values import CAR + +Ecu = car.CarParams.Ecu + +FINGERPRINTS = { + CAR.HYUNDAI_SANTA_FE: [{ + 67: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 8, 593: 8, 608: 8, 688: 6, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1155: 8, 1156: 8, 1162: 8, 1164: 8, 1168: 7, 1170: 8, 1173: 8, 1183: 8, 1186: 2, 1191: 2, 1227: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1379: 8, 1384: 8, 1407: 8, 1414: 3, 1419: 8, 1427: 6, 1456: 4, 1470: 8 + }, + { + 67: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 8, 593: 8, 608: 8, 688: 6, 764: 8, 809: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1064: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1155: 8, 1162: 8, 1164: 8, 1168: 7, 1170: 8, 1173: 8, 1180: 8, 1183: 8, 1186: 2, 1227: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1371: 8, 1378: 8, 1384: 8, 1407: 8, 1414: 3, 1419: 8, 1427: 6, 1456: 4, 1470: 8, 1988: 8, 2000: 8, 2004: 8, 2008: 8, 2012: 8 + }, + { + 67: 8, 68: 8, 80: 4, 160: 8, 161: 8, 272: 8, 288: 4, 339: 8, 356: 8, 357: 8, 399: 8, 544: 8, 608: 8, 672: 8, 688: 5, 704: 1, 790: 8, 809: 8, 848: 8, 880: 8, 898: 8, 900: 8, 901: 8, 904: 8, 1056: 8, 1064: 8, 1065: 8, 1072: 8, 1075: 8, 1087: 8, 1088: 8, 1151: 8, 1200: 8, 1201: 8, 1232: 4, 1264: 8, 1265: 8, 1266: 8, 1296: 8, 1306: 8, 1312: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1348: 8, 1349: 8, 1369: 8, 1370: 8, 1371: 8, 1407: 8, 1415: 8, 1419: 8, 1440: 8, 1442: 4, 1461: 8, 1470: 8 + }], + CAR.HYUNDAI_SONATA: [{ + 67: 8, 68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 8, 546: 8, 549: 8, 550: 8, 576: 8, 593: 8, 608: 8, 688: 6, 809: 8, 832: 8, 854: 8, 865: 8, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 905: 8, 908: 8, 909: 8, 912: 7, 913: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1089: 5, 1096: 8, 1107: 5, 1108: 8, 1114: 8, 1136: 8, 1145: 8, 1151: 8, 1155: 8, 1156: 8, 1157: 4, 1162: 8, 1164: 8, 1168: 8, 1170: 8, 1173: 8, 1180: 8, 1183: 8, 1184: 8, 1186: 2, 1191: 2, 1193: 8, 1210: 8, 1225: 8, 1227: 8, 1265: 4, 1268: 8, 1280: 8, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1330: 8, 1339: 8, 1342: 6, 1343: 8, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1371: 8, 1378: 8, 1379: 8, 1384: 8, 1394: 8, 1407: 8, 1419: 8, 1427: 6, 1446: 8, 1456: 4, 1460: 8, 1470: 8, 1485: 8, 1504: 3, 1988: 8, 1996: 8, 2000: 8, 2004: 8, 2008: 8, 2012: 8, 2015: 8 + }], + CAR.KIA_STINGER: [{ + 67: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 358: 6, 359: 8, 544: 8, 576: 8, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1064: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1168: 7, 1170: 8, 1173: 8, 1184: 8, 1265: 4, 1280: 1, 1281: 4, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1371: 8, 1378: 4, 1379: 8, 1384: 8, 1407: 8, 1419: 8, 1425: 2, 1427: 6, 1456: 4, 1470: 8 + }], + CAR.GENESIS_G90: [{ + 67: 8, 68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 358: 6, 359: 8, 544: 8, 593: 8, 608: 8, 688: 5, 809: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1162: 4, 1168: 7, 1170: 8, 1173: 8, 1184: 8, 1265: 4, 1280: 1, 1281: 3, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1370: 8, 1371: 8, 1378: 4, 1384: 8, 1407: 8, 1419: 8, 1425: 2, 1427: 6, 1434: 2, 1456: 4, 1470: 8, 1988: 8, 2000: 8, 2003: 8, 2004: 8, 2005: 8, 2008: 8, 2011: 8, 2012: 8, 2013: 8 + }], + CAR.HYUNDAI_KONA_EV: [{ + 127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 544: 8, 549: 8, 593: 8, 688: 5, 832: 8, 881: 8, 882: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1136: 8, 1151: 6, 1168: 7, 1173: 8, 1183: 8, 1186: 2, 1191: 2, 1225: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1294: 8, 1307: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1378: 4, 1407: 8, 1419: 8, 1426: 8, 1427: 6, 1429: 8, 1430: 8, 1456: 4, 1470: 8, 1473: 8, 1507: 8, 1535: 8, 2000: 8, 2004: 8, 2008: 8, 2012: 8, 1157: 4, 1193: 8, 1379: 8, 1988: 8, 1996: 8 + }], + CAR.HYUNDAI_KONA_EV_2022: [{ + 127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 544: 8, 593: 8, 688: 5, 832: 8, 881: 8, 882: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 913: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1069: 8, 1078: 4, 1136: 8, 1145: 8, 1151: 8, 1155: 8, 1156: 8, 1157: 4, 1162: 8, 1164: 8, 1168: 8, 1173: 8, 1183: 8, 1188: 8, 1191: 2, 1193: 8, 1225: 8, 1227: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1339: 8, 1342: 8, 1343: 8, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1379: 8, 1407: 8, 1419: 8, 1426: 8, 1427: 6, 1429: 8, 1430: 8, 1446: 8, 1456: 4, 1470: 8, 1473: 8, 1485: 8, 1507: 8, 1535: 8, 1990: 8, 1998: 8 + }], + CAR.KIA_NIRO_EV: [{ + 127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 516: 8, 544: 8, 593: 8, 688: 5, 832: 8, 881: 8, 882: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1136: 8, 1151: 6, 1156: 8, 1157: 4, 1168: 7, 1173: 8, 1183: 8, 1186: 2, 1191: 2, 1193: 8, 1225: 8, 1260: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1407: 8, 1419: 8, 1426: 8, 1427: 6, 1429: 8, 1430: 8, 1456: 4, 1470: 8, 1473: 8, 1507: 8, 1535: 8, 1990: 8, 1998: 8, 1996: 8, 2000: 8, 2004: 8, 2008: 8, 2012: 8, 2015: 8 + }], + CAR.KIA_OPTIMA_H: [{ + 68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 544: 8, 593: 8, 688: 5, 832: 8, 881: 8, 882: 8, 897: 8, 902: 8, 903: 6, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1136: 6, 1151: 6, 1168: 7, 1173: 8, 1236: 2, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1342: 6, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1371: 8, 1407: 8, 1419: 8, 1427: 6, 1429: 8, 1430: 8, 1448: 8, 1456: 4, 1470: 8, 1476: 8, 1535: 8 + }, + { + 68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 544: 8, 576: 8, 593: 8, 688: 5, 881: 8, 882: 8, 897: 8, 902: 8, 903: 8, 909: 8, 912: 7, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1136: 6, 1151: 6, 1168: 7, 1173: 8, 1180: 8, 1186: 2, 1191: 2, 1265: 4, 1268: 8, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1371: 8, 1407: 8, 1419: 8, 1420: 8, 1425: 2, 1427: 6, 1429: 8, 1430: 8, 1448: 8, 1456: 4, 1470: 8, 1476: 8, 1535: 8 + }], +} + +FW_VERSIONS = { + CAR.HYUNDAI_AZERA_6TH_GEN: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00IG__ SCC F-CU- 1.00 1.00 99110-G8100 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00IG MDPS C 1.00 1.02 56310G8510\x00 4IGSC103', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00IG MFC AT MES LHD 1.00 1.04 99211-G8100 200511', + ], + }, + CAR.HYUNDAI_AZERA_HEV_6TH_GEN: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00IGH MFC AT KOR LHD 1.00 1.00 99211-G8000 180903', + b'\xf1\x00IGH MFC AT KOR LHD 1.00 1.01 99211-G8000 181109', + b'\xf1\x00IGH MFC AT KOR LHD 1.00 1.02 99211-G8100 191029', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00IG MDPS C 1.00 1.00 56310M9600\x00 4IHSC100', + b'\xf1\x00IG MDPS C 1.00 1.01 56310M9350\x00 4IH8C101', + b'\xf1\x00IG MDPS C 1.00 1.02 56310M9350\x00 4IH8C102', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00IGhe SCC FHCUP 1.00 1.00 99110-M9100 ', + b'\xf1\x00IGhe SCC FHCUP 1.00 1.01 99110-M9000 ', + b'\xf1\x00IGhe SCC FHCUP 1.00 1.02 99110-M9000 ', + ], + }, + CAR.HYUNDAI_GENESIS: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00DH LKAS 1.1 -150210', + b'\xf1\x00DH LKAS 1.4 -140110', + b'\xf1\x00DH LKAS 1.5 -140425', + ], + }, + CAR.HYUNDAI_IONIQ: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00AEhe SCC H-CUP 1.01 1.01 96400-G2000 ', + b'\xf1\x00AEhe SCC H-CUP 1.01 1.01 96400-G2100 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00AE MDPS C 1.00 1.05 56310/G2501 4AEHC105', + b'\xf1\x00AE MDPS C 1.00 1.07 56310/G2301 4AEHC107', + b'\xf1\x00AE MDPS C 1.00 1.07 56310/G2501 4AEHC107', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00AEH MFC AT EUR LHD 1.00 1.00 95740-G2400 180222', + b'\xf1\x00AEH MFC AT USA LHD 1.00 1.00 95740-G2400 180222', + ], + }, + CAR.HYUNDAI_IONIQ_PHEV_2019: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00AEhe SCC H-CUP 1.01 1.01 96400-G2000 ', + b'\xf1\x00AEhe SCC H-CUP 1.01 1.01 96400-G2100 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00AE MDPS C 1.00 1.07 56310/G2501 4AEHC107', + b'\xf1\x00AE MDPS C 1.00 1.07 56310/G2551 4AEHC107', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00AEP MFC AT AUS RHD 1.00 1.00 95740-G2400 180222', + b'\xf1\x00AEP MFC AT USA LHD 1.00 1.00 95740-G2400 180222', + ], + }, + CAR.HYUNDAI_IONIQ_PHEV: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00AEhe SCC F-CUP 1.00 1.00 99110-G2200 ', + b'\xf1\x00AEhe SCC F-CUP 1.00 1.00 99110-G2600 ', + b'\xf1\x00AEhe SCC F-CUP 1.00 1.02 99110-G2100 ', + b'\xf1\x00AEhe SCC FHCUP 1.00 1.00 99110-G2600 ', + b'\xf1\x00AEhe SCC FHCUP 1.00 1.02 99110-G2100 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00AE MDPS C 1.00 1.01 56310/G2210 4APHC101', + b'\xf1\x00AE MDPS C 1.00 1.01 56310/G2310 4APHC101', + b'\xf1\x00AE MDPS C 1.00 1.01 56310/G2510 4APHC101', + b'\xf1\x00AE MDPS C 1.00 1.01 56310/G2560 4APHC101', + b'\xf1\x00AE MDPS C 1.00 1.01 56310G2510\x00 4APHC101', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00AEP MFC AT EUR LHD 1.00 1.01 95740-G2600 190819', + b'\xf1\x00AEP MFC AT EUR RHD 1.00 1.01 95740-G2600 190819', + b'\xf1\x00AEP MFC AT USA LHD 1.00 1.00 95740-G2700 201027', + b'\xf1\x00AEP MFC AT USA LHD 1.00 1.01 95740-G2600 190819', + ], + }, + CAR.HYUNDAI_IONIQ_EV_2020: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00AEev SCC F-CUP 1.00 1.00 99110-G7200 ', + b'\xf1\x00AEev SCC F-CUP 1.00 1.00 99110-G7500 ', + b'\xf1\x00AEev SCC F-CUP 1.00 1.01 99110-G7000 ', + b'\xf1\x00AEev SCC F-CUP 1.00 1.01 99110-G7100 ', + b'\xf1\x00AEev SCC FHCUP 1.00 1.01 99110-G7100 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00AE MDPS C 1.00 1.01 56310/G7310 4APEC101', + b'\xf1\x00AE MDPS C 1.00 1.01 56310/G7510 4APEC101', + b'\xf1\x00AE MDPS C 1.00 1.01 56310/G7560 4APEC101', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.00 95740-G2600 190730', + b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.00 95740-G2700 201027', + b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.01 95740-G2600 190819', + b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.03 95740-G2500 190516', + b'\xf1\x00AEE MFC AT EUR RHD 1.00 1.01 95740-G2600 190819', + b'\xf1\x00AEE MFC AT USA LHD 1.00 1.01 95740-G2600 190819', + ], + }, + CAR.HYUNDAI_IONIQ_EV_LTD: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00AEev SCC F-CUP 1.00 1.00 96400-G7000 ', + b'\xf1\x00AEev SCC F-CUP 1.00 1.00 96400-G7100 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00AE MDPS C 1.00 1.02 56310G7300\x00 4AEEC102', + b'\xf1\x00AE MDPS C 1.00 1.03 56310/G7300 4AEEC103', + b'\xf1\x00AE MDPS C 1.00 1.03 56310G7300\x00 4AEEC103', + b'\xf1\x00AE MDPS C 1.00 1.04 56310/G7301 4AEEC104', + b'\xf1\x00AE MDPS C 1.00 1.04 56310/G7501 4AEEC104', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.00 95740-G2300 170703', + b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.00 95740-G2400 180222', + b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.00 95740-G7200 160418', + b'\xf1\x00AEE MFC AT USA LHD 1.00 1.00 95740-G2400 180222', + ], + }, + CAR.HYUNDAI_IONIQ_HEV_2022: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00AEhe SCC F-CUP 1.00 1.00 99110-G2600 ', + b'\xf1\x00AEhe SCC FHCUP 1.00 1.00 99110-G2600 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00AE MDPS C 1.00 1.01 56310G2510\x00 4APHC101', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00AEH MFC AT USA LHD 1.00 1.00 95740-G2700 201027', + ], + }, + CAR.HYUNDAI_SONATA: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00DN8_ SCC F-CU- 1.00 1.00 99110-L0000 ', + b'\xf1\x00DN8_ SCC F-CUP 1.00 1.00 99110-L0000 ', + b'\xf1\x00DN8_ SCC F-CUP 1.00 1.02 99110-L1000 ', + b'\xf1\x00DN8_ SCC FHCUP 1.00 1.00 99110-L0000 ', + b'\xf1\x00DN8_ SCC FHCUP 1.00 1.01 99110-L1000 ', + b'\xf1\x00DN8_ SCC FHCUP 1.00 1.02 99110-L1000 ', + ], + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00DN ESC \x01 102\x19\x04\x13 58910-L1300', + b'\xf1\x00DN ESC \x03 100 \x08\x01 58910-L0300', + b'\xf1\x00DN ESC \x06 104\x19\x08\x01 58910-L0100', + b'\xf1\x00DN ESC \x06 106 \x07\x01 58910-L0100', + b'\xf1\x00DN ESC \x06 107 \x07\x03 58910-L1300', + b'\xf1\x00DN ESC \x06 107"\x08\x07 58910-L0100', + b'\xf1\x00DN ESC \x07 104\x19\x08\x01 58910-L0100', + b'\xf1\x00DN ESC \x07 106 \x07\x01 58910-L0100', + b'\xf1\x00DN ESC \x07 107"\x08\x07 58910-L0100', + b'\xf1\x00DN ESC \x08 103\x19\x06\x01 58910-L1300', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00DN8 MDPS C 1,00 1,01 56310L0010\x00 4DNAC101', + b'\xf1\x00DN8 MDPS C 1.00 1.01 56310-L0010 4DNAC101', + b'\xf1\x00DN8 MDPS C 1.00 1.01 56310-L0210 4DNAC101', + b'\xf1\x00DN8 MDPS C 1.00 1.01 56310-L0210 4DNAC102', + b'\xf1\x00DN8 MDPS C 1.00 1.01 56310L0010\x00 4DNAC101', + b'\xf1\x00DN8 MDPS C 1.00 1.01 56310L0200\x00 4DNAC102', + b'\xf1\x00DN8 MDPS C 1.00 1.01 56310L0210\x00 4DNAC101', + b'\xf1\x00DN8 MDPS C 1.00 1.01 56310L0210\x00 4DNAC102', + b'\xf1\x00DN8 MDPS C 1.00 1.03 56310-L1010 4DNDC103', + b'\xf1\x00DN8 MDPS C 1.00 1.03 56310-L1030 4DNDC103', + b'\xf1\x00DN8 MDPS R 1.00 1.00 57700-L0000 4DNAP100', + b'\xf1\x00DN8 MDPS R 1.00 1.00 57700-L0000 4DNAP101', + b'\xf1\x00DN8 MDPS R 1.00 1.02 57700-L1000 4DNDP105', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00DN8 MFC AT KOR LHD 1.00 1.02 99211-L1000 190422', + b'\xf1\x00DN8 MFC AT KOR LHD 1.00 1.04 99211-L1000 191016', + b'\xf1\x00DN8 MFC AT RUS LHD 1.00 1.03 99211-L1000 190705', + b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.00 99211-L0000 190716', + b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.01 99211-L0000 191016', + b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.03 99211-L0000 210603', + b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.05 99211-L1000 201109', + b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.06 99211-L1000 210325', + b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.07 99211-L1000 211223', + ], + }, + CAR.HYUNDAI_SONATA_LF: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00LF__ SCC F-CUP 1.00 1.00 96401-C2200 ', + ], + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00LF ESC \t 11 \x17\x01\x13 58920-C2610', + b'\xf1\x00LF ESC \x0c 11 \x17\x01\x13 58920-C2610', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00LFF LKAS AT USA LHD 1.00 1.01 95740-C1000 E51', + b'\xf1\x00LFF LKAS AT USA LHD 1.01 1.02 95740-C1000 E52', + ], + }, + CAR.HYUNDAI_TUCSON: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00TL__ FCA F-CUP 1.00 1.01 99110-D3500 ', + b'\xf1\x00TL__ FCA F-CUP 1.00 1.02 99110-D3510 ', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00TL MFC AT KOR LHD 1.00 1.02 95895-D3800 180719', + b'\xf1\x00TL MFC AT USA LHD 1.00 1.06 95895-D3800 190107', + ], + }, + CAR.HYUNDAI_SANTA_FE: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00TM__ SCC F-CUP 1.00 1.00 99110-S1210 ', + b'\xf1\x00TM__ SCC F-CUP 1.00 1.01 99110-S2000 ', + b'\xf1\x00TM__ SCC F-CUP 1.00 1.02 99110-S2000 ', + b'\xf1\x00TM__ SCC F-CUP 1.00 1.03 99110-S2000 ', + ], + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00TM ESC \x02 100\x18\x030 58910-S2600', + b'\xf1\x00TM ESC \x02 102\x18\x07\x01 58910-S2600', + b'\xf1\x00TM ESC \x02 103\x18\x11\x07 58910-S2600', + b'\xf1\x00TM ESC \x02 104\x19\x07\x07 58910-S2600', + b'\xf1\x00TM ESC \x03 103\x18\x11\x07 58910-S2600', + b'\xf1\x00TM ESC \x0c 103\x18\x11\x08 58910-S2650', + b'\xf1\x00TM ESC \r 100\x18\x031 58910-S2650', + b'\xf1\x00TM ESC \r 103\x18\x11\x08 58910-S2650', + b'\xf1\x00TM ESC \r 104\x19\x07\x08 58910-S2650', + b'\xf1\x00TM ESC \r 105\x19\x05# 58910-S1500', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00TM MDPS C 1.00 1.00 56340-S2000 8409', + b'\xf1\x00TM MDPS C 1.00 1.00 56340-S2000 8A12', + b'\xf1\x00TM MDPS C 1.00 1.01 56340-S2000 9129', + b'\xf1\x00TM MDPS R 1.00 1.02 57700-S1100 4TMDP102', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00TM MFC AT EUR LHD 1.00 1.01 99211-S1010 181207', + b'\xf1\x00TM MFC AT USA LHD 1.00 1.00 99211-S2000 180409', + ], + }, + CAR.HYUNDAI_SANTA_FE_2022: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00TM__ SCC F-CUP 1.00 1.00 99110-S1500 ', + b'\xf1\x00TM__ SCC F-CUP 1.00 1.01 99110-S1500 ', + b'\xf1\x00TM__ SCC FHCUP 1.00 1.00 99110-S1500 ', + b'\xf1\x00TM__ SCC FHCUP 1.00 1.01 99110-S1500 ', + ], + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00TM ESC \x01 102!\x04\x03 58910-S2DA0', + b'\xf1\x00TM ESC \x01 104"\x10\x07 58910-S2DA0', + b'\xf1\x00TM ESC \x02 101 \x08\x04 58910-S2GA0', + b'\xf1\x00TM ESC \x02 103"\x07\x08 58910-S2GA0', + b'\xf1\x00TM ESC \x03 101 \x08\x02 58910-S2DA0', + b'\xf1\x00TM ESC \x03 102!\x04\x03 58910-S2DA0', + b'\xf1\x00TM ESC \x04 101 \x08\x04 58910-S2GA0', + b'\xf1\x00TM ESC \x04 102!\x04\x05 58910-S2GA0', + b'\xf1\x00TM ESC \x04 103"\x07\x08 58910-S2GA0', + b'\xf1\x00TM ESC \x1e 102 \x08\x08 58910-S1DA0', + b'\xf1\x00TM ESC 103!\x030 58910-S1MA0', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00TM MDPS C 1.00 1.01 56310-S1AB0 4TSDC101', + b'\xf1\x00TM MDPS C 1.00 1.01 56310-S1EB0 4TSDC101', + b'\xf1\x00TM MDPS C 1.00 1.02 56370-S2AA0 0B19', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00TM MFC AT EUR LHD 1.00 1.03 99211-S1500 210224', + b'\xf1\x00TM MFC AT MES LHD 1.00 1.05 99211-S1500 220126', + b'\xf1\x00TMA MFC AT MEX LHD 1.00 1.01 99211-S2500 210205', + b'\xf1\x00TMA MFC AT USA LHD 1.00 1.00 99211-S2500 200720', + b'\xf1\x00TMA MFC AT USA LHD 1.00 1.01 99211-S2500 210205', + b'\xf1\x00TMA MFC AT USA LHD 1.00 1.03 99211-S2500 220414', + ], + }, + CAR.HYUNDAI_SANTA_FE_HEV_2022: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00TMhe SCC FHCUP 1.00 1.00 99110-CL500 ', + b'\xf1\x00TMhe SCC FHCUP 1.00 1.01 99110-CL500 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00TM MDPS C 1.00 1.02 56310-CLAC0 4TSHC102', + b'\xf1\x00TM MDPS C 1.00 1.02 56310-CLEC0 4TSHC102', + b'\xf1\x00TM MDPS C 1.00 1.02 56310-GA000 4TSHA100', + b'\xf1\x00TM MDPS R 1.00 1.05 57700-CL000 4TSHP105', + b'\xf1\x00TM MDPS R 1.00 1.06 57700-CL000 4TSHP106', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00TMA MFC AT USA LHD 1.00 1.03 99211-S2500 220414', + b'\xf1\x00TMH MFC AT EUR LHD 1.00 1.06 99211-S1500 220727', + b'\xf1\x00TMH MFC AT KOR LHD 1.00 1.06 99211-S1500 220727', + b'\xf1\x00TMH MFC AT USA LHD 1.00 1.03 99211-S1500 210224', + b'\xf1\x00TMH MFC AT USA LHD 1.00 1.05 99211-S1500 220126', + b'\xf1\x00TMH MFC AT USA LHD 1.00 1.06 99211-S1500 220727', + ], + }, + CAR.HYUNDAI_SANTA_FE_PHEV_2022: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00TMhe SCC F-CUP 1.00 1.00 99110-CL500 ', + b'\xf1\x00TMhe SCC FHCUP 1.00 1.00 99110-CL500 ', + b'\xf1\x00TMhe SCC FHCUP 1.00 1.01 99110-CL500 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00TM MDPS C 1.00 1.02 56310-CLAC0 4TSHC102', + b'\xf1\x00TM MDPS C 1.00 1.02 56310-CLEC0 4TSHC102', + b'\xf1\x00TM MDPS C 1.00 1.02 56310CLEC0\x00 4TSHC102', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00TMP MFC AT USA LHD 1.00 1.03 99211-S1500 210224', + b'\xf1\x00TMP MFC AT USA LHD 1.00 1.05 99211-S1500 220126', + b'\xf1\x00TMP MFC AT USA LHD 1.00 1.06 99211-S1500 220727', + ], + }, + CAR.HYUNDAI_CUSTIN_1ST_GEN: { + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00KU ESC \x01 101!\x02\x03 58910-O3200', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00KU__ SCC F-CUP 1.00 1.01 99110-O3000 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00KU MDPS C 1.00 1.01 56310/O3100 4KUCC101', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00KU2 MFC AT CHN LHD 1.00 1.02 99211-O3000 220923', + ], + }, + CAR.KIA_STINGER: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00CK__ SCC F_CUP 1.00 1.01 96400-J5000 ', + b'\xf1\x00CK__ SCC F_CUP 1.00 1.01 96400-J5100 ', + b'\xf1\x00CK__ SCC F_CUP 1.00 1.02 96400-J5100 ', + b'\xf1\x00CK__ SCC F_CUP 1.00 1.03 96400-J5100 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00CK MDPS R 1.00 1.04 57700-J5200 4C2CL104', + b'\xf1\x00CK MDPS R 1.00 1.04 57700-J5220 4C2VL104', + b'\xf1\x00CK MDPS R 1.00 1.04 57700-J5420 4C4VL104', + b'\xf1\x00CK MDPS R 1.00 1.06 57700-J5220 4C2VL106', + b'\xf1\x00CK MDPS R 1.00 1.06 57700-J5420 4C4VL106', + b'\xf1\x00CK MDPS R 1.00 1.07 57700-J5220 4C2VL107', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00CK MFC AT EUR LHD 1.00 1.03 95740-J5000 170822', + b'\xf1\x00CK MFC AT USA LHD 1.00 1.03 95740-J5000 170822', + b'\xf1\x00CK MFC AT USA LHD 1.00 1.04 95740-J5000 180504', + ], + }, + CAR.KIA_STINGER_2022: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00CK__ SCC F-CUP 1.00 1.00 99110-J5500 ', + b'\xf1\x00CK__ SCC FHCUP 1.00 1.00 99110-J5500 ', + b'\xf1\x00CK__ SCC FHCUP 1.00 1.00 99110-J5600 ', + b'\xf1\x00CK__ SCC FHCUP 1.00 1.01 99110-J5100 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00CK MDPS R 1.00 5.03 57700-J5300 4C2CL503', + b'\xf1\x00CK MDPS R 1.00 5.03 57700-J5320 4C2VL503', + b'\xf1\x00CK MDPS R 1.00 5.03 57700-J5380 4C2VR503', + b'\xf1\x00CK MDPS R 1.00 5.03 57700-J5520 4C4VL503', + b'\xf1\x00CK MDPS R 1.00 5.04 57700-J5520 4C4VL504', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00CK MFC AT AUS RHD 1.00 1.00 99211-J5500 210622', + b'\xf1\x00CK MFC AT KOR LHD 1.00 1.00 99211-J5500 210622', + b'\xf1\x00CK MFC AT USA LHD 1.00 1.00 99211-J5500 210622', + b'\xf1\x00CK MFC AT USA LHD 1.00 1.03 99211-J5000 201209', + ], + }, + CAR.HYUNDAI_PALISADE: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00LX2 SCC FHCUP 1.00 1.04 99110-S8100 ', + b'\xf1\x00LX2_ SCC F-CUP 1.00 1.04 99110-S8100 ', + b'\xf1\x00LX2_ SCC F-CUP 1.00 1.05 99110-S8100 ', + b'\xf1\x00LX2_ SCC FHCU- 1.00 1.05 99110-S8100 ', + b'\xf1\x00LX2_ SCC FHCUP 1.00 1.00 99110-S8110 ', + b'\xf1\x00LX2_ SCC FHCUP 1.00 1.03 99110-S8100 ', + b'\xf1\x00LX2_ SCC FHCUP 1.00 1.04 99110-S8100 ', + b'\xf1\x00LX2_ SCC FHCUP 1.00 1.05 99110-S8100 ', + b'\xf1\x00ON__ FCA FHCUP 1.00 1.00 99110-S9110 ', + b'\xf1\x00ON__ FCA FHCUP 1.00 1.01 99110-S9110 ', + b'\xf1\x00ON__ FCA FHCUP 1.00 1.02 99110-S9100 ', + b'\xf1\x00ON__ FCA FHCUP 1.00 1.03 99110-S9100 ', + ], + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00LX ESC \x01 103\x19\t\x10 58910-S8360', + b'\xf1\x00LX ESC \x01 1031\t\x10 58910-S8360', + b'\xf1\x00LX ESC \x01 104 \x10\x15 58910-S8350', + b'\xf1\x00LX ESC \x01 104 \x10\x16 58910-S8360', + b'\xf1\x00LX ESC \x0b 101\x19\x03\x17 58910-S8330', + b'\xf1\x00LX ESC \x0b 101\x19\x03 58910-S8360', + b'\xf1\x00LX ESC \x0b 102\x19\x05\x07 58910-S8330', + b'\xf1\x00LX ESC \x0b 103\x19\t\x07 58910-S8330', + b'\xf1\x00LX ESC \x0b 103\x19\t\t 58910-S8350', + b'\xf1\x00LX ESC \x0b 103\x19\t\x10 58910-S8360', + b'\xf1\x00LX ESC \x0b 104 \x10\x16 58910-S8360', + b'\xf1\x00ON ESC \x01 101\x19\t\x08 58910-S9360', + b'\xf1\x00ON ESC \x0b 100\x18\x12\x18 58910-S9360', + b'\xf1\x00ON ESC \x0b 101\x19\t\x05 58910-S9320', + b'\xf1\x00ON ESC \x0b 101\x19\t\x08 58910-S9360', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00LX2 MDPS C 1,00 1,03 56310-S8020 4LXDC103', + b'\xf1\x00LX2 MDPS C 1.00 1.03 56310-S8000 4LXDC103', + b'\xf1\x00LX2 MDPS C 1.00 1.03 56310-S8020 4LXDC103', + b'\xf1\x00LX2 MDPS C 1.00 1.03 56310-XX000 4LXDC103', + b'\xf1\x00LX2 MDPS C 1.00 1.04 56310-S8020 4LXDC104', + b'\xf1\x00LX2 MDPS C 1.00 1.04 56310-S8420 4LXDC104', + b'\xf1\x00LX2 MDPS R 1.00 1.02 56370-S8300 9318', + b'\xf1\x00ON MDPS C 1.00 1.00 56340-S9000 8B13', + b'\xf1\x00ON MDPS C 1.00 1.01 56340-S9000 9201', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00LX2 MFC AT KOR LHD 1.00 1.08 99211-S8100 200903', + b'\xf1\x00LX2 MFC AT USA LHD 1.00 1.00 99211-S8110 210226', + b'\xf1\x00LX2 MFC AT USA LHD 1.00 1.03 99211-S8100 190125', + b'\xf1\x00LX2 MFC AT USA LHD 1.00 1.05 99211-S8100 190909', + b'\xf1\x00LX2 MFC AT USA LHD 1.00 1.07 99211-S8100 200422', + b'\xf1\x00LX2 MFC AT USA LHD 1.00 1.08 99211-S8100 200903', + b'\xf1\x00ON MFC AT USA LHD 1.00 1.01 99211-S9100 181105', + b'\xf1\x00ON MFC AT USA LHD 1.00 1.03 99211-S9100 200720', + b'\xf1\x00ON MFC AT USA LHD 1.00 1.04 99211-S9100 211227', + ], + }, + CAR.HYUNDAI_VELOSTER: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00JS__ SCC H-CUP 1.00 1.02 95650-J3200 ', + b'\xf1\x00JS__ SCC HNCUP 1.00 1.02 95650-J3100 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00JSL MDPS C 1.00 1.03 56340-J3000 8308', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00JS LKAS AT KOR LHD 1.00 1.03 95740-J3000 K33', + b'\xf1\x00JS LKAS AT USA LHD 1.00 1.02 95740-J3000 K32', + ], + }, + CAR.GENESIS_G70: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00IK__ SCC F-CUP 1.00 1.01 96400-G9100 ', + b'\xf1\x00IK__ SCC F-CUP 1.00 1.02 96400-G9100 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00IK MDPS R 1.00 1.06 57700-G9420 4I4VL106', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00IK MFC AT USA LHD 1.00 1.01 95740-G9000 170920', + ], + }, + CAR.GENESIS_G70_2020: { + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00IK MDPS R 1.00 1.06 57700-G9220 4I2VL106', + b'\xf1\x00IK MDPS R 1.00 1.07 57700-G9220 4I2VL107', + b'\xf1\x00IK MDPS R 1.00 1.07 57700-G9420 4I4VL107', + b'\xf1\x00IK MDPS R 1.00 1.08 57700-G9200 4I2CL108', + b'\xf1\x00IK MDPS R 1.00 1.08 57700-G9420 4I4VL108', + b'\xf1\x00IK MDPS R 1.00 5.09 57700-G9520 4I4VL509', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00IK__ SCC F-CUP 1.00 1.01 96400-G9100 ', + b'\xf1\x00IK__ SCC F-CUP 1.00 1.02 96400-G9100 ', + b'\xf1\x00IK__ SCC F-CUP 1.00 1.02 96400-G9100 \xf1\xa01.02', + b'\xf1\x00IK__ SCC FHCUP 1.00 1.00 99110-G9300 ', + b'\xf1\x00IK__ SCC FHCUP 1.00 1.02 96400-G9000 ', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00IK MFC AT KOR LHD 1.00 1.01 95740-G9000 170920', + b'\xf1\x00IK MFC AT USA LHD 1.00 1.01 95740-G9000 170920', + b'\xf1\x00IK MFC AT USA LHD 1.00 1.04 99211-G9000 220401', + ], + }, + CAR.GENESIS_G80: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00DH__ SCC F-CUP 1.00 1.01 96400-B1120 ', + b'\xf1\x00DH__ SCC F-CUP 1.00 1.02 96400-B1120 ', + b'\xf1\x00DH__ SCC FHCUP 1.00 1.01 96400-B1110 ', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00DH LKAS AT KOR LHD 1.01 1.01 95895-B1500 161014', + b'\xf1\x00DH LKAS AT KOR LHD 1.01 1.02 95895-B1500 170810', + b'\xf1\x00DH LKAS AT USA LHD 1.01 1.01 95895-B1500 161014', + b'\xf1\x00DH LKAS AT USA LHD 1.01 1.02 95895-B1500 170810', + b'\xf1\x00DH LKAS AT USA LHD 1.01 1.03 95895-B1500 180713', + b'\xf1\x00DH LKAS AT USA LHD 1.01 1.04 95895-B1500 181213', + ], + }, + CAR.GENESIS_G90: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00HI__ SCC F-CUP 1.00 1.01 96400-D2100 ', + b'\xf1\x00HI__ SCC FHCUP 1.00 1.02 99110-D2100 ', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00HI LKAS AT USA LHD 1.00 1.00 95895-D2020 160302', + b'\xf1\x00HI LKAS AT USA LHD 1.00 1.00 95895-D2030 170208', + b'\xf1\x00HI MFC AT USA LHD 1.00 1.03 99211-D2000 190831', + ], + }, + CAR.HYUNDAI_KONA: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00OS__ SCC F-CUP 1.00 1.00 95655-J9200 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00OS MDPS C 1.00 1.05 56310J9030\x00 4OSDC105', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00OS9 LKAS AT USA LHD 1.00 1.00 95740-J9300 g21', + ], + }, + CAR.KIA_CEED: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00CD__ SCC F-CUP 1.00 1.02 99110-J7000 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00CD MDPS C 1.00 1.06 56310-XX000 4CDEC106', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00CD LKAS AT EUR LHD 1.00 1.01 99211-J7000 B40', + ], + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00CD ESC \x03 102\x18\x08\x05 58920-J7350', + ], + }, + CAR.KIA_FORTE: { + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00BD MDPS C 1.00 1.02 56310-XX000 4BD2C102', + b'\xf1\x00BD MDPS C 1.00 1.08 56310/M6300 4BDDC108', + b'\xf1\x00BD MDPS C 1.00 1.08 56310M6300\x00 4BDDC108', + b'\xf1\x00BDm MDPS C A.01 1.01 56310M7800\x00 4BPMC101', + b'\xf1\x00BDm MDPS C A.01 1.03 56310M7800\x00 4BPMC103', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00BD LKAS AT USA LHD 1.00 1.04 95740-M6000 J33', + b'\xf1\x00BDP LKAS AT USA LHD 1.00 1.05 99211-M6500 744', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00BDPE_SCC FHCUPC 1.00 1.04 99110-M6500\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'\xf1\x00BD__ SCC H-CUP 1.00 1.02 99110-M6000 ', + ], + }, + CAR.KIA_K5_2021: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00DL3_ SCC F-CUP 1.00 1.03 99110-L2100 ', + b'\xf1\x00DL3_ SCC FHCUP 1.00 1.03 99110-L2000 ', + b'\xf1\x00DL3_ SCC FHCUP 1.00 1.03 99110-L2100 ', + b'\xf1\x00DL3_ SCC FHCUP 1.00 1.04 99110-L2100 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00DL3 MDPS C 1.00 1.01 56310-L3110 4DLAC101', + b'\xf1\x00DL3 MDPS C 1.00 1.01 56310-L3220 4DLAC101', + b'\xf1\x00DL3 MDPS C 1.00 1.02 56310-L2220 4DLDC102', + b'\xf1\x00DL3 MDPS C 1.00 1.02 56310L3220\x00 4DLAC102', + b'\xf1\x00DL3 MDPS R 1.00 1.02 57700-L3000 4DLAP102', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00DL3 MFC AT KOR LHD 1.00 1.04 99210-L2000 210527', + b'\xf1\x00DL3 MFC AT USA LHD 1.00 1.03 99210-L3000 200915', + b'\xf1\x00DL3 MFC AT USA LHD 1.00 1.04 99210-L3000 210208', + b'\xf1\x00DL3 MFC AT USA LHD 1.00 1.05 99210-L3000 211222', + ], + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00DL ESC \x01 104 \x07\x12 58910-L2200', + b'\xf1\x00DL ESC \x03 100 \x08\x02 58910-L3600', + b'\xf1\x00DL ESC \x06 101 \x04\x02 58910-L3200', + b'\xf1\x00DL ESC \x06 103"\x08\x06 58910-L3200', + b'\xf1\x00DL ESC \t 100 \x06\x02 58910-L3800', + b'\xf1\x00DL ESC \t 101 \x07\x02 58910-L3800', + b'\xf1\x00DL ESC \t 102"\x08\x10 58910-L3800', + ], + }, + CAR.KIA_K5_HEV_2020: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00DLhe SCC FHCUP 1.00 1.02 99110-L7000 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00DL3 MDPS C 1.00 1.02 56310-L7000 4DLHC102', + b'\xf1\x00DL3 MDPS C 1.00 1.02 56310-L7220 4DLHC102', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00DL3HMFC AT KOR LHD 1.00 1.02 99210-L2000 200309', + b'\xf1\x00DL3HMFC AT KOR LHD 1.00 1.04 99210-L2000 210527', + ], + }, + CAR.HYUNDAI_KONA_EV: { + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00OS IEB \x01 212 \x11\x13 58520-K4000', + b'\xf1\x00OS IEB \x02 210 \x02\x14 58520-K4000', + b'\xf1\x00OS IEB \x02 212 \x11\x13 58520-K4000', + b'\xf1\x00OS IEB \x03 210 \x02\x14 58520-K4000', + b'\xf1\x00OS IEB \x03 212 \x11\x13 58520-K4000', + b'\xf1\x00OS IEB \r 105\x18\t\x18 58520-K4000', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00OE2 LKAS AT EUR LHD 1.00 1.00 95740-K4200 200', + b'\xf1\x00OSE LKAS AT EUR LHD 1.00 1.00 95740-K4100 W40', + b'\xf1\x00OSE LKAS AT EUR RHD 1.00 1.00 95740-K4100 W40', + b'\xf1\x00OSE LKAS AT KOR LHD 1.00 1.00 95740-K4100 W40', + b'\xf1\x00OSE LKAS AT USA LHD 1.00 1.00 95740-K4100 W40', + b'\xf1\x00OSE LKAS AT USA LHD 1.00 1.00 95740-K4300 W50', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00OS MDPS C 1.00 1.03 56310/K4550 4OEDC103', + b'\xf1\x00OS MDPS C 1.00 1.04 56310-XX000 4OEDC104', + b'\xf1\x00OS MDPS C 1.00 1.04 56310K4000\x00 4OEDC104', + b'\xf1\x00OS MDPS C 1.00 1.04 56310K4050\x00 4OEDC104', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00OSev SCC F-CUP 1.00 1.00 99110-K4000 ', + b'\xf1\x00OSev SCC F-CUP 1.00 1.00 99110-K4100 ', + b'\xf1\x00OSev SCC F-CUP 1.00 1.01 99110-K4000 ', + b'\xf1\x00OSev SCC FNCUP 1.00 1.01 99110-K4000 ', + ], + }, + CAR.HYUNDAI_KONA_EV_2022: { + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00OS IEB \x02 102"\x05\x16 58520-K4010', + b'\xf1\x00OS IEB \x03 101 \x11\x13 58520-K4010', + b'\xf1\x00OS IEB \x03 102"\x05\x16 58520-K4010', + b'\xf1\x00OS IEB \r 102"\x05\x16 58520-K4010', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00OSP LKA AT AUS RHD 1.00 1.04 99211-J9200 904', + b'\xf1\x00OSP LKA AT CND LHD 1.00 1.02 99211-J9110 802', + b'\xf1\x00OSP LKA AT EUR LHD 1.00 1.04 99211-J9200 904', + b'\xf1\x00OSP LKA AT EUR RHD 1.00 1.02 99211-J9110 802', + b'\xf1\x00OSP LKA AT EUR RHD 1.00 1.04 99211-J9200 904', + b'\xf1\x00OSP LKA AT USA LHD 1.00 1.04 99211-J9200 904', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00OSP MDPS C 1.00 1.02 56310-K4271 4OEPC102', + b'\xf1\x00OSP MDPS C 1.00 1.02 56310/K4271 4OEPC102', + b'\xf1\x00OSP MDPS C 1.00 1.02 56310/K4970 4OEPC102', + b'\xf1\x00OSP MDPS C 1.00 1.02 56310K4260\x00 4OEPC102', + b'\xf1\x00OSP MDPS C 1.00 1.02 56310K4261\x00 4OEPC102', + b'\xf1\x00OSP MDPS C 1.00 1.02 56310K4971\x00 4OEPC102', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00YB__ FCA ----- 1.00 1.01 99110-K4500 \x00\x00\x00', + ], + }, + CAR.HYUNDAI_KONA_EV_2ND_GEN: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00SXev RDR ----- 1.00 1.00 99110-BF000 ', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00SX2EMFC AT KOR LHD 1.00 1.00 99211-BF000 230410', + ], + }, + CAR.KIA_NIRO_EV: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00DEev SCC F-CUP 1.00 1.00 99110-Q4000 ', + b'\xf1\x00DEev SCC F-CUP 1.00 1.00 99110-Q4100 ', + b'\xf1\x00DEev SCC F-CUP 1.00 1.00 99110-Q4500 ', + b'\xf1\x00DEev SCC F-CUP 1.00 1.00 99110-Q4600 ', + b'\xf1\x00DEev SCC F-CUP 1.00 1.02 96400-Q4000 ', + b'\xf1\x00DEev SCC F-CUP 1.00 1.02 96400-Q4100 ', + b'\xf1\x00DEev SCC F-CUP 1.00 1.03 96400-Q4100 ', + b'\xf1\x00DEev SCC FHCUP 1.00 1.00 99110-Q4600 ', + b'\xf1\x00DEev SCC FHCUP 1.00 1.03 96400-Q4000 ', + b'\xf1\x00DEev SCC FNCUP 1.00 1.00 99110-Q4600 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00DE MDPS C 1.00 1.04 56310Q4100\x00 4DEEC104', + b'\xf1\x00DE MDPS C 1.00 1.05 56310Q4000\x00 4DEEC105', + b'\xf1\x00DE MDPS C 1.00 1.05 56310Q4100\x00 4DEEC105', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00DEE MFC AT EUR LHD 1.00 1.00 99211-Q4000 191211', + b'\xf1\x00DEE MFC AT EUR LHD 1.00 1.00 99211-Q4100 200706', + b'\xf1\x00DEE MFC AT EUR LHD 1.00 1.03 95740-Q4000 180821', + b'\xf1\x00DEE MFC AT KOR LHD 1.00 1.03 95740-Q4000 180821', + b'\xf1\x00DEE MFC AT USA LHD 1.00 1.00 99211-Q4000 191211', + b'\xf1\x00DEE MFC AT USA LHD 1.00 1.01 99211-Q4500 210428', + b'\xf1\x00DEE MFC AT USA LHD 1.00 1.03 95740-Q4000 180821', + ], + }, + CAR.KIA_NIRO_EV_2ND_GEN: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00SG2_ RDR ----- 1.00 1.01 99110-AT000 ', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00SG2EMFC AT EUR LHD 1.01 1.09 99211-AT000 220801', + b'\xf1\x00SG2EMFC AT USA LHD 1.01 1.09 99211-AT000 220801', + ], + }, + CAR.KIA_NIRO_PHEV: { + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00DE MDPS C 1.00 1.01 56310G5520\x00 4DEPC101', + b'\xf1\x00DE MDPS C 1.00 1.09 56310G5301\x00 4DEHC109', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00DEH MFC AT USA LHD 1.00 1.00 95740-G5010 170117', + b'\xf1\x00DEP MFC AT USA LHD 1.00 1.00 95740-G5010 170117', + b'\xf1\x00DEP MFC AT USA LHD 1.00 1.01 95740-G5010 170424', + b'\xf1\x00DEP MFC AT USA LHD 1.00 1.05 99211-G5000 190826', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00DEhe SCC F-CUP 1.00 1.02 99110-G5100 ', + b'\xf1\x00DEhe SCC H-CUP 1.01 1.02 96400-G5100 ', + ], + }, + CAR.KIA_NIRO_PHEV_2022: { + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00DE MDPS C 1.00 1.01 56310G5520\x00 4DEPC101', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00DEP MFC AT USA LHD 1.00 1.00 99211-G5500 210428', + b'\xf1\x00DEP MFC AT USA LHD 1.00 1.06 99211-G5000 201028', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00DEhe SCC F-CUP 1.00 1.00 99110-G5600 ', + b'\xf1\x00DEhe SCC FHCUP 1.00 1.00 99110-G5600 ', + ], + }, + CAR.KIA_NIRO_HEV_2021: { + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00DE MDPS C 1.00 1.01 56310G5520\x00 4DEPC101', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00DEH MFC AT KOR LHD 1.00 1.04 99211-G5000 190516', + b'\xf1\x00DEH MFC AT USA LHD 1.00 1.00 99211-G5500 210428', + b'\xf1\x00DEH MFC AT USA LHD 1.00 1.07 99211-G5000 201221', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00DEhe SCC FHCUP 1.00 1.00 99110-G5600 ', + b'\xf1\x00DEhe SCC FHCUP 1.00 1.01 99110-G5000 ', + ], + }, + CAR.KIA_SELTOS: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00SP2_ SCC FHCUP 1.01 1.05 99110-Q5100 ', + ], + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00SP ESC \x07 101\x19\t\x05 58910-Q5450', + b'\xf1\x00SP ESC \t 101\x19\t\x05 58910-Q5450', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00SP2 MDPS C 1.00 1.04 56300Q5200 ', + b'\xf1\x00SP2 MDPS C 1.01 1.05 56300Q5200 ', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00SP2 MFC AT USA LHD 1.00 1.04 99210-Q5000 191114', + b'\xf1\x00SP2 MFC AT USA LHD 1.00 1.05 99210-Q5000 201012', + ], + }, + CAR.KIA_OPTIMA_G4: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00JF__ SCC F-CUP 1.00 1.00 96400-D4100 ', + ], + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00JF ESC \x0f 16 \x16\x06\x17 58920-D5080', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00JFWGN LDWS AT USA LHD 1.00 1.02 95895-D4100 G21', + ], + }, + CAR.KIA_OPTIMA_G4_FL: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00JF__ SCC F-CUP 1.00 1.00 96400-D4110 ', + ], + (Ecu.abs, 0x7d1, None): [ + b"\xf1\x00JF ESC \t 11 \x18\x03' 58920-D5260", + b'\xf1\x00JF ESC \x0b 11 \x18\x030 58920-D5180', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00JFA LKAS AT USA LHD 1.00 1.00 95895-D5001 h32', + b'\xf1\x00JFA LKAS AT USA LHD 1.00 1.00 95895-D5100 h32', + ], + }, + CAR.KIA_OPTIMA_H: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00JFhe SCC FNCUP 1.00 1.00 96400-A8000 ', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00JFP LKAS AT EUR LHD 1.00 1.03 95895-A8100 160711', + ], + }, + CAR.KIA_OPTIMA_H_G4_FL: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00JFhe SCC FHCUP 1.00 1.01 99110-A8500 ', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00JFH MFC AT KOR LHD 1.00 1.01 95895-A8200 180323', + ], + }, + CAR.HYUNDAI_ELANTRA: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00AD LKAS AT USA LHD 1.01 1.01 95895-F2000 251', + b'\xf1\x00ADP LKAS AT USA LHD 1.00 1.03 99211-F2000 X31', + ], + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00AD ESC \x11 11 \x18\x05\x06 58910-F2840', + b'\xf1\x00AD ESC \x11 12 \x15\t\t 58920-F2810', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00AD__ SCC H-CUP 1.00 1.00 99110-F2100 ', + b'\xf1\x00AD__ SCC H-CUP 1.00 1.01 96400-F2100 ', + ], + }, + CAR.HYUNDAI_ELANTRA_GT_I30: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00PD LKAS AT KOR LHD 1.00 1.02 95740-G3000 A51', + b'\xf1\x00PD LKAS AT USA LHD 1.00 1.02 95740-G3000 A51', + b'\xf1\x00PD LKAS AT USA LHD 1.01 1.01 95740-G3100 A54', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00PD MDPS C 1.00 1.00 56310G3300\x00 4PDDC100', + b'\xf1\x00PD MDPS C 1.00 1.03 56310/G3300 4PDDC103', + b'\xf1\x00PD MDPS C 1.00 1.04 56310/G3300 4PDDC104', + ], + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00PD ESC \t 104\x18\t\x03 58920-G3350', + b'\xf1\x00PD ESC \x0b 103\x17\x110 58920-G3350', + b'\xf1\x00PD ESC \x0b 104\x18\t\x03 58920-G3350', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00PD__ SCC F-CUP 1.00 1.00 96400-G3300 ', + b'\xf1\x00PD__ SCC F-CUP 1.01 1.00 96400-G3100 ', + b'\xf1\x00PD__ SCC FNCUP 1.01 1.00 96400-G3000 ', + ], + }, + CAR.HYUNDAI_ELANTRA_2021: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00CN7_ SCC F-CUP 1.00 1.01 99110-AA000 ', + b'\xf1\x00CN7_ SCC FHCUP 1.00 1.01 99110-AA000 ', + b'\xf1\x00CN7_ SCC FNCUP 1.00 1.01 99110-AA000 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00CN7 MDPS C 1.00 1.06 56310/AA050 4CNDC106', + b'\xf1\x00CN7 MDPS C 1.00 1.06 56310/AA070 4CNDC106', + b'\xf1\x00CN7 MDPS C 1.00 1.06 56310AA050\x00 4CNDC106', + b'\xf1\x00CN7 MDPS C 1.00 1.07 56310AA050\x00 4CNDC107', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.00 99210-AB000 200819', + b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.01 99210-AB000 210205', + b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.02 99210-AB000 220111', + b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.03 99210-AA000 200819', + b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.03 99210-AB000 220426', + b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.06 99210-AA000 220111', + b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.07 99210-AA000 220426', + b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.08 99210-AA000 220728', + ], + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00CN ESC \t 101 \x10\x03 58910-AB800', + b'\xf1\x00CN ESC \t 104 \x08\x03 58910-AA800', + b'\xf1\x00CN ESC \t 105 \x10\x03 58910-AA800', + ], + }, + CAR.HYUNDAI_ELANTRA_HEV_2021: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00CN7HMFC AT USA LHD 1.00 1.03 99210-AA000 200819', + b'\xf1\x00CN7HMFC AT USA LHD 1.00 1.05 99210-AA000 210930', + b'\xf1\x00CN7HMFC AT USA LHD 1.00 1.07 99210-AA000 220426', + b'\xf1\x00CN7HMFC AT USA LHD 1.00 1.08 99210-AA000 220728', + b'\xf1\x00CN7HMFC AT USA LHD 1.00 1.09 99210-AA000 221108', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00CNhe SCC FHCUP 1.00 1.01 99110-BY000 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00CN7 MDPS C 1.00 1.02 56310/BY050 4CNHC102', + b'\xf1\x00CN7 MDPS C 1.00 1.03 56310/BY050 4CNHC103', + b'\xf1\x00CN7 MDPS C 1.00 1.03 56310BY050\x00 4CNHC103', + b'\xf1\x00CN7 MDPS C 1.00 1.03 56310BY0500 4CNHC103', + b'\xf1\x00CN7 MDPS C 1.00 1.04 56310BY050\x00 4CNHC104', + ], + }, + CAR.HYUNDAI_KONA_HEV: { + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00OS IEB \x01 104 \x11 58520-CM000', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00OShe SCC FNCUP 1.00 1.01 99110-CM000 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00OS MDPS C 1.00 1.00 56310CM030\x00 4OHDC100', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00OSH LKAS AT KOR LHD 1.00 1.01 95740-CM000 l31', + ], + }, + CAR.HYUNDAI_SONATA_HYBRID: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00DNhe SCC F-CUP 1.00 1.02 99110-L5000 ', + b'\xf1\x00DNhe SCC FHCUP 1.00 1.00 99110-L5000 ', + b'\xf1\x00DNhe SCC FHCUP 1.00 1.02 99110-L5000 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00DN8 MDPS C 1.00 1.01 56310-L5000 4DNHC101', + b'\xf1\x00DN8 MDPS C 1.00 1.02 56310-L5450 4DNHC102', + b'\xf1\x00DN8 MDPS C 1.00 1.02 56310-L5500 4DNHC102', + b'\xf1\x00DN8 MDPS C 1.00 1.03 56310-L5450 4DNHC103', + b'\xf1\x00DN8 MDPS C 1.00 1.03 56310L5450\x00 4DNHC104', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00DN8HMFC AT KOR LHD 1.00 1.03 99211-L1000 190705', + b'\xf1\x00DN8HMFC AT USA LHD 1.00 1.04 99211-L1000 191016', + b'\xf1\x00DN8HMFC AT USA LHD 1.00 1.05 99211-L1000 201109', + b'\xf1\x00DN8HMFC AT USA LHD 1.00 1.06 99211-L1000 210325', + b'\xf1\x00DN8HMFC AT USA LHD 1.00 1.07 99211-L1000 211223', + ], + }, + CAR.KIA_SORENTO: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00UMP LKAS AT KOR LHD 1.00 1.00 95740-C5550 S30', + b'\xf1\x00UMP LKAS AT USA LHD 1.00 1.00 95740-C6550 d00', + b'\xf1\x00UMP LKAS AT USA LHD 1.01 1.01 95740-C6550 d01', + ], + (Ecu.abs, 0x7d1, None): [ + b'\xf1\x00UM ESC \x02 12 \x18\x05\x05 58910-C6300', + b'\xf1\x00UM ESC \x0c 12 \x18\x05\x06 58910-C6330', + b'\xf1\x00UM ESC \x13 12 \x17\x07\x05 58910-C5320', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00UM__ SCC F-CUP 1.00 1.00 96400-C5500 ', + b'\xf1\x00UM__ SCC F-CUP 1.00 1.00 96400-C6500 ', + ], + }, + CAR.KIA_EV6: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00CV1_ RDR ----- 1.00 1.01 99110-CV000 ', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00CV1 MFC AT EUR LHD 1.00 1.05 99210-CV000 211027', + b'\xf1\x00CV1 MFC AT EUR LHD 1.00 1.06 99210-CV000 220328', + b'\xf1\x00CV1 MFC AT EUR RHD 1.00 1.00 99210-CV100 220630', + b'\xf1\x00CV1 MFC AT KOR LHD 1.00 1.04 99210-CV000 210823', + b'\xf1\x00CV1 MFC AT KOR LHD 1.00 1.05 99210-CV000 211027', + b'\xf1\x00CV1 MFC AT KOR LHD 1.00 1.06 99210-CV000 220328', + b'\xf1\x00CV1 MFC AT USA LHD 1.00 1.00 99210-CV100 220630', + b'\xf1\x00CV1 MFC AT USA LHD 1.00 1.00 99210-CV200 230510', + b'\xf1\x00CV1 MFC AT USA LHD 1.00 1.05 99210-CV000 211027', + b'\xf1\x00CV1 MFC AT USA LHD 1.00 1.06 99210-CV000 220328', + ], + }, + CAR.HYUNDAI_IONIQ_5: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00NE1_ RDR ----- 1.00 1.00 99110-GI000 ', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00NE1 MFC AT CAN LHD 1.00 1.01 99211-GI010 211007', + b'\xf1\x00NE1 MFC AT CAN LHD 1.00 1.05 99211-GI010 220614', + b'\xf1\x00NE1 MFC AT EUR LHD 1.00 1.01 99211-GI010 211007', + b'\xf1\x00NE1 MFC AT EUR LHD 1.00 1.06 99211-GI000 210813', + b'\xf1\x00NE1 MFC AT EUR LHD 1.00 1.06 99211-GI010 230110', + b'\xf1\x00NE1 MFC AT EUR RHD 1.00 1.01 99211-GI010 211007', + b'\xf1\x00NE1 MFC AT EUR RHD 1.00 1.02 99211-GI010 211206', + b'\xf1\x00NE1 MFC AT KOR LHD 1.00 1.00 99211-GI020 230719', + b'\xf1\x00NE1 MFC AT KOR LHD 1.00 1.05 99211-GI010 220614', + b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.00 99211-GI020 230719', + b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.01 99211-GI010 211007', + b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.02 99211-GI010 211206', + b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.03 99211-GI010 220401', + b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.05 99211-GI010 220614', + b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.06 99211-GI010 230110', + ], + }, + CAR.HYUNDAI_IONIQ_6: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00CE__ RDR ----- 1.00 1.01 99110-KL000 ', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00CE MFC AT CAN LHD 1.00 1.04 99211-KL000 221213', + b'\xf1\x00CE MFC AT EUR LHD 1.00 1.03 99211-KL000 221011', + b'\xf1\x00CE MFC AT EUR LHD 1.00 1.04 99211-KL000 221213', + b'\xf1\x00CE MFC AT USA LHD 1.00 1.04 99211-KL000 221213', + ], + }, + CAR.HYUNDAI_TUCSON_4TH_GEN: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00NX4 FR_CMR AT CAN LHD 1.00 1.00 99211-N9260 14Y', + b'\xf1\x00NX4 FR_CMR AT CAN LHD 1.00 1.01 99211-N9100 14A', + b'\xf1\x00NX4 FR_CMR AT EUR LHD 1.00 1.00 99211-N9220 14K', + b'\xf1\x00NX4 FR_CMR AT EUR LHD 1.00 2.02 99211-N9000 14E', + b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-N9210 14G', + b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-N9220 14K', + b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-N9240 14Q', + b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-N9250 14W', + b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-N9260 14Y', + b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.01 99211-N9100 14A', + b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.01 99211-N9240 14T', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00NX4__ 1.00 1.00 99110-N9100 ', + b'\xf1\x00NX4__ 1.00 1.01 99110-N9000 ', + b'\xf1\x00NX4__ 1.00 1.02 99110-N9000 ', + b'\xf1\x00NX4__ 1.01 1.00 99110-N9100 ', + ], + }, + CAR.HYUNDAI_SANTA_CRUZ_1ST_GEN: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-CW000 14M', + b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-CW010 14X', + b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-CW020 14Z', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00NX4__ 1.00 1.00 99110-K5000 ', + b'\xf1\x00NX4__ 1.01 1.00 99110-K5000 ', + ], + }, + CAR.KIA_SPORTAGE_5TH_GEN: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00NQ5 FR_CMR AT AUS RHD 1.00 1.00 99211-P1040 663', + b'\xf1\x00NQ5 FR_CMR AT EUR LHD 1.00 1.00 99211-P1040 663', + b'\xf1\x00NQ5 FR_CMR AT GEN LHD 1.00 1.00 99211-P1060 665', + b'\xf1\x00NQ5 FR_CMR AT USA LHD 1.00 1.00 99211-P1030 662', + b'\xf1\x00NQ5 FR_CMR AT USA LHD 1.00 1.00 99211-P1040 663', + b'\xf1\x00NQ5 FR_CMR AT USA LHD 1.00 1.00 99211-P1060 665', + b'\xf1\x00NQ5 FR_CMR AT USA LHD 1.00 1.00 99211-P1070 690', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00NQ5__ 1.00 1.02 99110-P1000 ', + b'\xf1\x00NQ5__ 1.00 1.03 99110-CH000 ', + b'\xf1\x00NQ5__ 1.00 1.03 99110-P1000 ', + b'\xf1\x00NQ5__ 1.01 1.03 99110-CH000 ', + b'\xf1\x00NQ5__ 1.01 1.03 99110-P1000 ', + ], + }, + CAR.GENESIS_GV70_1ST_GEN: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00JK1 MFC AT USA LHD 1.00 1.01 99211-AR200 220125', + b'\xf1\x00JK1 MFC AT USA LHD 1.00 1.01 99211-AR300 220125', + b'\xf1\x00JK1 MFC AT USA LHD 1.00 1.04 99211-AR000 210204', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00JK1_ SCC FHCUP 1.00 1.00 99110-AR200 ', + b'\xf1\x00JK1_ SCC FHCUP 1.00 1.00 99110-AR300 ', + b'\xf1\x00JK1_ SCC FHCUP 1.00 1.02 99110-AR000 ', + ], + }, + CAR.GENESIS_GV60_EV_1ST_GEN: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00JW1 MFC AT USA LHD 1.00 1.02 99211-CU000 211215', + b'\xf1\x00JW1 MFC AT USA LHD 1.00 1.02 99211-CU100 211215', + b'\xf1\x00JW1 MFC AT USA LHD 1.00 1.03 99211-CU000 221118', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00JW1_ RDR ----- 1.00 1.00 99110-CU000 ', + ], + }, + CAR.KIA_SORENTO_4TH_GEN: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00MQ4 MFC AT USA LHD 1.00 1.00 99210-R5100 221019', + b'\xf1\x00MQ4 MFC AT USA LHD 1.00 1.03 99210-R5000 200903', + b'\xf1\x00MQ4 MFC AT USA LHD 1.00 1.05 99210-R5000 210623', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00MQ4_ SCC F-CUP 1.00 1.06 99110-P2000 ', + b'\xf1\x00MQ4_ SCC FHCUP 1.00 1.00 99110-R5000 ', + b'\xf1\x00MQ4_ SCC FHCUP 1.00 1.06 99110-P2000 ', + b'\xf1\x00MQ4_ SCC FHCUP 1.00 1.08 99110-P2000 ', + ], + }, + CAR.KIA_SORENTO_HEV_4TH_GEN: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00MQ4HMFC AT KOR LHD 1.00 1.04 99210-P2000 200330', + b'\xf1\x00MQ4HMFC AT KOR LHD 1.00 1.12 99210-P2000 230331', + b'\xf1\x00MQ4HMFC AT USA LHD 1.00 1.10 99210-P2000 210406', + b'\xf1\x00MQ4HMFC AT USA LHD 1.00 1.11 99210-P2000 211217', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00MQhe SCC FHCUP 1.00 1.04 99110-P4000 ', + b'\xf1\x00MQhe SCC FHCUP 1.00 1.06 99110-P4000 ', + b'\xf1\x00MQhe SCC FHCUP 1.00 1.07 99110-P4000 ', + ], + }, + CAR.KIA_NIRO_HEV_2ND_GEN: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00SG2HMFC AT USA LHD 1.01 1.08 99211-AT000 220531', + b'\xf1\x00SG2HMFC AT USA LHD 1.01 1.09 99211-AT000 220801', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00SG2_ RDR ----- 1.00 1.01 99110-AT000 ', + ], + }, + CAR.GENESIS_GV80: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00JX1 MFC AT USA LHD 1.00 1.02 99211-T6110 220513', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00JX1_ SCC FHCUP 1.00 1.01 99110-T6100 ', + ], + }, + CAR.KIA_CARNIVAL_4TH_GEN: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00KA4 MFC AT EUR LHD 1.00 1.06 99210-R0000 220221', + b'\xf1\x00KA4 MFC AT KOR LHD 1.00 1.06 99210-R0000 220221', + b'\xf1\x00KA4 MFC AT USA LHD 1.00 1.00 99210-R0100 230105', + b'\xf1\x00KA4 MFC AT USA LHD 1.00 1.01 99210-R0100 230710', + b'\xf1\x00KA4 MFC AT USA LHD 1.00 1.05 99210-R0000 201221', + b'\xf1\x00KA4 MFC AT USA LHD 1.00 1.06 99210-R0000 220221', + b'\xf1\x00KA4CMFC AT CHN LHD 1.00 1.01 99211-I4000 210525', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00KA4_ SCC F-CUP 1.00 1.03 99110-R0000 ', + b'\xf1\x00KA4_ SCC FHCUP 1.00 1.00 99110-R0100 ', + b'\xf1\x00KA4_ SCC FHCUP 1.00 1.03 99110-R0000 ', + b'\xf1\x00KA4c SCC FHCUP 1.00 1.01 99110-I4000 ', + ], + }, + CAR.KIA_K8_HEV_1ST_GEN: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00GL3HMFC AT KOR LHD 1.00 1.03 99211-L8000 210907', + b'\xf1\x00GL3HMFC AT KOR LHD 1.00 1.04 99211-L8000 230207', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00GL3_ RDR ----- 1.00 1.02 99110-L8000 ', + ], + }, + CAR.HYUNDAI_STARIA_4TH_GEN: { + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00US4 MFC AT KOR LHD 1.00 1.06 99211-CG000 230524', + ], + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x00US4_ RDR ----- 1.00 1.00 99110-CG000 ', + ], + }, +} diff --git a/car/hyundai/hyundaican.py b/car/hyundai/hyundaican.py new file mode 100644 index 0000000000..b4b951f89e --- /dev/null +++ b/car/hyundai/hyundaican.py @@ -0,0 +1,213 @@ +import crcmod +from openpilot.selfdrive.car.hyundai.values import CAR, HyundaiFlags + +hyundai_checksum = crcmod.mkCrcFun(0x11D, initCrc=0xFD, rev=False, xorOut=0xdf) + +def create_lkas11(packer, frame, CP, apply_steer, steer_req, + torque_fault, lkas11, sys_warning, sys_state, enabled, + left_lane, right_lane, + left_lane_depart, right_lane_depart): + values = {s: lkas11[s] for s in [ + "CF_Lkas_LdwsActivemode", + "CF_Lkas_LdwsSysState", + "CF_Lkas_SysWarning", + "CF_Lkas_LdwsLHWarning", + "CF_Lkas_LdwsRHWarning", + "CF_Lkas_HbaLamp", + "CF_Lkas_FcwBasReq", + "CF_Lkas_HbaSysState", + "CF_Lkas_FcwOpt", + "CF_Lkas_HbaOpt", + "CF_Lkas_FcwSysState", + "CF_Lkas_FcwCollisionWarning", + "CF_Lkas_FusionState", + "CF_Lkas_FcwOpt_USM", + "CF_Lkas_LdwsOpt_USM", + ]} + values["CF_Lkas_LdwsSysState"] = sys_state + values["CF_Lkas_SysWarning"] = 3 if sys_warning else 0 + values["CF_Lkas_LdwsLHWarning"] = left_lane_depart + values["CF_Lkas_LdwsRHWarning"] = right_lane_depart + values["CR_Lkas_StrToqReq"] = apply_steer + values["CF_Lkas_ActToi"] = steer_req + values["CF_Lkas_ToiFlt"] = torque_fault # seems to allow actuation on CR_Lkas_StrToqReq + values["CF_Lkas_MsgCount"] = frame % 0x10 + + if CP.carFingerprint in (CAR.HYUNDAI_SONATA, CAR.HYUNDAI_PALISADE, CAR.KIA_NIRO_EV, CAR.KIA_NIRO_HEV_2021, CAR.HYUNDAI_SANTA_FE, + CAR.HYUNDAI_IONIQ_EV_2020, CAR.HYUNDAI_IONIQ_PHEV, CAR.KIA_SELTOS, CAR.HYUNDAI_ELANTRA_2021, CAR.GENESIS_G70_2020, + CAR.HYUNDAI_ELANTRA_HEV_2021, CAR.HYUNDAI_SONATA_HYBRID, CAR.HYUNDAI_KONA_EV, CAR.HYUNDAI_KONA_HEV, CAR.HYUNDAI_KONA_EV_2022, + CAR.HYUNDAI_SANTA_FE_2022, CAR.KIA_K5_2021, CAR.HYUNDAI_IONIQ_HEV_2022, CAR.HYUNDAI_SANTA_FE_HEV_2022, + CAR.HYUNDAI_SANTA_FE_PHEV_2022, CAR.KIA_STINGER_2022, CAR.KIA_K5_HEV_2020, CAR.KIA_CEED, + CAR.HYUNDAI_AZERA_6TH_GEN, CAR.HYUNDAI_AZERA_HEV_6TH_GEN, CAR.HYUNDAI_CUSTIN_1ST_GEN): + values["CF_Lkas_LdwsActivemode"] = int(left_lane) + (int(right_lane) << 1) + values["CF_Lkas_LdwsOpt_USM"] = 2 + + # FcwOpt_USM 5 = Orange blinking car + lanes + # FcwOpt_USM 4 = Orange car + lanes + # FcwOpt_USM 3 = Green blinking car + lanes + # FcwOpt_USM 2 = Green car + lanes + # FcwOpt_USM 1 = White car + lanes + # FcwOpt_USM 0 = No car + lanes + values["CF_Lkas_FcwOpt_USM"] = 2 if enabled else 1 + + # SysWarning 4 = keep hands on wheel + # SysWarning 5 = keep hands on wheel (red) + # SysWarning 6 = keep hands on wheel (red) + beep + # Note: the warning is hidden while the blinkers are on + values["CF_Lkas_SysWarning"] = 4 if sys_warning else 0 + + # Likely cars lacking the ability to show individual lane lines in the dash + elif CP.carFingerprint in (CAR.KIA_OPTIMA_G4, CAR.KIA_OPTIMA_G4_FL): + # SysWarning 4 = keep hands on wheel + beep + values["CF_Lkas_SysWarning"] = 4 if sys_warning else 0 + + # SysState 0 = no icons + # SysState 1-2 = white car + lanes + # SysState 3 = green car + lanes, green steering wheel + # SysState 4 = green car + lanes + values["CF_Lkas_LdwsSysState"] = 3 if enabled else 1 + values["CF_Lkas_LdwsOpt_USM"] = 2 # non-2 changes above SysState definition + + # these have no effect + values["CF_Lkas_LdwsActivemode"] = 0 + values["CF_Lkas_FcwOpt_USM"] = 0 + + elif CP.carFingerprint == CAR.HYUNDAI_GENESIS: + # This field is actually LdwsActivemode + # Genesis and Optima fault when forwarding while engaged + values["CF_Lkas_LdwsActivemode"] = 2 + + dat = packer.make_can_msg("LKAS11", 0, values)[2] + + if CP.flags & HyundaiFlags.CHECKSUM_CRC8: + # CRC Checksum as seen on 2019 Hyundai Santa Fe + dat = dat[:6] + dat[7:8] + checksum = hyundai_checksum(dat) + elif CP.flags & HyundaiFlags.CHECKSUM_6B: + # Checksum of first 6 Bytes, as seen on 2018 Kia Sorento + checksum = sum(dat[:6]) % 256 + else: + # Checksum of first 6 Bytes and last Byte as seen on 2018 Kia Stinger + checksum = (sum(dat[:6]) + dat[7]) % 256 + + values["CF_Lkas_Chksum"] = checksum + + return packer.make_can_msg("LKAS11", 0, values) + + +def create_clu11(packer, frame, clu11, button, CP): + values = {s: clu11[s] for s in [ + "CF_Clu_CruiseSwState", + "CF_Clu_CruiseSwMain", + "CF_Clu_SldMainSW", + "CF_Clu_ParityBit1", + "CF_Clu_VanzDecimal", + "CF_Clu_Vanz", + "CF_Clu_SPEED_UNIT", + "CF_Clu_DetentOut", + "CF_Clu_RheostatLevel", + "CF_Clu_CluInfo", + "CF_Clu_AmpInfo", + "CF_Clu_AliveCnt1", + ]} + values["CF_Clu_CruiseSwState"] = button + values["CF_Clu_AliveCnt1"] = frame % 0x10 + # send buttons to camera on camera-scc based cars + bus = 2 if CP.flags & HyundaiFlags.CAMERA_SCC else 0 + return packer.make_can_msg("CLU11", bus, values) + + +def create_lfahda_mfc(packer, enabled, hda_set_speed=0): + values = { + "LFA_Icon_State": 2 if enabled else 0, + "HDA_Active": 1 if hda_set_speed else 0, + "HDA_Icon_State": 2 if hda_set_speed else 0, + "HDA_VSetReq": hda_set_speed, + } + return packer.make_can_msg("LFAHDA_MFC", 0, values) + +def create_acc_commands(packer, enabled, accel, upper_jerk, idx, hud_control, set_speed, stopping, long_override, use_fca): + commands = [] + + scc11_values = { + "MainMode_ACC": 1, + "TauGapSet": hud_control.leadDistanceBars, + "VSetDis": set_speed if enabled else 0, + "AliveCounterACC": idx % 0x10, + "ObjValid": 1, # close lead makes controls tighter + "ACC_ObjStatus": 1, # close lead makes controls tighter + "ACC_ObjLatPos": 0, + "ACC_ObjRelSpd": 0, + "ACC_ObjDist": 1, # close lead makes controls tighter + } + commands.append(packer.make_can_msg("SCC11", 0, scc11_values)) + + scc12_values = { + "ACCMode": 2 if enabled and long_override else 1 if enabled else 0, + "StopReq": 1 if stopping else 0, + "aReqRaw": accel, + "aReqValue": accel, # stock ramps up and down respecting jerk limit until it reaches aReqRaw + "CR_VSM_Alive": idx % 0xF, + } + + # show AEB disabled indicator on dash with SCC12 if not sending FCA messages. + # these signals also prevent a TCS fault on non-FCA cars with alpha longitudinal + if not use_fca: + scc12_values["CF_VSM_ConfMode"] = 1 + scc12_values["AEB_Status"] = 1 # AEB disabled + + scc12_dat = packer.make_can_msg("SCC12", 0, scc12_values)[2] + scc12_values["CR_VSM_ChkSum"] = 0x10 - sum(sum(divmod(i, 16)) for i in scc12_dat) % 0x10 + + commands.append(packer.make_can_msg("SCC12", 0, scc12_values)) + + scc14_values = { + "ComfortBandUpper": 0.0, # stock usually is 0 but sometimes uses higher values + "ComfortBandLower": 0.0, # stock usually is 0 but sometimes uses higher values + "JerkUpperLimit": upper_jerk, # stock usually is 1.0 but sometimes uses higher values + "JerkLowerLimit": 5.0, # stock usually is 0.5 but sometimes uses higher values + "ACCMode": 2 if enabled and long_override else 1 if enabled else 4, # stock will always be 4 instead of 0 after first disengage + "ObjGap": 2 if hud_control.leadVisible else 0, # 5: >30, m, 4: 25-30 m, 3: 20-25 m, 2: < 20 m, 0: no lead + } + commands.append(packer.make_can_msg("SCC14", 0, scc14_values)) + + # Only send FCA11 on cars where it exists on the bus + if use_fca: + # note that some vehicles most likely have an alternate checksum/counter definition + # https://github.com/commaai/opendbc/commit/9ddcdb22c4929baf310295e832668e6e7fcfa602 + fca11_values = { + "CR_FCA_Alive": idx % 0xF, + "PAINT1_Status": 1, + "FCA_DrvSetStatus": 1, + "FCA_Status": 1, # AEB disabled + } + fca11_dat = packer.make_can_msg("FCA11", 0, fca11_values)[2] + fca11_values["CR_FCA_ChkSum"] = hyundai_checksum(fca11_dat[:7]) + commands.append(packer.make_can_msg("FCA11", 0, fca11_values)) + + return commands + +def create_acc_opt(packer): + commands = [] + + scc13_values = { + "SCCDrvModeRValue": 2, + "SCC_Equip": 1, + "Lead_Veh_Dep_Alert_USM": 2, + } + commands.append(packer.make_can_msg("SCC13", 0, scc13_values)) + + # TODO: this needs to be detected and conditionally sent on unsupported long cars + fca12_values = { + "FCA_DrvSetState": 2, + "FCA_USM": 1, # AEB disabled + } + commands.append(packer.make_can_msg("FCA12", 0, fca12_values)) + + return commands + +def create_frt_radar_opt(packer): + frt_radar11_values = { + "CF_FCA_Equip_Front_Radar": 1, + } + return packer.make_can_msg("FRT_RADAR11", 0, frt_radar11_values) diff --git a/car/hyundai/hyundaicanfd.py b/car/hyundai/hyundaicanfd.py new file mode 100644 index 0000000000..54804f94fd --- /dev/null +++ b/car/hyundai/hyundaicanfd.py @@ -0,0 +1,223 @@ +from openpilot.common.numpy_fast import clip +from openpilot.selfdrive.car import CanBusBase +from openpilot.selfdrive.car.hyundai.values import HyundaiFlags + + +class CanBus(CanBusBase): + def __init__(self, CP, hda2=None, fingerprint=None) -> None: + super().__init__(CP, fingerprint) + + if hda2 is None: + assert CP is not None + hda2 = CP.flags & HyundaiFlags.CANFD_HDA2.value + + # On the CAN-FD platforms, the LKAS camera is on both A-CAN and E-CAN. HDA2 cars + # have a different harness than the HDA1 and non-HDA variants in order to split + # a different bus, since the steering is done by different ECUs. + self._a, self._e = 1, 0 + if hda2: + self._a, self._e = 0, 1 + + self._a += self.offset + self._e += self.offset + self._cam = 2 + self.offset + + @property + def ECAN(self): + return self._e + + @property + def ACAN(self): + return self._a + + @property + def CAM(self): + return self._cam + + +def create_steering_messages(packer, CP, CAN, enabled, lat_active, apply_steer): + + ret = [] + + values = { + "LKA_MODE": 2, + "LKA_ICON": 2 if enabled else 1, + "TORQUE_REQUEST": apply_steer, + "LKA_ASSIST": 0, + "STEER_REQ": 1 if lat_active else 0, + "STEER_MODE": 0, + "HAS_LANE_SAFETY": 0, # hide LKAS settings + "NEW_SIGNAL_1": 0, + "NEW_SIGNAL_2": 0, + } + + if CP.flags & HyundaiFlags.CANFD_HDA2: + hda2_lkas_msg = "LKAS_ALT" if CP.flags & HyundaiFlags.CANFD_HDA2_ALT_STEERING else "LKAS" + if CP.openpilotLongitudinalControl: + ret.append(packer.make_can_msg("LFA", CAN.ECAN, values)) + ret.append(packer.make_can_msg(hda2_lkas_msg, CAN.ACAN, values)) + else: + ret.append(packer.make_can_msg("LFA", CAN.ECAN, values)) + + return ret + +def create_suppress_lfa(packer, CAN, hda2_lfa_block_msg, hda2_alt_steering): + suppress_msg = "CAM_0x362" if hda2_alt_steering else "CAM_0x2a4" + msg_bytes = 32 if hda2_alt_steering else 24 + + values = {f"BYTE{i}": hda2_lfa_block_msg[f"BYTE{i}"] for i in range(3, msg_bytes) if i != 7} + values["COUNTER"] = hda2_lfa_block_msg["COUNTER"] + values["SET_ME_0"] = 0 + values["SET_ME_0_2"] = 0 + values["LEFT_LANE_LINE"] = 0 + values["RIGHT_LANE_LINE"] = 0 + return packer.make_can_msg(suppress_msg, CAN.ACAN, values) + +def create_buttons(packer, CP, CAN, cnt, btn): + values = { + "COUNTER": cnt, + "SET_ME_1": 1, + "CRUISE_BUTTONS": btn, + } + + bus = CAN.ECAN if CP.flags & HyundaiFlags.CANFD_HDA2 else CAN.CAM + return packer.make_can_msg("CRUISE_BUTTONS", bus, values) + +def create_acc_cancel(packer, CP, CAN, cruise_info_copy): + # TODO: why do we copy different values here? + if CP.flags & HyundaiFlags.CANFD_CAMERA_SCC.value: + values = {s: cruise_info_copy[s] for s in [ + "COUNTER", + "CHECKSUM", + "NEW_SIGNAL_1", + "MainMode_ACC", + "ACCMode", + "ZEROS_9", + "CRUISE_STANDSTILL", + "ZEROS_5", + "DISTANCE_SETTING", + "VSetDis", + ]} + else: + values = {s: cruise_info_copy[s] for s in [ + "COUNTER", + "CHECKSUM", + "ACCMode", + "VSetDis", + "CRUISE_STANDSTILL", + ]} + values.update({ + "ACCMode": 4, + "aReqRaw": 0.0, + "aReqValue": 0.0, + }) + return packer.make_can_msg("SCC_CONTROL", CAN.ECAN, values) + +def create_lfahda_cluster(packer, CAN, enabled): + values = { + "HDA_ICON": 1 if enabled else 0, + "LFA_ICON": 2 if enabled else 0, + } + return packer.make_can_msg("LFAHDA_CLUSTER", CAN.ECAN, values) + + +def create_acc_control(packer, CAN, enabled, accel_last, accel, stopping, gas_override, set_speed, hud_control): + jerk = 5 + jn = jerk / 50 + if not enabled or gas_override: + a_val, a_raw = 0, 0 + else: + a_raw = accel + a_val = clip(accel, accel_last - jn, accel_last + jn) + + values = { + "ACCMode": 0 if not enabled else (2 if gas_override else 1), + "MainMode_ACC": 1, + "StopReq": 1 if stopping else 0, + "aReqValue": a_val, + "aReqRaw": a_raw, + "VSetDis": set_speed, + "JerkLowerLimit": jerk if enabled else 1, + "JerkUpperLimit": 3.0, + + "ACC_ObjDist": 1, + "ObjValid": 0, + "OBJ_STATUS": 2, + "SET_ME_2": 0x4, + "SET_ME_3": 0x3, + "SET_ME_TMP_64": 0x64, + "DISTANCE_SETTING": hud_control.leadDistanceBars, + } + + return packer.make_can_msg("SCC_CONTROL", CAN.ECAN, values) + + +def create_spas_messages(packer, CAN, frame, left_blink, right_blink): + ret = [] + + values = { + } + ret.append(packer.make_can_msg("SPAS1", CAN.ECAN, values)) + + blink = 0 + if left_blink: + blink = 3 + elif right_blink: + blink = 4 + values = { + "BLINKER_CONTROL": blink, + } + ret.append(packer.make_can_msg("SPAS2", CAN.ECAN, values)) + + return ret + + +def create_adrv_messages(packer, CAN, frame): + # messages needed to car happy after disabling + # the ADAS Driving ECU to do longitudinal control + + ret = [] + + values = { + } + ret.append(packer.make_can_msg("ADRV_0x51", CAN.ACAN, values)) + + if frame % 2 == 0: + values = { + 'AEB_SETTING': 0x1, # show AEB disabled icon + 'SET_ME_2': 0x2, + 'SET_ME_FF': 0xff, + 'SET_ME_FC': 0xfc, + 'SET_ME_9': 0x9, + } + ret.append(packer.make_can_msg("ADRV_0x160", CAN.ECAN, values)) + + if frame % 5 == 0: + values = { + 'SET_ME_1C': 0x1c, + 'SET_ME_FF': 0xff, + 'SET_ME_TMP_F': 0xf, + 'SET_ME_TMP_F_2': 0xf, + } + ret.append(packer.make_can_msg("ADRV_0x1ea", CAN.ECAN, values)) + + values = { + 'SET_ME_E1': 0xe1, + 'SET_ME_3A': 0x3a, + } + ret.append(packer.make_can_msg("ADRV_0x200", CAN.ECAN, values)) + + if frame % 20 == 0: + values = { + 'SET_ME_15': 0x15, + } + ret.append(packer.make_can_msg("ADRV_0x345", CAN.ECAN, values)) + + if frame % 100 == 0: + values = { + 'SET_ME_22': 0x22, + 'SET_ME_41': 0x41, + } + ret.append(packer.make_can_msg("ADRV_0x1da", CAN.ECAN, values)) + + return ret diff --git a/car/hyundai/interface.py b/car/hyundai/interface.py new file mode 100644 index 0000000000..22c54bce6b --- /dev/null +++ b/car/hyundai/interface.py @@ -0,0 +1,180 @@ +from cereal import car +from panda import Panda +from openpilot.selfdrive.car.hyundai.hyundaicanfd import CanBus +from openpilot.selfdrive.car.hyundai.values import HyundaiFlags, CAR, DBC, CANFD_CAR, CAMERA_SCC_CAR, CANFD_RADAR_SCC_CAR, \ + CANFD_UNSUPPORTED_LONGITUDINAL_CAR, EV_CAR, HYBRID_CAR, LEGACY_SAFETY_MODE_CAR, \ + UNSUPPORTED_LONGITUDINAL_CAR, Buttons +from openpilot.selfdrive.car.hyundai.radar_interface import RADAR_START_ADDR +from openpilot.selfdrive.car import create_button_events, get_safety_config +from openpilot.selfdrive.car.interfaces import CarInterfaceBase +from openpilot.selfdrive.car.disable_ecu import disable_ecu + +Ecu = car.CarParams.Ecu +ButtonType = car.CarState.ButtonEvent.Type +EventName = car.CarEvent.EventName +ENABLE_BUTTONS = (Buttons.RES_ACCEL, Buttons.SET_DECEL, Buttons.CANCEL) +BUTTONS_DICT = {Buttons.RES_ACCEL: ButtonType.accelCruise, Buttons.SET_DECEL: ButtonType.decelCruise, + Buttons.GAP_DIST: ButtonType.gapAdjustCruise, Buttons.CANCEL: ButtonType.cancel} + + +class CarInterface(CarInterfaceBase): + @staticmethod + def _get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs): + ret.carName = "hyundai" + ret.radarUnavailable = RADAR_START_ADDR not in fingerprint[1] or DBC[ret.carFingerprint]["radar"] is None + + # These cars have been put into dashcam only due to both a lack of users and test coverage. + # These cars likely still work fine. Once a user confirms each car works and a test route is + # added to selfdrive/car/tests/routes.py, we can remove it from this list. + # FIXME: the Optima Hybrid 2017 uses a different SCC12 checksum + ret.dashcamOnly = candidate in {CAR.KIA_OPTIMA_H, } + + hda2 = Ecu.adas in [fw.ecu for fw in car_fw] + CAN = CanBus(None, hda2, fingerprint) + + if candidate in CANFD_CAR: + # detect if car is hybrid + if 0x105 in fingerprint[CAN.ECAN]: + ret.flags |= HyundaiFlags.HYBRID.value + elif candidate in EV_CAR: + ret.flags |= HyundaiFlags.EV.value + + # detect HDA2 with ADAS Driving ECU + if hda2: + ret.flags |= HyundaiFlags.CANFD_HDA2.value + if 0x110 in fingerprint[CAN.CAM]: + ret.flags |= HyundaiFlags.CANFD_HDA2_ALT_STEERING.value + else: + # non-HDA2 + if 0x1cf not in fingerprint[CAN.ECAN]: + ret.flags |= HyundaiFlags.CANFD_ALT_BUTTONS.value + # ICE cars do not have 0x130; GEARS message on 0x40 or 0x70 instead + if 0x130 not in fingerprint[CAN.ECAN]: + if 0x40 not in fingerprint[CAN.ECAN]: + ret.flags |= HyundaiFlags.CANFD_ALT_GEARS_2.value + else: + ret.flags |= HyundaiFlags.CANFD_ALT_GEARS.value + if candidate not in CANFD_RADAR_SCC_CAR: + ret.flags |= HyundaiFlags.CANFD_CAMERA_SCC.value + else: + # TODO: detect EV and hybrid + if candidate in HYBRID_CAR: + ret.flags |= HyundaiFlags.HYBRID.value + elif candidate in EV_CAR: + ret.flags |= HyundaiFlags.EV.value + + # Send LFA message on cars with HDA + if 0x485 in fingerprint[2]: + ret.flags |= HyundaiFlags.SEND_LFA.value + + # These cars use the FCA11 message for the AEB and FCW signals, all others use SCC12 + if 0x38d in fingerprint[0] or 0x38d in fingerprint[2]: + ret.flags |= HyundaiFlags.USE_FCA.value + + ret.steerActuatorDelay = 0.1 # Default delay + ret.steerLimitTimer = 0.4 + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) + + if candidate == CAR.KIA_OPTIMA_G4_FL: + ret.steerActuatorDelay = 0.2 + + # *** longitudinal control *** + if candidate in CANFD_CAR: + ret.longitudinalTuning.kpV = [0.1] + ret.longitudinalTuning.kiV = [0.0] + ret.experimentalLongitudinalAvailable = candidate not in (CANFD_UNSUPPORTED_LONGITUDINAL_CAR | CANFD_RADAR_SCC_CAR) + else: + ret.longitudinalTuning.kpV = [0.5] + ret.longitudinalTuning.kiV = [0.0] + ret.experimentalLongitudinalAvailable = candidate not in (UNSUPPORTED_LONGITUDINAL_CAR | CAMERA_SCC_CAR) + ret.openpilotLongitudinalControl = experimental_long and ret.experimentalLongitudinalAvailable + ret.pcmCruise = not ret.openpilotLongitudinalControl + + ret.stoppingControl = True + ret.startingState = True + ret.vEgoStarting = 0.1 + ret.startAccel = 1.0 + ret.longitudinalActuatorDelayLowerBound = 0.5 + ret.longitudinalActuatorDelayUpperBound = 0.5 + + # *** feature detection *** + if candidate in CANFD_CAR: + ret.enableBsm = 0x1e5 in fingerprint[CAN.ECAN] + else: + ret.enableBsm = 0x58b in fingerprint[0] + + # *** panda safety config *** + if candidate in CANFD_CAR: + cfgs = [get_safety_config(car.CarParams.SafetyModel.hyundaiCanfd), ] + if CAN.ECAN >= 4: + cfgs.insert(0, get_safety_config(car.CarParams.SafetyModel.noOutput)) + ret.safetyConfigs = cfgs + + if ret.flags & HyundaiFlags.CANFD_HDA2: + ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_HYUNDAI_CANFD_HDA2 + if ret.flags & HyundaiFlags.CANFD_HDA2_ALT_STEERING: + ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_HYUNDAI_CANFD_HDA2_ALT_STEERING + if ret.flags & HyundaiFlags.CANFD_ALT_BUTTONS: + ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_HYUNDAI_CANFD_ALT_BUTTONS + if ret.flags & HyundaiFlags.CANFD_CAMERA_SCC: + ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_HYUNDAI_CAMERA_SCC + else: + if candidate in LEGACY_SAFETY_MODE_CAR: + # these cars require a special panda safety mode due to missing counters and checksums in the messages + ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.hyundaiLegacy)] + else: + ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.hyundai, 0)] + + if candidate in CAMERA_SCC_CAR: + ret.safetyConfigs[0].safetyParam |= Panda.FLAG_HYUNDAI_CAMERA_SCC + + if ret.openpilotLongitudinalControl: + ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_HYUNDAI_LONG + if ret.flags & HyundaiFlags.HYBRID: + ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_HYUNDAI_HYBRID_GAS + elif ret.flags & HyundaiFlags.EV: + ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_HYUNDAI_EV_GAS + + if candidate in (CAR.HYUNDAI_KONA, CAR.HYUNDAI_KONA_EV, CAR.HYUNDAI_KONA_HEV, CAR.HYUNDAI_KONA_EV_2022): + ret.flags |= HyundaiFlags.ALT_LIMITS.value + ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_HYUNDAI_ALT_LIMITS + + ret.centerToFront = ret.wheelbase * 0.4 + + return ret + + @staticmethod + def init(CP, logcan, sendcan): + if CP.openpilotLongitudinalControl and not (CP.flags & HyundaiFlags.CANFD_CAMERA_SCC.value): + addr, bus = 0x7d0, 0 + if CP.flags & HyundaiFlags.CANFD_HDA2.value: + addr, bus = 0x730, CanBus(CP).ECAN + disable_ecu(logcan, sendcan, bus=bus, addr=addr, com_cont_req=b'\x28\x83\x01') + + # for blinkers + if CP.flags & HyundaiFlags.ENABLE_BLINKERS: + disable_ecu(logcan, sendcan, bus=CanBus(CP).ECAN, addr=0x7B1, com_cont_req=b'\x28\x83\x01') + + def _update(self, c): + ret = self.CS.update(self.cp, self.cp_cam) + + if self.CS.CP.openpilotLongitudinalControl: + ret.buttonEvents = create_button_events(self.CS.cruise_buttons[-1], self.CS.prev_cruise_buttons, BUTTONS_DICT) + + # On some newer model years, the CANCEL button acts as a pause/resume button based on the PCM state + # To avoid re-engaging when openpilot cancels, check user engagement intention via buttons + # Main button also can trigger an engagement on these cars + allow_enable = any(btn in ENABLE_BUTTONS for btn in self.CS.cruise_buttons) or any(self.CS.main_buttons) + events = self.create_common_events(ret, pcm_enable=self.CS.CP.pcmCruise, allow_enable=allow_enable) + + # low speed steer alert hysteresis logic (only for cars with steer cut off above 10 m/s) + if ret.vEgo < (self.CP.minSteerSpeed + 2.) and self.CP.minSteerSpeed > 10.: + self.low_speed_alert = True + if ret.vEgo > (self.CP.minSteerSpeed + 4.): + self.low_speed_alert = False + if self.low_speed_alert: + events.add(car.CarEvent.EventName.belowSteerSpeed) + + ret.events = events.to_msg() + + return ret diff --git a/car/hyundai/radar_interface.py b/car/hyundai/radar_interface.py new file mode 100644 index 0000000000..5260050986 --- /dev/null +++ b/car/hyundai/radar_interface.py @@ -0,0 +1,79 @@ +import math + +from cereal import car +from opendbc.can.parser import CANParser +from openpilot.selfdrive.car.interfaces import RadarInterfaceBase +from openpilot.selfdrive.car.hyundai.values import DBC + +RADAR_START_ADDR = 0x500 +RADAR_MSG_COUNT = 32 + +# POC for parsing corner radars: https://github.com/commaai/openpilot/pull/24221/ + +def get_radar_can_parser(CP): + if DBC[CP.carFingerprint]['radar'] is None: + return None + + messages = [(f"RADAR_TRACK_{addr:x}", 50) for addr in range(RADAR_START_ADDR, RADAR_START_ADDR + RADAR_MSG_COUNT)] + return CANParser(DBC[CP.carFingerprint]['radar'], messages, 1) + + +class RadarInterface(RadarInterfaceBase): + def __init__(self, CP): + super().__init__(CP) + self.updated_messages = set() + self.trigger_msg = RADAR_START_ADDR + RADAR_MSG_COUNT - 1 + self.track_id = 0 + + self.radar_off_can = CP.radarUnavailable + self.rcp = get_radar_can_parser(CP) + + def update(self, can_strings): + if self.radar_off_can or (self.rcp is None): + return super().update(None) + + vls = self.rcp.update_strings(can_strings) + self.updated_messages.update(vls) + + if self.trigger_msg not in self.updated_messages: + return None + + rr = self._update(self.updated_messages) + self.updated_messages.clear() + + return rr + + def _update(self, updated_messages): + ret = car.RadarData.new_message() + if self.rcp is None: + return ret + + errors = [] + + if not self.rcp.can_valid: + errors.append("canError") + ret.errors = errors + + for addr in range(RADAR_START_ADDR, RADAR_START_ADDR + RADAR_MSG_COUNT): + msg = self.rcp.vl[f"RADAR_TRACK_{addr:x}"] + + if addr not in self.pts: + self.pts[addr] = car.RadarData.RadarPoint.new_message() + self.pts[addr].trackId = self.track_id + self.track_id += 1 + + valid = msg['STATE'] in (3, 4) + if valid: + azimuth = math.radians(msg['AZIMUTH']) + self.pts[addr].measured = True + self.pts[addr].dRel = math.cos(azimuth) * msg['LONG_DIST'] + self.pts[addr].yRel = 0.5 * -math.sin(azimuth) * msg['LONG_DIST'] + self.pts[addr].vRel = msg['REL_SPEED'] + self.pts[addr].aRel = msg['REL_ACCEL'] + self.pts[addr].yvRel = float('nan') + + else: + del self.pts[addr] + + ret.points = list(self.pts.values()) + return ret diff --git a/car/hyundai/tests/__init__.py b/car/hyundai/tests/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/car/hyundai/tests/print_platform_codes.py b/car/hyundai/tests/print_platform_codes.py new file mode 100755 index 0000000000..f641535678 --- /dev/null +++ b/car/hyundai/tests/print_platform_codes.py @@ -0,0 +1,22 @@ +#!/usr/bin/env python3 +from cereal import car +from openpilot.selfdrive.car.hyundai.values import PLATFORM_CODE_ECUS, get_platform_codes +from openpilot.selfdrive.car.hyundai.fingerprints import FW_VERSIONS + +Ecu = car.CarParams.Ecu +ECU_NAME = {v: k for k, v in Ecu.schema.enumerants.items()} + +if __name__ == "__main__": + for car_model, ecus in FW_VERSIONS.items(): + print() + print(car_model) + for ecu in sorted(ecus, key=lambda x: int(x[0])): + if ecu[0] not in PLATFORM_CODE_ECUS: + continue + + platform_codes = get_platform_codes(ecus[ecu]) + codes = {code for code, _ in platform_codes} + dates = {date for _, date in platform_codes if date is not None} + print(f' (Ecu.{ECU_NAME[ecu[0]]}, {hex(ecu[1])}, {ecu[2]}):') + print(f' Codes: {codes}') + print(f' Dates: {dates}') diff --git a/car/hyundai/tests/test_hyundai.py b/car/hyundai/tests/test_hyundai.py new file mode 100644 index 0000000000..4d31d7d15e --- /dev/null +++ b/car/hyundai/tests/test_hyundai.py @@ -0,0 +1,218 @@ +from hypothesis import settings, given, strategies as st + +import pytest + +from cereal import car +from openpilot.selfdrive.car.fw_versions import build_fw_dict +from openpilot.selfdrive.car.hyundai.values import CAMERA_SCC_CAR, CANFD_CAR, CAN_GEARS, CAR, CHECKSUM, DATE_FW_ECUS, \ + HYBRID_CAR, EV_CAR, FW_QUERY_CONFIG, LEGACY_SAFETY_MODE_CAR, CANFD_FUZZY_WHITELIST, \ + UNSUPPORTED_LONGITUDINAL_CAR, PLATFORM_CODE_ECUS, HYUNDAI_VERSION_REQUEST_LONG, \ + get_platform_codes +from openpilot.selfdrive.car.hyundai.fingerprints import FW_VERSIONS + +Ecu = car.CarParams.Ecu +ECU_NAME = {v: k for k, v in Ecu.schema.enumerants.items()} + +# Some platforms have date codes in a different format we don't yet parse (or are missing). +# For now, assert list of expected missing date cars +NO_DATES_PLATFORMS = { + # CAN FD + CAR.KIA_SPORTAGE_5TH_GEN, + CAR.HYUNDAI_SANTA_CRUZ_1ST_GEN, + CAR.HYUNDAI_TUCSON_4TH_GEN, + # CAN + CAR.HYUNDAI_ELANTRA, + CAR.HYUNDAI_ELANTRA_GT_I30, + CAR.KIA_CEED, + CAR.KIA_FORTE, + CAR.KIA_OPTIMA_G4, + CAR.KIA_OPTIMA_G4_FL, + CAR.KIA_SORENTO, + CAR.HYUNDAI_KONA, + CAR.HYUNDAI_KONA_EV, + CAR.HYUNDAI_KONA_EV_2022, + CAR.HYUNDAI_KONA_HEV, + CAR.HYUNDAI_SONATA_LF, + CAR.HYUNDAI_VELOSTER, +} + +CANFD_EXPECTED_ECUS = {Ecu.fwdCamera, Ecu.fwdRadar} + + +class TestHyundaiFingerprint: + def test_can_features(self): + # Test no EV/HEV in any gear lists (should all use ELECT_GEAR) + assert set.union(*CAN_GEARS.values()) & (HYBRID_CAR | EV_CAR) == set() + + # Test CAN FD car not in CAN feature lists + can_specific_feature_list = set.union(*CAN_GEARS.values(), *CHECKSUM.values(), LEGACY_SAFETY_MODE_CAR, UNSUPPORTED_LONGITUDINAL_CAR, CAMERA_SCC_CAR) + for car_model in CANFD_CAR: + assert car_model not in can_specific_feature_list, "CAN FD car unexpectedly found in a CAN feature list" + + def test_hybrid_ev_sets(self): + assert HYBRID_CAR & EV_CAR == set(), "Shared cars between hybrid and EV" + assert CANFD_CAR & HYBRID_CAR == set(), "Hard coding CAN FD cars as hybrid is no longer supported" + + def test_canfd_ecu_whitelist(self): + # Asserts only expected Ecus can exist in database for CAN-FD cars + for car_model in CANFD_CAR: + ecus = {fw[0] for fw in FW_VERSIONS[car_model].keys()} + ecus_not_in_whitelist = ecus - CANFD_EXPECTED_ECUS + ecu_strings = ", ".join([f"Ecu.{ECU_NAME[ecu]}" for ecu in ecus_not_in_whitelist]) + assert len(ecus_not_in_whitelist) == 0, \ + f"{car_model}: Car model has unexpected ECUs: {ecu_strings}" + + def test_blacklisted_parts(self, subtests): + # Asserts no ECUs known to be shared across platforms exist in the database. + # Tucson having Santa Cruz camera and EPS for example + for car_model, ecus in FW_VERSIONS.items(): + with subtests.test(car_model=car_model.value): + if car_model == CAR.HYUNDAI_SANTA_CRUZ_1ST_GEN: + pytest.skip("Skip checking Santa Cruz for its parts") + + for code, _ in get_platform_codes(ecus[(Ecu.fwdCamera, 0x7c4, None)]): + if b"-" not in code: + continue + part = code.split(b"-")[1] + assert not part.startswith(b'CW'), "Car has bad part number" + + def test_correct_ecu_response_database(self, subtests): + """ + Assert standard responses for certain ECUs, since they can + respond to multiple queries with different data + """ + expected_fw_prefix = HYUNDAI_VERSION_REQUEST_LONG[1:] + for car_model, ecus in FW_VERSIONS.items(): + with subtests.test(car_model=car_model.value): + for ecu, fws in ecus.items(): + assert all(fw.startswith(expected_fw_prefix) for fw in fws), \ + f"FW from unexpected request in database: {(ecu, fws)}" + + @settings(max_examples=100) + @given(data=st.data()) + def test_platform_codes_fuzzy_fw(self, data): + """Ensure function doesn't raise an exception""" + fw_strategy = st.lists(st.binary()) + fws = data.draw(fw_strategy) + get_platform_codes(fws) + + def test_expected_platform_codes(self, subtests): + # Ensures we don't accidentally add multiple platform codes for a car unless it is intentional + for car_model, ecus in FW_VERSIONS.items(): + with subtests.test(car_model=car_model.value): + for ecu, fws in ecus.items(): + if ecu[0] not in PLATFORM_CODE_ECUS: + continue + + # Third and fourth character are usually EV/hybrid identifiers + codes = {code.split(b"-")[0][:2] for code, _ in get_platform_codes(fws)} + if car_model == CAR.HYUNDAI_PALISADE: + assert codes == {b"LX", b"ON"}, f"Car has unexpected platform codes: {car_model} {codes}" + elif car_model == CAR.HYUNDAI_KONA_EV and ecu[0] == Ecu.fwdCamera: + assert codes == {b"OE", b"OS"}, f"Car has unexpected platform codes: {car_model} {codes}" + else: + assert len(codes) == 1, f"Car has multiple platform codes: {car_model} {codes}" + + # Tests for platform codes, part numbers, and FW dates which Hyundai will use to fuzzy + # fingerprint in the absence of full FW matches: + def test_platform_code_ecus_available(self, subtests): + # TODO: add queries for these non-CAN FD cars to get EPS + no_eps_platforms = CANFD_CAR | {CAR.KIA_SORENTO, CAR.KIA_OPTIMA_G4, CAR.KIA_OPTIMA_G4_FL, CAR.KIA_OPTIMA_H, + CAR.KIA_OPTIMA_H_G4_FL, CAR.HYUNDAI_SONATA_LF, CAR.HYUNDAI_TUCSON, CAR.GENESIS_G90, CAR.GENESIS_G80, CAR.HYUNDAI_ELANTRA} + + # Asserts ECU keys essential for fuzzy fingerprinting are available on all platforms + for car_model, ecus in FW_VERSIONS.items(): + with subtests.test(car_model=car_model.value): + for platform_code_ecu in PLATFORM_CODE_ECUS: + if platform_code_ecu in (Ecu.fwdRadar, Ecu.eps) and car_model == CAR.HYUNDAI_GENESIS: + continue + if platform_code_ecu == Ecu.eps and car_model in no_eps_platforms: + continue + assert platform_code_ecu in [e[0] for e in ecus] + + def test_fw_format(self, subtests): + # Asserts: + # - every supported ECU FW version returns one platform code + # - every supported ECU FW version has a part number + # - expected parsing of ECU FW dates + + for car_model, ecus in FW_VERSIONS.items(): + with subtests.test(car_model=car_model.value): + for ecu, fws in ecus.items(): + if ecu[0] not in PLATFORM_CODE_ECUS: + continue + + codes = set() + for fw in fws: + result = get_platform_codes([fw]) + assert 1 == len(result), f"Unable to parse FW: {fw}" + codes |= result + + if ecu[0] not in DATE_FW_ECUS or car_model in NO_DATES_PLATFORMS: + assert all(date is None for _, date in codes) + else: + assert all(date is not None for _, date in codes) + + if car_model == CAR.HYUNDAI_GENESIS: + pytest.skip("No part numbers for car model") + + # Hyundai places the ECU part number in their FW versions, assert all parsable + # Some examples of valid formats: b"56310-L0010", b"56310L0010", b"56310/M6300" + assert all(b"-" in code for code, _ in codes), \ + f"FW does not have part number: {fw}" + + def test_platform_codes_spot_check(self): + # Asserts basic platform code parsing behavior for a few cases + results = get_platform_codes([b"\xf1\x00DH LKAS 1.1 -150210"]) + assert results == {(b"DH", b"150210")} + + # Some cameras and all radars do not have dates + results = get_platform_codes([b"\xf1\x00AEhe SCC H-CUP 1.01 1.01 96400-G2000 "]) + assert results == {(b"AEhe-G2000", None)} + + results = get_platform_codes([b"\xf1\x00CV1_ RDR ----- 1.00 1.01 99110-CV000 "]) + assert results == {(b"CV1-CV000", None)} + + results = get_platform_codes([ + b"\xf1\x00DH LKAS 1.1 -150210", + b"\xf1\x00AEhe SCC H-CUP 1.01 1.01 96400-G2000 ", + b"\xf1\x00CV1_ RDR ----- 1.00 1.01 99110-CV000 ", + ]) + assert results == {(b"DH", b"150210"), (b"AEhe-G2000", None), (b"CV1-CV000", None)} + + results = get_platform_codes([ + b"\xf1\x00LX2 MFC AT USA LHD 1.00 1.07 99211-S8100 220222", + b"\xf1\x00LX2 MFC AT USA LHD 1.00 1.08 99211-S8100 211103", + b"\xf1\x00ON MFC AT USA LHD 1.00 1.01 99211-S9100 190405", + b"\xf1\x00ON MFC AT USA LHD 1.00 1.03 99211-S9100 190720", + ]) + assert results == {(b"LX2-S8100", b"220222"), (b"LX2-S8100", b"211103"), + (b"ON-S9100", b"190405"), (b"ON-S9100", b"190720")} + + def test_fuzzy_excluded_platforms(self): + # Asserts a list of platforms that will not fuzzy fingerprint with platform codes due to them being shared. + # This list can be shrunk as we combine platforms and detect features + excluded_platforms = { + CAR.GENESIS_G70, # shared platform code, part number, and date + CAR.GENESIS_G70_2020, + } + excluded_platforms |= CANFD_CAR - EV_CAR - CANFD_FUZZY_WHITELIST # shared platform codes + excluded_platforms |= NO_DATES_PLATFORMS # date codes are required to match + + platforms_with_shared_codes = set() + for platform, fw_by_addr in FW_VERSIONS.items(): + car_fw = [] + for ecu, fw_versions in fw_by_addr.items(): + ecu_name, addr, sub_addr = ecu + for fw in fw_versions: + car_fw.append({"ecu": ecu_name, "fwVersion": fw, "address": addr, + "subAddress": 0 if sub_addr is None else sub_addr}) + + CP = car.CarParams.new_message(carFw=car_fw) + matches = FW_QUERY_CONFIG.match_fw_to_car_fuzzy(build_fw_dict(CP.carFw), CP.carVin, FW_VERSIONS) + if len(matches) == 1: + assert list(matches)[0] == platform + else: + platforms_with_shared_codes.add(platform) + + assert platforms_with_shared_codes == excluded_platforms diff --git a/car/hyundai/values.py b/car/hyundai/values.py new file mode 100644 index 0000000000..c489ea0042 --- /dev/null +++ b/car/hyundai/values.py @@ -0,0 +1,751 @@ +import re +from dataclasses import dataclass, field +from enum import Enum, IntFlag + +from cereal import car +from panda.python import uds +from openpilot.common.conversions import Conversions as CV +from openpilot.selfdrive.car import CarSpecs, DbcDict, PlatformConfig, Platforms, dbc_dict +from openpilot.selfdrive.car.docs_definitions import CarFootnote, CarHarness, CarDocs, CarParts, Column +from openpilot.selfdrive.car.fw_query_definitions import FwQueryConfig, Request, p16 + +Ecu = car.CarParams.Ecu + + +class CarControllerParams: + ACCEL_MIN = -3.5 # m/s + ACCEL_MAX = 2.0 # m/s + + def __init__(self, CP): + self.STEER_DELTA_UP = 3 + self.STEER_DELTA_DOWN = 7 + self.STEER_DRIVER_ALLOWANCE = 50 + self.STEER_DRIVER_MULTIPLIER = 2 + self.STEER_DRIVER_FACTOR = 1 + self.STEER_THRESHOLD = 150 + self.STEER_STEP = 1 # 100 Hz + + if CP.carFingerprint in CANFD_CAR: + self.STEER_MAX = 270 + self.STEER_DRIVER_ALLOWANCE = 250 + self.STEER_DRIVER_MULTIPLIER = 2 + self.STEER_THRESHOLD = 250 + self.STEER_DELTA_UP = 2 + self.STEER_DELTA_DOWN = 3 + + # To determine the limit for your car, find the maximum value that the stock LKAS will request. + # If the max stock LKAS request is <384, add your car to this list. + elif CP.carFingerprint in (CAR.GENESIS_G80, CAR.GENESIS_G90, CAR.HYUNDAI_ELANTRA, CAR.HYUNDAI_ELANTRA_GT_I30, CAR.HYUNDAI_IONIQ, + CAR.HYUNDAI_IONIQ_EV_LTD, CAR.HYUNDAI_SANTA_FE_PHEV_2022, CAR.HYUNDAI_SONATA_LF, CAR.KIA_FORTE, CAR.KIA_NIRO_PHEV, + CAR.KIA_OPTIMA_H, CAR.KIA_OPTIMA_H_G4_FL, CAR.KIA_SORENTO): + self.STEER_MAX = 255 + + # these cars have significantly more torque than most HKG; limit to 70% of max + elif CP.flags & HyundaiFlags.ALT_LIMITS: + self.STEER_MAX = 270 + self.STEER_DELTA_UP = 2 + self.STEER_DELTA_DOWN = 3 + + # Default for most HKG + else: + self.STEER_MAX = 384 + + +class HyundaiFlags(IntFlag): + # Dynamic Flags + CANFD_HDA2 = 1 + CANFD_ALT_BUTTONS = 2 + CANFD_ALT_GEARS = 2 ** 2 + CANFD_CAMERA_SCC = 2 ** 3 + + ALT_LIMITS = 2 ** 4 + ENABLE_BLINKERS = 2 ** 5 + CANFD_ALT_GEARS_2 = 2 ** 6 + SEND_LFA = 2 ** 7 + USE_FCA = 2 ** 8 + CANFD_HDA2_ALT_STEERING = 2 ** 9 + + # these cars use a different gas signal + HYBRID = 2 ** 10 + EV = 2 ** 11 + + # Static flags + + # If 0x500 is present on bus 1 it probably has a Mando radar outputting radar points. + # If no points are outputted by default it might be possible to turn it on using selfdrive/debug/hyundai_enable_radar_points.py + MANDO_RADAR = 2 ** 12 + CANFD = 2 ** 13 + + # The radar does SCC on these cars when HDA I, rather than the camera + RADAR_SCC = 2 ** 14 + CAMERA_SCC = 2 ** 15 + CHECKSUM_CRC8 = 2 ** 16 + CHECKSUM_6B = 2 ** 17 + + # these cars require a special panda safety mode due to missing counters and checksums in the messages + LEGACY = 2 ** 18 + + # these cars have not been verified to work with longitudinal yet - radar disable, sending correct messages, etc. + UNSUPPORTED_LONGITUDINAL = 2 ** 19 + + CANFD_NO_RADAR_DISABLE = 2 ** 20 + + CLUSTER_GEARS = 2 ** 21 + TCU_GEARS = 2 ** 22 + + MIN_STEER_32_MPH = 2 ** 23 + + +class Footnote(Enum): + CANFD = CarFootnote( + "Requires a CAN FD panda kit if not using " + + "comma 3X for this CAN FD car.", + Column.MODEL, shop_footnote=False) + + +@dataclass +class HyundaiCarDocs(CarDocs): + package: str = "Smart Cruise Control (SCC)" + + def init_make(self, CP: car.CarParams): + if CP.flags & HyundaiFlags.CANFD: + self.footnotes.insert(0, Footnote.CANFD) + + +@dataclass +class HyundaiPlatformConfig(PlatformConfig): + dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict("hyundai_kia_generic", None)) + + def init(self): + if self.flags & HyundaiFlags.MANDO_RADAR: + self.dbc_dict = dbc_dict('hyundai_kia_generic', 'hyundai_kia_mando_front_radar_generated') + + if self.flags & HyundaiFlags.MIN_STEER_32_MPH: + self.specs = self.specs.override(minSteerSpeed=32 * CV.MPH_TO_MS) + + +@dataclass +class HyundaiCanFDPlatformConfig(PlatformConfig): + dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict("hyundai_canfd", None)) + + def init(self): + self.flags |= HyundaiFlags.CANFD + + +class CAR(Platforms): + # Hyundai + HYUNDAI_AZERA_6TH_GEN = HyundaiPlatformConfig( + [HyundaiCarDocs("Hyundai Azera 2022", "All", car_parts=CarParts.common([CarHarness.hyundai_k]))], + CarSpecs(mass=1600, wheelbase=2.885, steerRatio=14.5), + ) + HYUNDAI_AZERA_HEV_6TH_GEN = HyundaiPlatformConfig( + [ + HyundaiCarDocs("Hyundai Azera Hybrid 2019", "All", car_parts=CarParts.common([CarHarness.hyundai_c])), + HyundaiCarDocs("Hyundai Azera Hybrid 2020", "All", car_parts=CarParts.common([CarHarness.hyundai_k])), + ], + CarSpecs(mass=1675, wheelbase=2.885, steerRatio=14.5), + flags=HyundaiFlags.HYBRID, + ) + HYUNDAI_ELANTRA = HyundaiPlatformConfig( + [ + # TODO: 2017-18 could be Hyundai G + HyundaiCarDocs("Hyundai Elantra 2017-18", min_enable_speed=19 * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_b])), + HyundaiCarDocs("Hyundai Elantra 2019", min_enable_speed=19 * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_g])), + ], + # steerRatio: 14 is Stock | Settled Params Learner values are steerRatio: 15.401566348670535, stiffnessFactor settled on 1.0081302973865127 + CarSpecs(mass=1275, wheelbase=2.7, steerRatio=15.4, tireStiffnessFactor=0.385), + flags=HyundaiFlags.LEGACY | HyundaiFlags.CLUSTER_GEARS | HyundaiFlags.MIN_STEER_32_MPH, + ) + HYUNDAI_ELANTRA_GT_I30 = HyundaiPlatformConfig( + [ + HyundaiCarDocs("Hyundai Elantra GT 2017-19", car_parts=CarParts.common([CarHarness.hyundai_e])), + HyundaiCarDocs("Hyundai i30 2017-19", car_parts=CarParts.common([CarHarness.hyundai_e])), + ], + HYUNDAI_ELANTRA.specs, + flags=HyundaiFlags.LEGACY | HyundaiFlags.CLUSTER_GEARS | HyundaiFlags.MIN_STEER_32_MPH, + ) + HYUNDAI_ELANTRA_2021 = HyundaiPlatformConfig( + [HyundaiCarDocs("Hyundai Elantra 2021-23", video_link="https://youtu.be/_EdYQtV52-c", car_parts=CarParts.common([CarHarness.hyundai_k]))], + CarSpecs(mass=2800 * CV.LB_TO_KG, wheelbase=2.72, steerRatio=12.9, tireStiffnessFactor=0.65), + flags=HyundaiFlags.CHECKSUM_CRC8, + ) + HYUNDAI_ELANTRA_HEV_2021 = HyundaiPlatformConfig( + [HyundaiCarDocs("Hyundai Elantra Hybrid 2021-23", video_link="https://youtu.be/_EdYQtV52-c", + car_parts=CarParts.common([CarHarness.hyundai_k]))], + CarSpecs(mass=3017 * CV.LB_TO_KG, wheelbase=2.72, steerRatio=12.9, tireStiffnessFactor=0.65), + flags=HyundaiFlags.CHECKSUM_CRC8 | HyundaiFlags.HYBRID, + ) + HYUNDAI_GENESIS = HyundaiPlatformConfig( + [ + # TODO: check 2015 packages + HyundaiCarDocs("Hyundai Genesis 2015-16", min_enable_speed=19 * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_j])), + HyundaiCarDocs("Genesis G80 2017", "All", min_enable_speed=19 * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_j])), + ], + CarSpecs(mass=2060, wheelbase=3.01, steerRatio=16.5, minSteerSpeed=60 * CV.KPH_TO_MS), + flags=HyundaiFlags.CHECKSUM_6B | HyundaiFlags.LEGACY, + ) + HYUNDAI_IONIQ = HyundaiPlatformConfig( + [HyundaiCarDocs("Hyundai Ioniq Hybrid 2017-19", car_parts=CarParts.common([CarHarness.hyundai_c]))], + CarSpecs(mass=1490, wheelbase=2.7, steerRatio=13.73, tireStiffnessFactor=0.385), + flags=HyundaiFlags.HYBRID | HyundaiFlags.MIN_STEER_32_MPH, + ) + HYUNDAI_IONIQ_HEV_2022 = HyundaiPlatformConfig( + [HyundaiCarDocs("Hyundai Ioniq Hybrid 2020-22", car_parts=CarParts.common([CarHarness.hyundai_h]))], # TODO: confirm 2020-21 harness, + CarSpecs(mass=1490, wheelbase=2.7, steerRatio=13.73, tireStiffnessFactor=0.385), + flags=HyundaiFlags.HYBRID | HyundaiFlags.LEGACY, + ) + HYUNDAI_IONIQ_EV_LTD = HyundaiPlatformConfig( + [HyundaiCarDocs("Hyundai Ioniq Electric 2019", car_parts=CarParts.common([CarHarness.hyundai_c]))], + CarSpecs(mass=1490, wheelbase=2.7, steerRatio=13.73, tireStiffnessFactor=0.385), + flags=HyundaiFlags.MANDO_RADAR | HyundaiFlags.EV | HyundaiFlags.LEGACY | HyundaiFlags.MIN_STEER_32_MPH, + ) + HYUNDAI_IONIQ_EV_2020 = HyundaiPlatformConfig( + [HyundaiCarDocs("Hyundai Ioniq Electric 2020", "All", car_parts=CarParts.common([CarHarness.hyundai_h]))], + CarSpecs(mass=1490, wheelbase=2.7, steerRatio=13.73, tireStiffnessFactor=0.385), + flags=HyundaiFlags.EV, + ) + HYUNDAI_IONIQ_PHEV_2019 = HyundaiPlatformConfig( + [HyundaiCarDocs("Hyundai Ioniq Plug-in Hybrid 2019", car_parts=CarParts.common([CarHarness.hyundai_c]))], + CarSpecs(mass=1490, wheelbase=2.7, steerRatio=13.73, tireStiffnessFactor=0.385), + flags=HyundaiFlags.HYBRID | HyundaiFlags.MIN_STEER_32_MPH, + ) + HYUNDAI_IONIQ_PHEV = HyundaiPlatformConfig( + [HyundaiCarDocs("Hyundai Ioniq Plug-in Hybrid 2020-22", "All", car_parts=CarParts.common([CarHarness.hyundai_h]))], + CarSpecs(mass=1490, wheelbase=2.7, steerRatio=13.73, tireStiffnessFactor=0.385), + flags=HyundaiFlags.HYBRID, + ) + HYUNDAI_KONA = HyundaiPlatformConfig( + [HyundaiCarDocs("Hyundai Kona 2020", min_enable_speed=6 * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_b]))], + CarSpecs(mass=1275, wheelbase=2.6, steerRatio=13.42, tireStiffnessFactor=0.385), + flags=HyundaiFlags.CLUSTER_GEARS, + ) + HYUNDAI_KONA_EV = HyundaiPlatformConfig( + [HyundaiCarDocs("Hyundai Kona Electric 2018-21", car_parts=CarParts.common([CarHarness.hyundai_g]))], + CarSpecs(mass=1685, wheelbase=2.6, steerRatio=13.42, tireStiffnessFactor=0.385), + flags=HyundaiFlags.EV, + ) + HYUNDAI_KONA_EV_2022 = HyundaiPlatformConfig( + [HyundaiCarDocs("Hyundai Kona Electric 2022-23", car_parts=CarParts.common([CarHarness.hyundai_o]))], + CarSpecs(mass=1743, wheelbase=2.6, steerRatio=13.42, tireStiffnessFactor=0.385), + flags=HyundaiFlags.CAMERA_SCC | HyundaiFlags.EV, + ) + HYUNDAI_KONA_EV_2ND_GEN = HyundaiCanFDPlatformConfig( + [HyundaiCarDocs("Hyundai Kona Electric (with HDA II, Korea only) 2023", video_link="https://www.youtube.com/watch?v=U2fOCmcQ8hw", + car_parts=CarParts.common([CarHarness.hyundai_r]))], + CarSpecs(mass=1740, wheelbase=2.66, steerRatio=13.6, tireStiffnessFactor=0.385), + flags=HyundaiFlags.EV | HyundaiFlags.CANFD_NO_RADAR_DISABLE, + ) + HYUNDAI_KONA_HEV = HyundaiPlatformConfig( + [HyundaiCarDocs("Hyundai Kona Hybrid 2020", car_parts=CarParts.common([CarHarness.hyundai_i]))], # TODO: check packages, + CarSpecs(mass=1425, wheelbase=2.6, steerRatio=13.42, tireStiffnessFactor=0.385), + flags=HyundaiFlags.HYBRID, + ) + HYUNDAI_SANTA_FE = HyundaiPlatformConfig( + [HyundaiCarDocs("Hyundai Santa Fe 2019-20", "All", video_link="https://youtu.be/bjDR0YjM__s", + car_parts=CarParts.common([CarHarness.hyundai_d]))], + CarSpecs(mass=3982 * CV.LB_TO_KG, wheelbase=2.766, steerRatio=16.55, tireStiffnessFactor=0.82), + flags=HyundaiFlags.MANDO_RADAR | HyundaiFlags.CHECKSUM_CRC8, + ) + HYUNDAI_SANTA_FE_2022 = HyundaiPlatformConfig( + [HyundaiCarDocs("Hyundai Santa Fe 2021-23", "All", video_link="https://youtu.be/VnHzSTygTS4", + car_parts=CarParts.common([CarHarness.hyundai_l]))], + HYUNDAI_SANTA_FE.specs, + flags=HyundaiFlags.CHECKSUM_CRC8, + ) + HYUNDAI_SANTA_FE_HEV_2022 = HyundaiPlatformConfig( + [HyundaiCarDocs("Hyundai Santa Fe Hybrid 2022-23", "All", car_parts=CarParts.common([CarHarness.hyundai_l]))], + HYUNDAI_SANTA_FE.specs, + flags=HyundaiFlags.CHECKSUM_CRC8 | HyundaiFlags.HYBRID, + ) + HYUNDAI_SANTA_FE_PHEV_2022 = HyundaiPlatformConfig( + [HyundaiCarDocs("Hyundai Santa Fe Plug-in Hybrid 2022-23", "All", car_parts=CarParts.common([CarHarness.hyundai_l]))], + HYUNDAI_SANTA_FE.specs, + flags=HyundaiFlags.CHECKSUM_CRC8 | HyundaiFlags.HYBRID, + ) + HYUNDAI_SONATA = HyundaiPlatformConfig( + [HyundaiCarDocs("Hyundai Sonata 2020-23", "All", video_link="https://www.youtube.com/watch?v=ix63r9kE3Fw", + car_parts=CarParts.common([CarHarness.hyundai_a]))], + CarSpecs(mass=1513, wheelbase=2.84, steerRatio=13.27 * 1.15, tireStiffnessFactor=0.65), # 15% higher at the center seems reasonable + flags=HyundaiFlags.MANDO_RADAR | HyundaiFlags.CHECKSUM_CRC8, + ) + HYUNDAI_SONATA_LF = HyundaiPlatformConfig( + [HyundaiCarDocs("Hyundai Sonata 2018-19", car_parts=CarParts.common([CarHarness.hyundai_e]))], + CarSpecs(mass=1536, wheelbase=2.804, steerRatio=13.27 * 1.15), # 15% higher at the center seems reasonable + + flags=HyundaiFlags.UNSUPPORTED_LONGITUDINAL | HyundaiFlags.TCU_GEARS, + ) + HYUNDAI_STARIA_4TH_GEN = HyundaiCanFDPlatformConfig( + [HyundaiCarDocs("Hyundai Staria 2023", "All", car_parts=CarParts.common([CarHarness.hyundai_k]))], + CarSpecs(mass=2205, wheelbase=3.273, steerRatio=11.94), # https://www.hyundai.com/content/dam/hyundai/au/en/models/staria-load/premium-pip-update-2023/spec-sheet/STARIA_Load_Spec-Table_March_2023_v3.1.pdf + ) + HYUNDAI_TUCSON = HyundaiPlatformConfig( + [ + HyundaiCarDocs("Hyundai Tucson 2021", min_enable_speed=19 * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_l])), + HyundaiCarDocs("Hyundai Tucson Diesel 2019", car_parts=CarParts.common([CarHarness.hyundai_l])), + ], + CarSpecs(mass=3520 * CV.LB_TO_KG, wheelbase=2.67, steerRatio=16.1, tireStiffnessFactor=0.385), + flags=HyundaiFlags.TCU_GEARS, + ) + HYUNDAI_PALISADE = HyundaiPlatformConfig( + [ + HyundaiCarDocs("Hyundai Palisade 2020-22", "All", video_link="https://youtu.be/TAnDqjF4fDY?t=456", car_parts=CarParts.common([CarHarness.hyundai_h])), + HyundaiCarDocs("Kia Telluride 2020-22", "All", car_parts=CarParts.common([CarHarness.hyundai_h])), + ], + CarSpecs(mass=1999, wheelbase=2.9, steerRatio=15.6 * 1.15, tireStiffnessFactor=0.63), + flags=HyundaiFlags.MANDO_RADAR | HyundaiFlags.CHECKSUM_CRC8, + ) + HYUNDAI_VELOSTER = HyundaiPlatformConfig( + [HyundaiCarDocs("Hyundai Veloster 2019-20", min_enable_speed=5. * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_e]))], + CarSpecs(mass=2917 * CV.LB_TO_KG, wheelbase=2.8, steerRatio=13.75 * 1.15, tireStiffnessFactor=0.5), + flags=HyundaiFlags.LEGACY | HyundaiFlags.TCU_GEARS, + ) + HYUNDAI_SONATA_HYBRID = HyundaiPlatformConfig( + [HyundaiCarDocs("Hyundai Sonata Hybrid 2020-23", "All", car_parts=CarParts.common([CarHarness.hyundai_a]))], + HYUNDAI_SONATA.specs, + flags=HyundaiFlags.MANDO_RADAR | HyundaiFlags.CHECKSUM_CRC8 | HyundaiFlags.HYBRID, + ) + HYUNDAI_IONIQ_5 = HyundaiCanFDPlatformConfig( + [ + HyundaiCarDocs("Hyundai Ioniq 5 (Southeast Asia only) 2022-23", "All", car_parts=CarParts.common([CarHarness.hyundai_q])), + HyundaiCarDocs("Hyundai Ioniq 5 (without HDA II) 2022-23", "Highway Driving Assist", car_parts=CarParts.common([CarHarness.hyundai_k])), + HyundaiCarDocs("Hyundai Ioniq 5 (with HDA II) 2022-23", "Highway Driving Assist II", car_parts=CarParts.common([CarHarness.hyundai_q])), + ], + CarSpecs(mass=1948, wheelbase=2.97, steerRatio=14.26, tireStiffnessFactor=0.65), + flags=HyundaiFlags.EV, + ) + HYUNDAI_IONIQ_6 = HyundaiCanFDPlatformConfig( + [HyundaiCarDocs("Hyundai Ioniq 6 (with HDA II) 2023-24", "Highway Driving Assist II", car_parts=CarParts.common([CarHarness.hyundai_p]))], + HYUNDAI_IONIQ_5.specs, + flags=HyundaiFlags.EV | HyundaiFlags.CANFD_NO_RADAR_DISABLE, + ) + HYUNDAI_TUCSON_4TH_GEN = HyundaiCanFDPlatformConfig( + [ + HyundaiCarDocs("Hyundai Tucson 2022", car_parts=CarParts.common([CarHarness.hyundai_n])), + HyundaiCarDocs("Hyundai Tucson 2023-24", "All", car_parts=CarParts.common([CarHarness.hyundai_n])), + HyundaiCarDocs("Hyundai Tucson Hybrid 2022-24", "All", car_parts=CarParts.common([CarHarness.hyundai_n])), + HyundaiCarDocs("Hyundai Tucson Plug-in Hybrid 2024", "All", car_parts=CarParts.common([CarHarness.hyundai_n])), + ], + CarSpecs(mass=1630, wheelbase=2.756, steerRatio=13.7, tireStiffnessFactor=0.385), + ) + HYUNDAI_SANTA_CRUZ_1ST_GEN = HyundaiCanFDPlatformConfig( + [HyundaiCarDocs("Hyundai Santa Cruz 2022-24", car_parts=CarParts.common([CarHarness.hyundai_n]))], + # weight from Limited trim - the only supported trim, steering ratio according to Hyundai News https://www.hyundainews.com/assets/documents/original/48035-2022SantaCruzProductGuideSpecsv2081521.pdf + CarSpecs(mass=1870, wheelbase=3, steerRatio=14.2), + ) + HYUNDAI_CUSTIN_1ST_GEN = HyundaiPlatformConfig( + [HyundaiCarDocs("Hyundai Custin 2023", "All", car_parts=CarParts.common([CarHarness.hyundai_k]))], + CarSpecs(mass=1690, wheelbase=3.055, steerRatio=17), # mass: from https://www.hyundai-motor.com.tw/clicktobuy/custin#spec_0, steerRatio: from learner + flags=HyundaiFlags.CHECKSUM_CRC8, + ) + + # Kia + KIA_FORTE = HyundaiPlatformConfig( + [ + HyundaiCarDocs("Kia Forte 2019-21", min_enable_speed=6 * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_g])), + HyundaiCarDocs("Kia Forte 2022-23", car_parts=CarParts.common([CarHarness.hyundai_e])), + ], + CarSpecs(mass=2878 * CV.LB_TO_KG, wheelbase=2.8, steerRatio=13.75, tireStiffnessFactor=0.5) + ) + KIA_K5_2021 = HyundaiPlatformConfig( + [HyundaiCarDocs("Kia K5 2021-24", car_parts=CarParts.common([CarHarness.hyundai_a]))], + CarSpecs(mass=3381 * CV.LB_TO_KG, wheelbase=2.85, steerRatio=13.27, tireStiffnessFactor=0.5), # 2021 Kia K5 Steering Ratio (all trims) + flags=HyundaiFlags.CHECKSUM_CRC8, + ) + KIA_K5_HEV_2020 = HyundaiPlatformConfig( + [HyundaiCarDocs("Kia K5 Hybrid 2020-22", car_parts=CarParts.common([CarHarness.hyundai_a]))], + KIA_K5_2021.specs, + flags=HyundaiFlags.MANDO_RADAR | HyundaiFlags.CHECKSUM_CRC8 | HyundaiFlags.HYBRID, + ) + KIA_K8_HEV_1ST_GEN = HyundaiCanFDPlatformConfig( + [HyundaiCarDocs("Kia K8 Hybrid (with HDA II) 2023", "Highway Driving Assist II", car_parts=CarParts.common([CarHarness.hyundai_q]))], + # mass: https://carprices.ae/brands/kia/2023/k8/1.6-turbo-hybrid, steerRatio: guesstimate from K5 platform + CarSpecs(mass=1630, wheelbase=2.895, steerRatio=13.27) + ) + KIA_NIRO_EV = HyundaiPlatformConfig( + [ + HyundaiCarDocs("Kia Niro EV 2019", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", car_parts=CarParts.common([CarHarness.hyundai_h])), + HyundaiCarDocs("Kia Niro EV 2020", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", car_parts=CarParts.common([CarHarness.hyundai_f])), + HyundaiCarDocs("Kia Niro EV 2021", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", car_parts=CarParts.common([CarHarness.hyundai_c])), + HyundaiCarDocs("Kia Niro EV 2022", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", car_parts=CarParts.common([CarHarness.hyundai_h])), + ], + CarSpecs(mass=3543 * CV.LB_TO_KG, wheelbase=2.7, steerRatio=13.6, tireStiffnessFactor=0.385), # average of all the cars + flags=HyundaiFlags.MANDO_RADAR | HyundaiFlags.EV, + ) + KIA_NIRO_EV_2ND_GEN = HyundaiCanFDPlatformConfig( + [HyundaiCarDocs("Kia Niro EV 2023", "All", car_parts=CarParts.common([CarHarness.hyundai_a]))], + KIA_NIRO_EV.specs, + flags=HyundaiFlags.EV, + ) + KIA_NIRO_PHEV = HyundaiPlatformConfig( + [ + HyundaiCarDocs("Kia Niro Hybrid 2018", "All", min_enable_speed=10. * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_c])), + HyundaiCarDocs("Kia Niro Plug-in Hybrid 2018-19", "All", min_enable_speed=10. * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_c])), + HyundaiCarDocs("Kia Niro Plug-in Hybrid 2020", car_parts=CarParts.common([CarHarness.hyundai_d])), + ], + KIA_NIRO_EV.specs, + flags=HyundaiFlags.MANDO_RADAR | HyundaiFlags.HYBRID | HyundaiFlags.UNSUPPORTED_LONGITUDINAL | HyundaiFlags.MIN_STEER_32_MPH, + ) + KIA_NIRO_PHEV_2022 = HyundaiPlatformConfig( + [ + HyundaiCarDocs("Kia Niro Plug-in Hybrid 2021", car_parts=CarParts.common([CarHarness.hyundai_d])), + HyundaiCarDocs("Kia Niro Plug-in Hybrid 2022", car_parts=CarParts.common([CarHarness.hyundai_f])), + ], + KIA_NIRO_EV.specs, + flags=HyundaiFlags.HYBRID | HyundaiFlags.MANDO_RADAR, + ) + KIA_NIRO_HEV_2021 = HyundaiPlatformConfig( + [ + HyundaiCarDocs("Kia Niro Hybrid 2021", car_parts=CarParts.common([CarHarness.hyundai_d])), + HyundaiCarDocs("Kia Niro Hybrid 2022", car_parts=CarParts.common([CarHarness.hyundai_f])), + ], + KIA_NIRO_EV.specs, + flags=HyundaiFlags.HYBRID, + ) + KIA_NIRO_HEV_2ND_GEN = HyundaiCanFDPlatformConfig( + [HyundaiCarDocs("Kia Niro Hybrid 2023", car_parts=CarParts.common([CarHarness.hyundai_a]))], + KIA_NIRO_EV.specs, + ) + KIA_OPTIMA_G4 = HyundaiPlatformConfig( + [HyundaiCarDocs("Kia Optima 2017", "Advanced Smart Cruise Control", + car_parts=CarParts.common([CarHarness.hyundai_b]))], # TODO: may support 2016, 2018 + CarSpecs(mass=3558 * CV.LB_TO_KG, wheelbase=2.8, steerRatio=13.75, tireStiffnessFactor=0.5), + flags=HyundaiFlags.LEGACY | HyundaiFlags.TCU_GEARS | HyundaiFlags.MIN_STEER_32_MPH, + ) + KIA_OPTIMA_G4_FL = HyundaiPlatformConfig( + [HyundaiCarDocs("Kia Optima 2019-20", car_parts=CarParts.common([CarHarness.hyundai_g]))], + CarSpecs(mass=3558 * CV.LB_TO_KG, wheelbase=2.8, steerRatio=13.75, tireStiffnessFactor=0.5), + flags=HyundaiFlags.UNSUPPORTED_LONGITUDINAL | HyundaiFlags.TCU_GEARS, + ) + # TODO: may support adjacent years. may have a non-zero minimum steering speed + KIA_OPTIMA_H = HyundaiPlatformConfig( + [HyundaiCarDocs("Kia Optima Hybrid 2017", "Advanced Smart Cruise Control", car_parts=CarParts.common([CarHarness.hyundai_c]))], + CarSpecs(mass=3558 * CV.LB_TO_KG, wheelbase=2.8, steerRatio=13.75, tireStiffnessFactor=0.5), + flags=HyundaiFlags.HYBRID | HyundaiFlags.LEGACY, + ) + KIA_OPTIMA_H_G4_FL = HyundaiPlatformConfig( + [HyundaiCarDocs("Kia Optima Hybrid 2019", car_parts=CarParts.common([CarHarness.hyundai_h]))], + CarSpecs(mass=3558 * CV.LB_TO_KG, wheelbase=2.8, steerRatio=13.75, tireStiffnessFactor=0.5), + flags=HyundaiFlags.HYBRID | HyundaiFlags.UNSUPPORTED_LONGITUDINAL, + ) + KIA_SELTOS = HyundaiPlatformConfig( + [HyundaiCarDocs("Kia Seltos 2021", car_parts=CarParts.common([CarHarness.hyundai_a]))], + CarSpecs(mass=1337, wheelbase=2.63, steerRatio=14.56), + flags=HyundaiFlags.CHECKSUM_CRC8, + ) + KIA_SPORTAGE_5TH_GEN = HyundaiCanFDPlatformConfig( + [ + HyundaiCarDocs("Kia Sportage 2023-24", car_parts=CarParts.common([CarHarness.hyundai_n])), + HyundaiCarDocs("Kia Sportage Hybrid 2023", car_parts=CarParts.common([CarHarness.hyundai_n])), + ], + # weight from SX and above trims, average of FWD and AWD version, steering ratio according to Kia News https://www.kiamedia.com/us/en/models/sportage/2023/specifications + CarSpecs(mass=1725, wheelbase=2.756, steerRatio=13.6), + ) + KIA_SORENTO = HyundaiPlatformConfig( + [ + HyundaiCarDocs("Kia Sorento 2018", "Advanced Smart Cruise Control & LKAS", video_link="https://www.youtube.com/watch?v=Fkh3s6WHJz8", + car_parts=CarParts.common([CarHarness.hyundai_e])), + HyundaiCarDocs("Kia Sorento 2019", video_link="https://www.youtube.com/watch?v=Fkh3s6WHJz8", car_parts=CarParts.common([CarHarness.hyundai_e])), + ], + CarSpecs(mass=1985, wheelbase=2.78, steerRatio=14.4 * 1.1), # 10% higher at the center seems reasonable + flags=HyundaiFlags.CHECKSUM_6B | HyundaiFlags.UNSUPPORTED_LONGITUDINAL, + ) + KIA_SORENTO_4TH_GEN = HyundaiCanFDPlatformConfig( + [HyundaiCarDocs("Kia Sorento 2021-23", car_parts=CarParts.common([CarHarness.hyundai_k]))], + CarSpecs(mass=3957 * CV.LB_TO_KG, wheelbase=2.81, steerRatio=13.5), # average of the platforms + flags=HyundaiFlags.RADAR_SCC, + ) + KIA_SORENTO_HEV_4TH_GEN = HyundaiCanFDPlatformConfig( + [ + HyundaiCarDocs("Kia Sorento Hybrid 2021-23", "All", car_parts=CarParts.common([CarHarness.hyundai_a])), + HyundaiCarDocs("Kia Sorento Plug-in Hybrid 2022-23", "All", car_parts=CarParts.common([CarHarness.hyundai_a])), + ], + CarSpecs(mass=4395 * CV.LB_TO_KG, wheelbase=2.81, steerRatio=13.5), # average of the platforms + flags=HyundaiFlags.RADAR_SCC, + ) + KIA_STINGER = HyundaiPlatformConfig( + [HyundaiCarDocs("Kia Stinger 2018-20", video_link="https://www.youtube.com/watch?v=MJ94qoofYw0", + car_parts=CarParts.common([CarHarness.hyundai_c]))], + CarSpecs(mass=1825, wheelbase=2.78, steerRatio=14.4 * 1.15) # 15% higher at the center seems reasonable + ) + KIA_STINGER_2022 = HyundaiPlatformConfig( + [HyundaiCarDocs("Kia Stinger 2022-23", "All", car_parts=CarParts.common([CarHarness.hyundai_k]))], + KIA_STINGER.specs, + ) + KIA_CEED = HyundaiPlatformConfig( + [HyundaiCarDocs("Kia Ceed 2019", car_parts=CarParts.common([CarHarness.hyundai_e]))], + CarSpecs(mass=1450, wheelbase=2.65, steerRatio=13.75, tireStiffnessFactor=0.5), + flags=HyundaiFlags.LEGACY, + ) + KIA_EV6 = HyundaiCanFDPlatformConfig( + [ + HyundaiCarDocs("Kia EV6 (Southeast Asia only) 2022-24", "All", car_parts=CarParts.common([CarHarness.hyundai_p])), + HyundaiCarDocs("Kia EV6 (without HDA II) 2022-24", "Highway Driving Assist", car_parts=CarParts.common([CarHarness.hyundai_l])), + HyundaiCarDocs("Kia EV6 (with HDA II) 2022-24", "Highway Driving Assist II", car_parts=CarParts.common([CarHarness.hyundai_p])) + ], + CarSpecs(mass=2055, wheelbase=2.9, steerRatio=16, tireStiffnessFactor=0.65), + flags=HyundaiFlags.EV, + ) + KIA_CARNIVAL_4TH_GEN = HyundaiCanFDPlatformConfig( + [ + HyundaiCarDocs("Kia Carnival 2022-24", car_parts=CarParts.common([CarHarness.hyundai_a])), + HyundaiCarDocs("Kia Carnival (China only) 2023", car_parts=CarParts.common([CarHarness.hyundai_k])) + ], + CarSpecs(mass=2087, wheelbase=3.09, steerRatio=14.23), + flags=HyundaiFlags.RADAR_SCC, + ) + + # Genesis + GENESIS_GV60_EV_1ST_GEN = HyundaiCanFDPlatformConfig( + [ + HyundaiCarDocs("Genesis GV60 (Advanced Trim) 2023", "All", car_parts=CarParts.common([CarHarness.hyundai_a])), + HyundaiCarDocs("Genesis GV60 (Performance Trim) 2023", "All", car_parts=CarParts.common([CarHarness.hyundai_k])), + ], + CarSpecs(mass=2205, wheelbase=2.9, steerRatio=12.6), # steerRatio: https://www.motor1.com/reviews/586376/2023-genesis-gv60-first-drive/#:~:text=Relative%20to%20the%20related%20Ioniq,5%2FEV6%27s%2014.3%3A1. + flags=HyundaiFlags.EV, + ) + GENESIS_G70 = HyundaiPlatformConfig( + [HyundaiCarDocs("Genesis G70 2018", "All", car_parts=CarParts.common([CarHarness.hyundai_f]))], + CarSpecs(mass=1640, wheelbase=2.84, steerRatio=13.56), + flags=HyundaiFlags.LEGACY, + ) + GENESIS_G70_2020 = HyundaiPlatformConfig( + [ + # TODO: 2021 MY harness is unknown + HyundaiCarDocs("Genesis G70 2019-21", "All", car_parts=CarParts.common([CarHarness.hyundai_f])), + # TODO: From 3.3T Sport Advanced 2022 & Prestige 2023 Trim, 2.0T is unknown + HyundaiCarDocs("Genesis G70 2022-23", "All", car_parts=CarParts.common([CarHarness.hyundai_l])), + ], + GENESIS_G70.specs, + flags=HyundaiFlags.MANDO_RADAR, + ) + GENESIS_GV70_1ST_GEN = HyundaiCanFDPlatformConfig( + [ + HyundaiCarDocs("Genesis GV70 (2.5T Trim) 2022-23", "All", car_parts=CarParts.common([CarHarness.hyundai_l])), + HyundaiCarDocs("Genesis GV70 (3.5T Trim) 2022-23", "All", car_parts=CarParts.common([CarHarness.hyundai_m])), + ], + CarSpecs(mass=1950, wheelbase=2.87, steerRatio=14.6), + flags=HyundaiFlags.RADAR_SCC, + ) + GENESIS_G80 = HyundaiPlatformConfig( + [HyundaiCarDocs("Genesis G80 2018-19", "All", car_parts=CarParts.common([CarHarness.hyundai_h]))], + CarSpecs(mass=2060, wheelbase=3.01, steerRatio=16.5), + flags=HyundaiFlags.LEGACY, + ) + GENESIS_G90 = HyundaiPlatformConfig( + [HyundaiCarDocs("Genesis G90 2017-20", "All", car_parts=CarParts.common([CarHarness.hyundai_c]))], + CarSpecs(mass=2200, wheelbase=3.15, steerRatio=12.069), + ) + GENESIS_GV80 = HyundaiCanFDPlatformConfig( + [HyundaiCarDocs("Genesis GV80 2023", "All", car_parts=CarParts.common([CarHarness.hyundai_m]))], + CarSpecs(mass=2258, wheelbase=2.95, steerRatio=14.14), + flags=HyundaiFlags.RADAR_SCC, + ) + + +class Buttons: + NONE = 0 + RES_ACCEL = 1 + SET_DECEL = 2 + GAP_DIST = 3 + CANCEL = 4 # on newer models, this is a pause/resume button + + +def get_platform_codes(fw_versions: list[bytes]) -> set[tuple[bytes, bytes | None]]: + # Returns unique, platform-specific identification codes for a set of versions + codes = set() # (code-Optional[part], date) + for fw in fw_versions: + code_match = PLATFORM_CODE_FW_PATTERN.search(fw) + part_match = PART_NUMBER_FW_PATTERN.search(fw) + date_match = DATE_FW_PATTERN.search(fw) + if code_match is not None: + code: bytes = code_match.group() + part = part_match.group() if part_match else None + date = date_match.group() if date_match else None + if part is not None: + # part number starts with generic ECU part type, add what is specific to platform + code += b"-" + part[-5:] + + codes.add((code, date)) + return codes + + +def match_fw_to_car_fuzzy(live_fw_versions, vin, offline_fw_versions) -> set[str]: + # Non-electric CAN FD platforms often do not have platform code specifiers needed + # to distinguish between hybrid and ICE. All EVs so far are either exclusively + # electric or specify electric in the platform code. + fuzzy_platform_blacklist = {str(c) for c in (CANFD_CAR - EV_CAR - CANFD_FUZZY_WHITELIST)} + candidates: set[str] = set() + + for candidate, fws in offline_fw_versions.items(): + # Keep track of ECUs which pass all checks (platform codes, within date range) + valid_found_ecus = set() + valid_expected_ecus = {ecu[1:] for ecu in fws if ecu[0] in PLATFORM_CODE_ECUS} + for ecu, expected_versions in fws.items(): + addr = ecu[1:] + # Only check ECUs expected to have platform codes + if ecu[0] not in PLATFORM_CODE_ECUS: + continue + + # Expected platform codes & dates + codes = get_platform_codes(expected_versions) + expected_platform_codes = {code for code, _ in codes} + expected_dates = {date for _, date in codes if date is not None} + + # Found platform codes & dates + codes = get_platform_codes(live_fw_versions.get(addr, set())) + found_platform_codes = {code for code, _ in codes} + found_dates = {date for _, date in codes if date is not None} + + # Check platform code + part number matches for any found versions + if not any(found_platform_code in expected_platform_codes for found_platform_code in found_platform_codes): + break + + if ecu[0] in DATE_FW_ECUS: + # If ECU can have a FW date, require it to exist + # (this excludes candidates in the database without dates) + if not len(expected_dates) or not len(found_dates): + break + + # Check any date within range in the database, format is %y%m%d + if not any(min(expected_dates) <= found_date <= max(expected_dates) for found_date in found_dates): + break + + valid_found_ecus.add(addr) + + # If all live ECUs pass all checks for candidate, add it as a match + if valid_expected_ecus.issubset(valid_found_ecus): + candidates.add(candidate) + + return candidates - fuzzy_platform_blacklist + + +HYUNDAI_VERSION_REQUEST_LONG = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ + p16(0xf100) # Long description + +HYUNDAI_VERSION_REQUEST_ALT = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ + p16(0xf110) # Alt long description + +HYUNDAI_ECU_MANUFACTURING_DATE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ + p16(uds.DATA_IDENTIFIER_TYPE.ECU_MANUFACTURING_DATE) + +HYUNDAI_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + +# Regex patterns for parsing platform code, FW date, and part number from FW versions +PLATFORM_CODE_FW_PATTERN = re.compile(b'((?<=' + HYUNDAI_VERSION_REQUEST_LONG[1:] + + b')[A-Z]{2}[A-Za-z0-9]{0,2})') +DATE_FW_PATTERN = re.compile(b'(?<=[ -])([0-9]{6}$)') +PART_NUMBER_FW_PATTERN = re.compile(b'(?<=[0-9][.,][0-9]{2} )([0-9]{5}[-/]?[A-Z][A-Z0-9]{3}[0-9])') + +# We've seen both ICE and hybrid for these platforms, and they have hybrid descriptors (e.g. MQ4 vs MQ4H) +CANFD_FUZZY_WHITELIST = {CAR.KIA_SORENTO_4TH_GEN, CAR.KIA_SORENTO_HEV_4TH_GEN, CAR.KIA_K8_HEV_1ST_GEN, + # TODO: the hybrid variant is not out yet + CAR.KIA_CARNIVAL_4TH_GEN} + +# List of ECUs expected to have platform codes, camera and radar should exist on all cars +# TODO: use abs, it has the platform code and part number on many platforms +PLATFORM_CODE_ECUS = [Ecu.fwdRadar, Ecu.fwdCamera, Ecu.eps] +# So far we've only seen dates in fwdCamera +# TODO: there are date codes in the ABS firmware versions in hex +DATE_FW_ECUS = [Ecu.fwdCamera] + +# Note: an ECU on CAN FD cars may sometimes send 0x30080aaaaaaaaaaa (flow control continue) while we +# are attempting to query ECUs. This currently does not seem to affect fingerprinting from the camera +FW_QUERY_CONFIG = FwQueryConfig( + requests=[ + # TODO: add back whitelists + # CAN queries (OBD-II port) + Request( + [HYUNDAI_VERSION_REQUEST_LONG], + [HYUNDAI_VERSION_RESPONSE], + ), + + # CAN & CAN-FD queries (from camera) + Request( + [HYUNDAI_VERSION_REQUEST_LONG], + [HYUNDAI_VERSION_RESPONSE], + bus=0, + auxiliary=True, + ), + Request( + [HYUNDAI_VERSION_REQUEST_LONG], + [HYUNDAI_VERSION_RESPONSE], + bus=1, + auxiliary=True, + obd_multiplexing=False, + ), + + # CAN & CAN FD query to understand the three digit date code + # HDA2 cars usually use 6 digit date codes, so skip bus 1 + Request( + [HYUNDAI_ECU_MANUFACTURING_DATE], + [HYUNDAI_VERSION_RESPONSE], + bus=0, + auxiliary=True, + logging=True, + ), + + # CAN-FD alt request logging queries for hvac and parkingAdas + Request( + [HYUNDAI_VERSION_REQUEST_ALT], + [HYUNDAI_VERSION_RESPONSE], + bus=0, + auxiliary=True, + logging=True, + ), + Request( + [HYUNDAI_VERSION_REQUEST_ALT], + [HYUNDAI_VERSION_RESPONSE], + bus=1, + auxiliary=True, + logging=True, + obd_multiplexing=False, + ), + ], + # We lose these ECUs without the comma power on these cars. + # Note that we still attempt to match with them when they are present + non_essential_ecus={ + Ecu.abs: [CAR.HYUNDAI_PALISADE, CAR.HYUNDAI_SONATA, CAR.HYUNDAI_SANTA_FE_2022, CAR.KIA_K5_2021, CAR.HYUNDAI_ELANTRA_2021, + CAR.HYUNDAI_SANTA_FE, CAR.HYUNDAI_KONA_EV_2022, CAR.HYUNDAI_KONA_EV, CAR.HYUNDAI_CUSTIN_1ST_GEN, CAR.KIA_SORENTO, + CAR.KIA_CEED, CAR.KIA_SELTOS], + }, + extra_ecus=[ + (Ecu.adas, 0x730, None), # ADAS Driving ECU on HDA2 platforms + (Ecu.parkingAdas, 0x7b1, None), # ADAS Parking ECU (may exist on all platforms) + (Ecu.hvac, 0x7b3, None), # HVAC Control Assembly + (Ecu.cornerRadar, 0x7b7, None), + (Ecu.combinationMeter, 0x7c6, None), # CAN FD Instrument cluster + ], + # Custom fuzzy fingerprinting function using platform codes, part numbers + FW dates: + match_fw_to_car_fuzzy=match_fw_to_car_fuzzy, +) + +CHECKSUM = { + "crc8": CAR.with_flags(HyundaiFlags.CHECKSUM_CRC8), + "6B": CAR.with_flags(HyundaiFlags.CHECKSUM_6B), +} + +CAN_GEARS = { + # which message has the gear. hybrid and EV use ELECT_GEAR + "use_cluster_gears": CAR.with_flags(HyundaiFlags.CLUSTER_GEARS), + "use_tcu_gears": CAR.with_flags(HyundaiFlags.TCU_GEARS), +} + +CANFD_CAR = CAR.with_flags(HyundaiFlags.CANFD) +CANFD_RADAR_SCC_CAR = CAR.with_flags(HyundaiFlags.RADAR_SCC) + +# These CAN FD cars do not accept communication control to disable the ADAS ECU, +# responds with 0x7F2822 - 'conditions not correct' +CANFD_UNSUPPORTED_LONGITUDINAL_CAR = CAR.with_flags(HyundaiFlags.CANFD_NO_RADAR_DISABLE) + +# The camera does SCC on these cars, rather than the radar +CAMERA_SCC_CAR = CAR.with_flags(HyundaiFlags.CAMERA_SCC) + +HYBRID_CAR = CAR.with_flags(HyundaiFlags.HYBRID) + +EV_CAR = CAR.with_flags(HyundaiFlags.EV) + +LEGACY_SAFETY_MODE_CAR = CAR.with_flags(HyundaiFlags.LEGACY) + +UNSUPPORTED_LONGITUDINAL_CAR = CAR.with_flags(HyundaiFlags.LEGACY) | CAR.with_flags(HyundaiFlags.UNSUPPORTED_LONGITUDINAL) + +DBC = CAR.create_dbc_map() diff --git a/car/mazda/__init__.py b/car/mazda/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/car/mazda/carcontroller.py b/car/mazda/carcontroller.py new file mode 100644 index 0000000000..3d41634879 --- /dev/null +++ b/car/mazda/carcontroller.py @@ -0,0 +1,66 @@ +from cereal import car +from opendbc.can.packer import CANPacker +from openpilot.selfdrive.car import apply_driver_steer_torque_limits +from openpilot.selfdrive.car.interfaces import CarControllerBase +from openpilot.selfdrive.car.mazda import mazdacan +from openpilot.selfdrive.car.mazda.values import CarControllerParams, Buttons + +VisualAlert = car.CarControl.HUDControl.VisualAlert + + +class CarController(CarControllerBase): + def __init__(self, dbc_name, CP, VM): + self.CP = CP + self.apply_steer_last = 0 + self.packer = CANPacker(dbc_name) + self.brake_counter = 0 + self.frame = 0 + + def update(self, CC, CS, now_nanos): + can_sends = [] + + apply_steer = 0 + + if CC.latActive: + # calculate steer and also set limits due to driver torque + new_steer = int(round(CC.actuators.steer * CarControllerParams.STEER_MAX)) + apply_steer = apply_driver_steer_torque_limits(new_steer, self.apply_steer_last, + CS.out.steeringTorque, CarControllerParams) + + if CC.cruiseControl.cancel: + # If brake is pressed, let us wait >70ms before trying to disable crz to avoid + # a race condition with the stock system, where the second cancel from openpilot + # will disable the crz 'main on'. crz ctrl msg runs at 50hz. 70ms allows us to + # read 3 messages and most likely sync state before we attempt cancel. + self.brake_counter = self.brake_counter + 1 + if self.frame % 10 == 0 and not (CS.out.brakePressed and self.brake_counter < 7): + # Cancel Stock ACC if it's enabled while OP is disengaged + # Send at a rate of 10hz until we sync with stock ACC state + can_sends.append(mazdacan.create_button_cmd(self.packer, self.CP, CS.crz_btns_counter, Buttons.CANCEL)) + else: + self.brake_counter = 0 + if CC.cruiseControl.resume and self.frame % 5 == 0: + # Mazda Stop and Go requires a RES button (or gas) press if the car stops more than 3 seconds + # Send Resume button when planner wants car to move + can_sends.append(mazdacan.create_button_cmd(self.packer, self.CP, CS.crz_btns_counter, Buttons.RESUME)) + + self.apply_steer_last = apply_steer + + # send HUD alerts + if self.frame % 50 == 0: + ldw = CC.hudControl.visualAlert == VisualAlert.ldw + steer_required = CC.hudControl.visualAlert == VisualAlert.steerRequired + # TODO: find a way to silence audible warnings so we can add more hud alerts + steer_required = steer_required and CS.lkas_allowed_speed + can_sends.append(mazdacan.create_alert_command(self.packer, CS.cam_laneinfo, ldw, steer_required)) + + # send steering command + can_sends.append(mazdacan.create_steering_control(self.packer, self.CP, + self.frame, apply_steer, CS.cam_lkas)) + + new_actuators = CC.actuators.as_builder() + new_actuators.steer = apply_steer / CarControllerParams.STEER_MAX + new_actuators.steerOutputCan = apply_steer + + self.frame += 1 + return new_actuators, can_sends diff --git a/car/mazda/carstate.py b/car/mazda/carstate.py new file mode 100644 index 0000000000..83b238fb68 --- /dev/null +++ b/car/mazda/carstate.py @@ -0,0 +1,153 @@ +from cereal import car +from openpilot.common.conversions import Conversions as CV +from opendbc.can.can_define import CANDefine +from opendbc.can.parser import CANParser +from openpilot.selfdrive.car.interfaces import CarStateBase +from openpilot.selfdrive.car.mazda.values import DBC, LKAS_LIMITS, MazdaFlags + +class CarState(CarStateBase): + def __init__(self, CP): + super().__init__(CP) + + can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) + self.shifter_values = can_define.dv["GEAR"]["GEAR"] + + self.crz_btns_counter = 0 + self.acc_active_last = False + self.low_speed_alert = False + self.lkas_allowed_speed = False + self.lkas_disabled = False + + self.prev_distance_button = 0 + self.distance_button = 0 + + def update(self, cp, cp_cam): + + ret = car.CarState.new_message() + + self.prev_distance_button = self.distance_button + self.distance_button = cp.vl["CRZ_BTNS"]["DISTANCE_LESS"] + + ret.wheelSpeeds = self.get_wheel_speeds( + cp.vl["WHEEL_SPEEDS"]["FL"], + cp.vl["WHEEL_SPEEDS"]["FR"], + cp.vl["WHEEL_SPEEDS"]["RL"], + cp.vl["WHEEL_SPEEDS"]["RR"], + ) + ret.vEgoRaw = (ret.wheelSpeeds.fl + ret.wheelSpeeds.fr + ret.wheelSpeeds.rl + ret.wheelSpeeds.rr) / 4. + ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) + + # Match panda speed reading + speed_kph = cp.vl["ENGINE_DATA"]["SPEED"] + ret.standstill = speed_kph <= .1 + + can_gear = int(cp.vl["GEAR"]["GEAR"]) + ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(can_gear, None)) + + ret.genericToggle = bool(cp.vl["BLINK_INFO"]["HIGH_BEAMS"]) + ret.leftBlindspot = cp.vl["BSM"]["LEFT_BS_STATUS"] != 0 + ret.rightBlindspot = cp.vl["BSM"]["RIGHT_BS_STATUS"] != 0 + ret.leftBlinker, ret.rightBlinker = self.update_blinker_from_lamp(40, cp.vl["BLINK_INFO"]["LEFT_BLINK"] == 1, + cp.vl["BLINK_INFO"]["RIGHT_BLINK"] == 1) + + ret.steeringAngleDeg = cp.vl["STEER"]["STEER_ANGLE"] + ret.steeringTorque = cp.vl["STEER_TORQUE"]["STEER_TORQUE_SENSOR"] + ret.steeringPressed = abs(ret.steeringTorque) > LKAS_LIMITS.STEER_THRESHOLD + + ret.steeringTorqueEps = cp.vl["STEER_TORQUE"]["STEER_TORQUE_MOTOR"] + ret.steeringRateDeg = cp.vl["STEER_RATE"]["STEER_ANGLE_RATE"] + + # TODO: this should be from 0 - 1. + ret.brakePressed = cp.vl["PEDALS"]["BRAKE_ON"] == 1 + ret.brake = cp.vl["BRAKE"]["BRAKE_PRESSURE"] + + ret.seatbeltUnlatched = cp.vl["SEATBELT"]["DRIVER_SEATBELT"] == 0 + ret.doorOpen = any([cp.vl["DOORS"]["FL"], cp.vl["DOORS"]["FR"], + cp.vl["DOORS"]["BL"], cp.vl["DOORS"]["BR"]]) + + # TODO: this should be from 0 - 1. + ret.gas = cp.vl["ENGINE_DATA"]["PEDAL_GAS"] + ret.gasPressed = ret.gas > 0 + + # Either due to low speed or hands off + lkas_blocked = cp.vl["STEER_RATE"]["LKAS_BLOCK"] == 1 + + if self.CP.minSteerSpeed > 0: + # LKAS is enabled at 52kph going up and disabled at 45kph going down + # wait for LKAS_BLOCK signal to clear when going up since it lags behind the speed sometimes + if speed_kph > LKAS_LIMITS.ENABLE_SPEED and not lkas_blocked: + self.lkas_allowed_speed = True + elif speed_kph < LKAS_LIMITS.DISABLE_SPEED: + self.lkas_allowed_speed = False + else: + self.lkas_allowed_speed = True + + # TODO: the signal used for available seems to be the adaptive cruise signal, instead of the main on + # it should be used for carState.cruiseState.nonAdaptive instead + ret.cruiseState.available = cp.vl["CRZ_CTRL"]["CRZ_AVAILABLE"] == 1 + ret.cruiseState.enabled = cp.vl["CRZ_CTRL"]["CRZ_ACTIVE"] == 1 + ret.cruiseState.standstill = cp.vl["PEDALS"]["STANDSTILL"] == 1 + ret.cruiseState.speed = cp.vl["CRZ_EVENTS"]["CRZ_SPEED"] * CV.KPH_TO_MS + + if ret.cruiseState.enabled: + if not self.lkas_allowed_speed and self.acc_active_last: + self.low_speed_alert = True + else: + self.low_speed_alert = False + + # Check if LKAS is disabled due to lack of driver torque when all other states indicate + # it should be enabled (steer lockout). Don't warn until we actually get lkas active + # and lose it again, i.e, after initial lkas activation + ret.steerFaultTemporary = self.lkas_allowed_speed and lkas_blocked + + self.acc_active_last = ret.cruiseState.enabled + + self.crz_btns_counter = cp.vl["CRZ_BTNS"]["CTR"] + + # camera signals + self.lkas_disabled = cp_cam.vl["CAM_LANEINFO"]["LANE_LINES"] == 0 + self.cam_lkas = cp_cam.vl["CAM_LKAS"] + self.cam_laneinfo = cp_cam.vl["CAM_LANEINFO"] + ret.steerFaultPermanent = cp_cam.vl["CAM_LKAS"]["ERR_BIT_1"] == 1 + + return ret + + @staticmethod + def get_can_parser(CP): + messages = [ + # sig_address, frequency + ("BLINK_INFO", 10), + ("STEER", 67), + ("STEER_RATE", 83), + ("STEER_TORQUE", 83), + ("WHEEL_SPEEDS", 100), + ] + + if CP.flags & MazdaFlags.GEN1: + messages += [ + ("ENGINE_DATA", 100), + ("CRZ_CTRL", 50), + ("CRZ_EVENTS", 50), + ("CRZ_BTNS", 10), + ("PEDALS", 50), + ("BRAKE", 50), + ("SEATBELT", 10), + ("DOORS", 10), + ("GEAR", 20), + ("BSM", 10), + ] + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, 0) + + @staticmethod + def get_cam_can_parser(CP): + messages = [] + + if CP.flags & MazdaFlags.GEN1: + messages += [ + # sig_address, frequency + ("CAM_LANEINFO", 2), + ("CAM_LKAS", 16), + ] + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, 2) diff --git a/car/mazda/fingerprints.py b/car/mazda/fingerprints.py new file mode 100644 index 0000000000..f460fe9950 --- /dev/null +++ b/car/mazda/fingerprints.py @@ -0,0 +1,265 @@ +from cereal import car +from openpilot.selfdrive.car.mazda.values import CAR + +Ecu = car.CarParams.Ecu + +FW_VERSIONS = { + CAR.MAZDA_CX5_2022: { + (Ecu.eps, 0x730, None): [ + b'KSD5-3210X-C-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'PEW5-188K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PW67-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX2D-188K2-G\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX2G-188K2-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX2H-188K2-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX2H-188K2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX85-188K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXFG-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'SH54-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'K131-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x760, None): [ + b'KGWD-437K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'KSD5-437K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'GSH7-67XK2-S\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-T\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-U\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.transmission, 0x7e1, None): [ + b'PG69-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PW66-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXDL-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXFG-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXFG-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYB2-21PS1-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYB2-21PS1-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYJ3-21PS1-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'SH51-21PS1-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, + CAR.MAZDA_CX5: { + (Ecu.eps, 0x730, None): [ + b'K319-3210X-A-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'KCB8-3210X-B-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'KJ01-3210X-G-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'KJ01-3210X-J-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'KJ01-3210X-M-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'PA53-188K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PAR4-188K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX2E-188K2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX2F-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX2G-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX2H-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX2H-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX2H-188K2-G\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX2K-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX38-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX42-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX68-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYFA-188K2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYFC-188K2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYFD-188K2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYNF-188K2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'SHKT-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'K123-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'K131-67XK2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'K131-67XK2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'K131-67XK2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'K131-67XK2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'K131-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x760, None): [ + b'K123-437K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'KBJ5-437K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'KL2K-437K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'KN0W-437K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'B61L-67XK2-R\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'B61L-67XK2-S\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'B61L-67XK2-T\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'B61L-67XK2-V\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-M\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-N\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-R\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.transmission, 0x7e1, None): [ + b'PA66-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PA66-21PS1-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX39-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX39-21PS1-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX68-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYB1-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYB1-21PS1-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYB1-21PS1-G\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYB2-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYB2-21PS1-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYB2-21PS1-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYB2-21PS1-G\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYB2-21PS1-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYNC-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'SH9T-21PS1-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, + CAR.MAZDA_CX9: { + (Ecu.eps, 0x730, None): [ + b'K070-3210X-C-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'KJ01-3210X-G-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'KJ01-3210X-L-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'PX23-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX24-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXM4-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXN8-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXN8-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYD7-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYD8-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYFM-188K2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYFM-188K2-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'K123-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'K131-67XK2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'K131-67XK2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'TK80-67XK2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'TK80-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x760, None): [ + b'TA0B-437K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'TK79-437K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'TK79-437K2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'TM53-437K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'TN40-437K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'B61L-67XK2-P\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'B61L-67XK2-V\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-K\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'TK80-67XK2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.transmission, 0x7e1, None): [ + b'PXM4-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXM7-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXM7-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYD5-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYD5-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYD6-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYD6-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYFM-21PS1-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYFM-21PS1-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, + CAR.MAZDA_3: { + (Ecu.eps, 0x730, None): [ + b'BHN1-3210X-J-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'K070-3210X-C-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'KR11-3210X-K-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'P5JD-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PY2P-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYJW-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYKC-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYKE-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'B63C-67XK2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GHP9-67Y10---41\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'K131-67XK2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x760, None): [ + b'B45A-437AS-0-08\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'B61L-67XK2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'B61L-67XK2-P\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'B61L-67XK2-Q\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'B61L-67XK2-T\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.transmission, 0x7e1, None): [ + b'P52G-21PS1-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PY2S-21PS1-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYKA-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYKE-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYKE-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, + CAR.MAZDA_6: { + (Ecu.eps, 0x730, None): [ + b'GBEF-3210X-B-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GBEF-3210X-C-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GFBC-3210X-A-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'PA34-188K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX4F-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYH7-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYH7-188K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'K131-67XK2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'K131-67XK2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x760, None): [ + b'GBVH-437K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GBVH-437K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GDDM-437K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'B61L-67XK2-S\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'B61L-67XK2-T\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-P\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.transmission, 0x7e1, None): [ + b'PA28-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYH3-21PS1-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYH7-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, + CAR.MAZDA_CX9_2021: { + (Ecu.eps, 0x730, None): [ + b'TC3M-3210X-A-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'PXGW-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXGW-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXM4-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXM4-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXM6-188K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXM7-188K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'K131-67XK2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'K131-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x760, None): [ + b'TA0B-437K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'GSH7-67XK2-M\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-N\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-P\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-S\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-T\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-U\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.transmission, 0x7e1, None): [ + b'PXM4-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXM6-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PXM7-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, +} diff --git a/car/mazda/interface.py b/car/mazda/interface.py new file mode 100755 index 0000000000..6992d49ffe --- /dev/null +++ b/car/mazda/interface.py @@ -0,0 +1,50 @@ +#!/usr/bin/env python3 +from cereal import car +from openpilot.common.conversions import Conversions as CV +from openpilot.selfdrive.car.mazda.values import CAR, LKAS_LIMITS +from openpilot.selfdrive.car import create_button_events, get_safety_config +from openpilot.selfdrive.car.interfaces import CarInterfaceBase + +ButtonType = car.CarState.ButtonEvent.Type +EventName = car.CarEvent.EventName + +class CarInterface(CarInterfaceBase): + + @staticmethod + def _get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs): + ret.carName = "mazda" + ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.mazda)] + ret.radarUnavailable = True + + ret.dashcamOnly = candidate not in (CAR.MAZDA_CX5_2022, CAR.MAZDA_CX9_2021) + + ret.steerActuatorDelay = 0.1 + ret.steerLimitTimer = 0.8 + + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) + + if candidate not in (CAR.MAZDA_CX5_2022, ): + ret.minSteerSpeed = LKAS_LIMITS.DISABLE_SPEED * CV.KPH_TO_MS + + ret.centerToFront = ret.wheelbase * 0.41 + + return ret + + # returns a car.CarState + def _update(self, c): + ret = self.CS.update(self.cp, self.cp_cam) + + # TODO: add button types for inc and dec + ret.buttonEvents = create_button_events(self.CS.distance_button, self.CS.prev_distance_button, {1: ButtonType.gapAdjustCruise}) + + # events + events = self.create_common_events(ret) + + if self.CS.lkas_disabled: + events.add(EventName.lkasDisabled) + elif self.CS.low_speed_alert: + events.add(EventName.belowSteerSpeed) + + ret.events = events.to_msg() + + return ret diff --git a/car/mazda/mazdacan.py b/car/mazda/mazdacan.py new file mode 100644 index 0000000000..74f6af04c5 --- /dev/null +++ b/car/mazda/mazdacan.py @@ -0,0 +1,128 @@ +from openpilot.selfdrive.car.mazda.values import Buttons, MazdaFlags + + +def create_steering_control(packer, CP, frame, apply_steer, lkas): + + tmp = apply_steer + 2048 + + lo = tmp & 0xFF + hi = tmp >> 8 + + # copy values from camera + b1 = int(lkas["BIT_1"]) + er1 = int(lkas["ERR_BIT_1"]) + lnv = 0 + ldw = 0 + er2 = int(lkas["ERR_BIT_2"]) + + # Some older models do have these, newer models don't. + # Either way, they all work just fine if set to zero. + steering_angle = 0 + b2 = 0 + + tmp = steering_angle + 2048 + ahi = tmp >> 10 + amd = (tmp & 0x3FF) >> 2 + amd = (amd >> 4) | (( amd & 0xF) << 4) + alo = (tmp & 0x3) << 2 + + ctr = frame % 16 + # bytes: [ 1 ] [ 2 ] [ 3 ] [ 4 ] + csum = 249 - ctr - hi - lo - (lnv << 3) - er1 - (ldw << 7) - ( er2 << 4) - (b1 << 5) + + # bytes [ 5 ] [ 6 ] [ 7 ] + csum = csum - ahi - amd - alo - b2 + + if ahi == 1: + csum = csum + 15 + + if csum < 0: + if csum < -256: + csum = csum + 512 + else: + csum = csum + 256 + + csum = csum % 256 + + values = {} + if CP.flags & MazdaFlags.GEN1: + values = { + "LKAS_REQUEST": apply_steer, + "CTR": ctr, + "ERR_BIT_1": er1, + "LINE_NOT_VISIBLE" : lnv, + "LDW": ldw, + "BIT_1": b1, + "ERR_BIT_2": er2, + "STEERING_ANGLE": steering_angle, + "ANGLE_ENABLED": b2, + "CHKSUM": csum + } + + return packer.make_can_msg("CAM_LKAS", 0, values) + + +def create_alert_command(packer, cam_msg: dict, ldw: bool, steer_required: bool): + values = {s: cam_msg[s] for s in [ + "LINE_VISIBLE", + "LINE_NOT_VISIBLE", + "LANE_LINES", + "BIT1", + "BIT2", + "BIT3", + "NO_ERR_BIT", + "S1", + "S1_HBEAM", + ]} + values.update({ + # TODO: what's the difference between all these? do we need to send all? + "HANDS_WARN_3_BITS": 0b111 if steer_required else 0, + "HANDS_ON_STEER_WARN": steer_required, + "HANDS_ON_STEER_WARN_2": steer_required, + + # TODO: right lane works, left doesn't + # TODO: need to do something about L/R + "LDW_WARN_LL": 0, + "LDW_WARN_RL": 0, + }) + return packer.make_can_msg("CAM_LANEINFO", 0, values) + + +def create_button_cmd(packer, CP, counter, button): + + can = int(button == Buttons.CANCEL) + res = int(button == Buttons.RESUME) + + if CP.flags & MazdaFlags.GEN1: + values = { + "CAN_OFF": can, + "CAN_OFF_INV": (can + 1) % 2, + + "SET_P": 0, + "SET_P_INV": 1, + + "RES": res, + "RES_INV": (res + 1) % 2, + + "SET_M": 0, + "SET_M_INV": 1, + + "DISTANCE_LESS": 0, + "DISTANCE_LESS_INV": 1, + + "DISTANCE_MORE": 0, + "DISTANCE_MORE_INV": 1, + + "MODE_X": 0, + "MODE_X_INV": 1, + + "MODE_Y": 0, + "MODE_Y_INV": 1, + + "BIT1": 1, + "BIT2": 1, + "BIT3": 1, + "CTR": (counter + 1) % 16, + } + + return packer.make_can_msg("CRZ_BTNS", 0, values) diff --git a/car/mazda/radar_interface.py b/car/mazda/radar_interface.py new file mode 100755 index 0000000000..b461fcd5f8 --- /dev/null +++ b/car/mazda/radar_interface.py @@ -0,0 +1,5 @@ +#!/usr/bin/env python3 +from openpilot.selfdrive.car.interfaces import RadarInterfaceBase + +class RadarInterface(RadarInterfaceBase): + pass diff --git a/car/mazda/values.py b/car/mazda/values.py new file mode 100644 index 0000000000..a8c808d582 --- /dev/null +++ b/car/mazda/values.py @@ -0,0 +1,104 @@ +from dataclasses import dataclass, field +from enum import IntFlag + +from cereal import car +from openpilot.common.conversions import Conversions as CV +from openpilot.selfdrive.car import CarSpecs, DbcDict, PlatformConfig, Platforms, dbc_dict +from openpilot.selfdrive.car.docs_definitions import CarHarness, CarDocs, CarParts +from openpilot.selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries + +Ecu = car.CarParams.Ecu + + +# Steer torque limits + +class CarControllerParams: + STEER_MAX = 800 # theoretical max_steer 2047 + STEER_DELTA_UP = 10 # torque increase per refresh + STEER_DELTA_DOWN = 25 # torque decrease per refresh + STEER_DRIVER_ALLOWANCE = 15 # allowed driver torque before start limiting + STEER_DRIVER_MULTIPLIER = 1 # weight driver torque + STEER_DRIVER_FACTOR = 1 # from dbc + STEER_ERROR_MAX = 350 # max delta between torque cmd and torque motor + STEER_STEP = 1 # 100 Hz + + def __init__(self, CP): + pass + + +@dataclass +class MazdaCarDocs(CarDocs): + package: str = "All" + car_parts: CarParts = field(default_factory=CarParts.common([CarHarness.mazda])) + + +@dataclass(frozen=True, kw_only=True) +class MazdaCarSpecs(CarSpecs): + tireStiffnessFactor: float = 0.7 # not optimized yet + + +class MazdaFlags(IntFlag): + # Static flags + # Gen 1 hardware: same CAN messages and same camera + GEN1 = 1 + + +@dataclass +class MazdaPlatformConfig(PlatformConfig): + dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict('mazda_2017', None)) + flags: int = MazdaFlags.GEN1 + + +class CAR(Platforms): + MAZDA_CX5 = MazdaPlatformConfig( + [MazdaCarDocs("Mazda CX-5 2017-21")], + MazdaCarSpecs(mass=3655 * CV.LB_TO_KG, wheelbase=2.7, steerRatio=15.5) + ) + MAZDA_CX9 = MazdaPlatformConfig( + [MazdaCarDocs("Mazda CX-9 2016-20")], + MazdaCarSpecs(mass=4217 * CV.LB_TO_KG, wheelbase=3.1, steerRatio=17.6) + ) + MAZDA_3 = MazdaPlatformConfig( + [MazdaCarDocs("Mazda 3 2017-18")], + MazdaCarSpecs(mass=2875 * CV.LB_TO_KG, wheelbase=2.7, steerRatio=14.0) + ) + MAZDA_6 = MazdaPlatformConfig( + [MazdaCarDocs("Mazda 6 2017-20")], + MazdaCarSpecs(mass=3443 * CV.LB_TO_KG, wheelbase=2.83, steerRatio=15.5) + ) + MAZDA_CX9_2021 = MazdaPlatformConfig( + [MazdaCarDocs("Mazda CX-9 2021-23", video_link="https://youtu.be/dA3duO4a0O4")], + MAZDA_CX9.specs + ) + MAZDA_CX5_2022 = MazdaPlatformConfig( + [MazdaCarDocs("Mazda CX-5 2022-24")], + MAZDA_CX5.specs, + ) + + +class LKAS_LIMITS: + STEER_THRESHOLD = 15 + DISABLE_SPEED = 45 # kph + ENABLE_SPEED = 52 # kph + + +class Buttons: + NONE = 0 + SET_PLUS = 1 + SET_MINUS = 2 + RESUME = 3 + CANCEL = 4 + + +FW_QUERY_CONFIG = FwQueryConfig( + requests=[ + # TODO: check data to ensure ABS does not skip ISO-TP frames on bus 0 + Request( + [StdQueries.MANUFACTURER_SOFTWARE_VERSION_REQUEST], + [StdQueries.MANUFACTURER_SOFTWARE_VERSION_RESPONSE], + bus=0, + ), + ], +) + +DBC = CAR.create_dbc_map() diff --git a/car/mock/__init__.py b/car/mock/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/car/mock/carcontroller.py b/car/mock/carcontroller.py new file mode 100644 index 0000000000..0cd37c0369 --- /dev/null +++ b/car/mock/carcontroller.py @@ -0,0 +1,5 @@ +from openpilot.selfdrive.car.interfaces import CarControllerBase + +class CarController(CarControllerBase): + def update(self, CC, CS, now_nanos): + return CC.actuators.as_builder(), [] diff --git a/car/mock/carstate.py b/car/mock/carstate.py new file mode 100644 index 0000000000..ece908b51c --- /dev/null +++ b/car/mock/carstate.py @@ -0,0 +1,4 @@ +from openpilot.selfdrive.car.interfaces import CarStateBase + +class CarState(CarStateBase): + pass diff --git a/car/mock/interface.py b/car/mock/interface.py new file mode 100755 index 0000000000..7506bab053 --- /dev/null +++ b/car/mock/interface.py @@ -0,0 +1,32 @@ +#!/usr/bin/env python3 +from cereal import car +import cereal.messaging as messaging +from openpilot.selfdrive.car.interfaces import CarInterfaceBase + +# mocked car interface for dashcam mode +class CarInterface(CarInterfaceBase): + def __init__(self, CP, CarController, CarState): + super().__init__(CP, CarController, CarState) + + self.speed = 0. + self.sm = messaging.SubMaster(['gpsLocation', 'gpsLocationExternal']) + + @staticmethod + def _get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs): + ret.carName = "mock" + ret.mass = 1700. + ret.wheelbase = 2.70 + ret.centerToFront = ret.wheelbase * 0.5 + ret.steerRatio = 13. + ret.dashcamOnly = True + return ret + + def _update(self, c): + self.sm.update(0) + gps_sock = 'gpsLocationExternal' if self.sm.recv_frame['gpsLocationExternal'] > 1 else 'gpsLocation' + + ret = car.CarState.new_message() + ret.vEgo = self.sm[gps_sock].speed + ret.vEgoRaw = self.sm[gps_sock].speed + + return ret diff --git a/car/mock/radar_interface.py b/car/mock/radar_interface.py new file mode 100644 index 0000000000..e654bd61fd --- /dev/null +++ b/car/mock/radar_interface.py @@ -0,0 +1,4 @@ +from openpilot.selfdrive.car.interfaces import RadarInterfaceBase + +class RadarInterface(RadarInterfaceBase): + pass diff --git a/car/mock/values.py b/car/mock/values.py new file mode 100644 index 0000000000..f98aac2ee3 --- /dev/null +++ b/car/mock/values.py @@ -0,0 +1,9 @@ +from openpilot.selfdrive.car import CarSpecs, PlatformConfig, Platforms + + +class CAR(Platforms): + MOCK = PlatformConfig( + [], + CarSpecs(mass=1700, wheelbase=2.7, steerRatio=13), + {} + ) diff --git a/car/nissan/__init__.py b/car/nissan/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/car/nissan/carcontroller.py b/car/nissan/carcontroller.py new file mode 100644 index 0000000000..c7bd231398 --- /dev/null +++ b/car/nissan/carcontroller.py @@ -0,0 +1,82 @@ +from cereal import car +from opendbc.can.packer import CANPacker +from openpilot.selfdrive.car import apply_std_steer_angle_limits +from openpilot.selfdrive.car.interfaces import CarControllerBase +from openpilot.selfdrive.car.nissan import nissancan +from openpilot.selfdrive.car.nissan.values import CAR, CarControllerParams + +VisualAlert = car.CarControl.HUDControl.VisualAlert + + +class CarController(CarControllerBase): + def __init__(self, dbc_name, CP, VM): + self.CP = CP + self.car_fingerprint = CP.carFingerprint + self.frame = 0 + + self.lkas_max_torque = 0 + self.apply_angle_last = 0 + + self.packer = CANPacker(dbc_name) + + def update(self, CC, CS, now_nanos): + actuators = CC.actuators + hud_control = CC.hudControl + pcm_cancel_cmd = CC.cruiseControl.cancel + + can_sends = [] + + ### STEER ### + steer_hud_alert = 1 if hud_control.visualAlert in (VisualAlert.steerRequired, VisualAlert.ldw) else 0 + + if CC.latActive: + # windup slower + apply_angle = apply_std_steer_angle_limits(actuators.steeringAngleDeg, self.apply_angle_last, CS.out.vEgoRaw, CarControllerParams) + + # Max torque from driver before EPS will give up and not apply torque + if not bool(CS.out.steeringPressed): + self.lkas_max_torque = CarControllerParams.LKAS_MAX_TORQUE + else: + # Scale max torque based on how much torque the driver is applying to the wheel + self.lkas_max_torque = max( + # Scale max torque down to half LKAX_MAX_TORQUE as a minimum + CarControllerParams.LKAS_MAX_TORQUE * 0.5, + # Start scaling torque at STEER_THRESHOLD + CarControllerParams.LKAS_MAX_TORQUE - 0.6 * max(0, abs(CS.out.steeringTorque) - CarControllerParams.STEER_THRESHOLD) + ) + + else: + apply_angle = CS.out.steeringAngleDeg + self.lkas_max_torque = 0 + + self.apply_angle_last = apply_angle + + if self.CP.carFingerprint in (CAR.NISSAN_ROGUE, CAR.NISSAN_XTRAIL, CAR.NISSAN_ALTIMA) and pcm_cancel_cmd: + can_sends.append(nissancan.create_acc_cancel_cmd(self.packer, self.car_fingerprint, CS.cruise_throttle_msg)) + + # TODO: Find better way to cancel! + # For some reason spamming the cancel button is unreliable on the Leaf + # We now cancel by making propilot think the seatbelt is unlatched, + # this generates a beep and a warning message every time you disengage + if self.CP.carFingerprint in (CAR.NISSAN_LEAF, CAR.NISSAN_LEAF_IC) and self.frame % 2 == 0: + can_sends.append(nissancan.create_cancel_msg(self.packer, CS.cancel_msg, pcm_cancel_cmd)) + + can_sends.append(nissancan.create_steering_control( + self.packer, apply_angle, self.frame, CC.latActive, self.lkas_max_torque)) + + # Below are the HUD messages. We copy the stock message and modify + if self.CP.carFingerprint != CAR.NISSAN_ALTIMA: + if self.frame % 2 == 0: + can_sends.append(nissancan.create_lkas_hud_msg(self.packer, CS.lkas_hud_msg, CC.enabled, hud_control.leftLaneVisible, hud_control.rightLaneVisible, + hud_control.leftLaneDepart, hud_control.rightLaneDepart)) + + if self.frame % 50 == 0: + can_sends.append(nissancan.create_lkas_hud_info_msg( + self.packer, CS.lkas_hud_info_msg, steer_hud_alert + )) + + new_actuators = actuators.as_builder() + new_actuators.steeringAngleDeg = apply_angle + + self.frame += 1 + return new_actuators, can_sends diff --git a/car/nissan/carstate.py b/car/nissan/carstate.py new file mode 100644 index 0000000000..57146b49c4 --- /dev/null +++ b/car/nissan/carstate.py @@ -0,0 +1,197 @@ +import copy +from collections import deque +from cereal import car +from opendbc.can.can_define import CANDefine +from openpilot.selfdrive.car.interfaces import CarStateBase +from openpilot.common.conversions import Conversions as CV +from opendbc.can.parser import CANParser +from openpilot.selfdrive.car.nissan.values import CAR, DBC, CarControllerParams + +TORQUE_SAMPLES = 12 + +class CarState(CarStateBase): + def __init__(self, CP): + super().__init__(CP) + can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) + + self.lkas_hud_msg = {} + self.lkas_hud_info_msg = {} + + self.steeringTorqueSamples = deque(TORQUE_SAMPLES*[0], TORQUE_SAMPLES) + self.shifter_values = can_define.dv["GEARBOX"]["GEAR_SHIFTER"] + + self.prev_distance_button = 0 + self.distance_button = 0 + + def update(self, cp, cp_adas, cp_cam): + ret = car.CarState.new_message() + + self.prev_distance_button = self.distance_button + self.distance_button = cp.vl["CRUISE_THROTTLE"]["FOLLOW_DISTANCE_BUTTON"] + + if self.CP.carFingerprint in (CAR.NISSAN_ROGUE, CAR.NISSAN_XTRAIL, CAR.NISSAN_ALTIMA): + ret.gas = cp.vl["GAS_PEDAL"]["GAS_PEDAL"] + elif self.CP.carFingerprint in (CAR.NISSAN_LEAF, CAR.NISSAN_LEAF_IC): + ret.gas = cp.vl["CRUISE_THROTTLE"]["GAS_PEDAL"] + + ret.gasPressed = bool(ret.gas > 3) + + if self.CP.carFingerprint in (CAR.NISSAN_ROGUE, CAR.NISSAN_XTRAIL, CAR.NISSAN_ALTIMA): + ret.brakePressed = bool(cp.vl["DOORS_LIGHTS"]["USER_BRAKE_PRESSED"]) + elif self.CP.carFingerprint in (CAR.NISSAN_LEAF, CAR.NISSAN_LEAF_IC): + ret.brakePressed = bool(cp.vl["CRUISE_THROTTLE"]["USER_BRAKE_PRESSED"]) + + ret.wheelSpeeds = self.get_wheel_speeds( + cp.vl["WHEEL_SPEEDS_FRONT"]["WHEEL_SPEED_FL"], + cp.vl["WHEEL_SPEEDS_FRONT"]["WHEEL_SPEED_FR"], + cp.vl["WHEEL_SPEEDS_REAR"]["WHEEL_SPEED_RL"], + cp.vl["WHEEL_SPEEDS_REAR"]["WHEEL_SPEED_RR"], + ) + ret.vEgoRaw = (ret.wheelSpeeds.fl + ret.wheelSpeeds.fr + ret.wheelSpeeds.rl + ret.wheelSpeeds.rr) / 4. + + ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) + ret.standstill = cp.vl["WHEEL_SPEEDS_REAR"]["WHEEL_SPEED_RL"] == 0.0 and cp.vl["WHEEL_SPEEDS_REAR"]["WHEEL_SPEED_RR"] == 0.0 + + if self.CP.carFingerprint == CAR.NISSAN_ALTIMA: + ret.cruiseState.enabled = bool(cp.vl["CRUISE_STATE"]["CRUISE_ENABLED"]) + else: + ret.cruiseState.enabled = bool(cp_adas.vl["CRUISE_STATE"]["CRUISE_ENABLED"]) + + if self.CP.carFingerprint in (CAR.NISSAN_ROGUE, CAR.NISSAN_XTRAIL): + ret.seatbeltUnlatched = cp.vl["HUD"]["SEATBELT_DRIVER_LATCHED"] == 0 + ret.cruiseState.available = bool(cp_cam.vl["PRO_PILOT"]["CRUISE_ON"]) + elif self.CP.carFingerprint in (CAR.NISSAN_LEAF, CAR.NISSAN_LEAF_IC): + if self.CP.carFingerprint == CAR.NISSAN_LEAF: + ret.seatbeltUnlatched = cp.vl["SEATBELT"]["SEATBELT_DRIVER_LATCHED"] == 0 + elif self.CP.carFingerprint == CAR.NISSAN_LEAF_IC: + ret.seatbeltUnlatched = cp.vl["CANCEL_MSG"]["CANCEL_SEATBELT"] == 1 + ret.cruiseState.available = bool(cp.vl["CRUISE_THROTTLE"]["CRUISE_AVAILABLE"]) + elif self.CP.carFingerprint == CAR.NISSAN_ALTIMA: + ret.seatbeltUnlatched = cp.vl["HUD"]["SEATBELT_DRIVER_LATCHED"] == 0 + ret.cruiseState.available = bool(cp_adas.vl["PRO_PILOT"]["CRUISE_ON"]) + + if self.CP.carFingerprint == CAR.NISSAN_ALTIMA: + speed = cp.vl["PROPILOT_HUD"]["SET_SPEED"] + else: + speed = cp_adas.vl["PROPILOT_HUD"]["SET_SPEED"] + + if speed != 255: + if self.CP.carFingerprint in (CAR.NISSAN_LEAF, CAR.NISSAN_LEAF_IC): + conversion = CV.MPH_TO_MS if cp.vl["HUD_SETTINGS"]["SPEED_MPH"] else CV.KPH_TO_MS + else: + conversion = CV.MPH_TO_MS if cp.vl["HUD"]["SPEED_MPH"] else CV.KPH_TO_MS + ret.cruiseState.speed = speed * conversion + ret.cruiseState.speedCluster = (speed - 1) * conversion # Speed on HUD is always 1 lower than actually sent on can bus + + if self.CP.carFingerprint == CAR.NISSAN_ALTIMA: + ret.steeringTorque = cp_cam.vl["STEER_TORQUE_SENSOR"]["STEER_TORQUE_DRIVER"] + else: + ret.steeringTorque = cp.vl["STEER_TORQUE_SENSOR"]["STEER_TORQUE_DRIVER"] + + self.steeringTorqueSamples.append(ret.steeringTorque) + # Filtering driver torque to prevent steeringPressed false positives + ret.steeringPressed = bool(abs(sum(self.steeringTorqueSamples) / TORQUE_SAMPLES) > CarControllerParams.STEER_THRESHOLD) + + ret.steeringAngleDeg = cp.vl["STEER_ANGLE_SENSOR"]["STEER_ANGLE"] + + ret.leftBlinker = bool(cp.vl["LIGHTS"]["LEFT_BLINKER"]) + ret.rightBlinker = bool(cp.vl["LIGHTS"]["RIGHT_BLINKER"]) + + ret.doorOpen = any([cp.vl["DOORS_LIGHTS"]["DOOR_OPEN_RR"], + cp.vl["DOORS_LIGHTS"]["DOOR_OPEN_RL"], + cp.vl["DOORS_LIGHTS"]["DOOR_OPEN_FR"], + cp.vl["DOORS_LIGHTS"]["DOOR_OPEN_FL"]]) + + ret.espDisabled = bool(cp.vl["ESP"]["ESP_DISABLED"]) + + can_gear = int(cp.vl["GEARBOX"]["GEAR_SHIFTER"]) + ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(can_gear, None)) + + if self.CP.carFingerprint == CAR.NISSAN_ALTIMA: + self.lkas_enabled = bool(cp.vl["LKAS_SETTINGS"]["LKAS_ENABLED"]) + else: + self.lkas_enabled = bool(cp_adas.vl["LKAS_SETTINGS"]["LKAS_ENABLED"]) + + self.cruise_throttle_msg = copy.copy(cp.vl["CRUISE_THROTTLE"]) + + if self.CP.carFingerprint in (CAR.NISSAN_LEAF, CAR.NISSAN_LEAF_IC): + self.cancel_msg = copy.copy(cp.vl["CANCEL_MSG"]) + + if self.CP.carFingerprint != CAR.NISSAN_ALTIMA: + self.lkas_hud_msg = copy.copy(cp_adas.vl["PROPILOT_HUD"]) + self.lkas_hud_info_msg = copy.copy(cp_adas.vl["PROPILOT_HUD_INFO_MSG"]) + + return ret + + @staticmethod + def get_can_parser(CP): + messages = [ + # sig_address, frequency + ("STEER_ANGLE_SENSOR", 100), + ("WHEEL_SPEEDS_REAR", 50), + ("WHEEL_SPEEDS_FRONT", 50), + ("ESP", 25), + ("GEARBOX", 25), + ("DOORS_LIGHTS", 10), + ("LIGHTS", 10), + ] + + if CP.carFingerprint in (CAR.NISSAN_ROGUE, CAR.NISSAN_XTRAIL, CAR.NISSAN_ALTIMA): + messages += [ + ("GAS_PEDAL", 100), + ("CRUISE_THROTTLE", 50), + ("HUD", 25), + ] + + elif CP.carFingerprint in (CAR.NISSAN_LEAF, CAR.NISSAN_LEAF_IC): + messages += [ + ("BRAKE_PEDAL", 100), + ("CRUISE_THROTTLE", 50), + ("CANCEL_MSG", 50), + ("HUD_SETTINGS", 25), + ("SEATBELT", 10), + ] + + if CP.carFingerprint == CAR.NISSAN_ALTIMA: + messages += [ + ("CRUISE_STATE", 10), + ("LKAS_SETTINGS", 10), + ("PROPILOT_HUD", 50), + ] + return CANParser(DBC[CP.carFingerprint]["pt"], messages, 1) + + messages.append(("STEER_TORQUE_SENSOR", 100)) + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, 0) + + @staticmethod + def get_adas_can_parser(CP): + # this function generates lists for signal, messages and initial values + + if CP.carFingerprint == CAR.NISSAN_ALTIMA: + messages = [ + ("LKAS", 100), + ("PRO_PILOT", 100), + ] + else: + messages = [ + ("PROPILOT_HUD_INFO_MSG", 2), + ("LKAS_SETTINGS", 10), + ("CRUISE_STATE", 50), + ("PROPILOT_HUD", 50), + ("LKAS", 100), + ] + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, 2) + + @staticmethod + def get_cam_can_parser(CP): + messages = [] + + if CP.carFingerprint in (CAR.NISSAN_ROGUE, CAR.NISSAN_XTRAIL): + messages.append(("PRO_PILOT", 100)) + elif CP.carFingerprint == CAR.NISSAN_ALTIMA: + messages.append(("STEER_TORQUE_SENSOR", 100)) + return CANParser(DBC[CP.carFingerprint]["pt"], messages, 0) + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, 1) diff --git a/car/nissan/fingerprints.py b/car/nissan/fingerprints.py new file mode 100644 index 0000000000..743feeace9 --- /dev/null +++ b/car/nissan/fingerprints.py @@ -0,0 +1,119 @@ +# ruff: noqa: E501 +from cereal import car +from openpilot.selfdrive.car.nissan.values import CAR + +Ecu = car.CarParams.Ecu + +FINGERPRINTS = { + CAR.NISSAN_XTRAIL: [{ + 2: 5, 42: 6, 346: 6, 347: 5, 348: 8, 349: 7, 361: 8, 386: 8, 389: 8, 397: 8, 398: 8, 403: 8, 520: 2, 523: 6, 548: 8, 645: 8, 658: 8, 665: 8, 666: 8, 674: 2, 682: 8, 683: 8, 689: 8, 723: 8, 758: 3, 768: 2, 783: 3, 851: 8, 855: 8, 1041: 8, 1055: 2, 1104: 4, 1105: 6, 1107: 4, 1108: 8, 1111: 4, 1227: 8, 1228: 8, 1247: 4, 1266: 8, 1273: 7, 1342: 1, 1376: 6, 1401: 8, 1474: 2, 1497: 3, 1821: 8, 1823: 8, 1837: 8, 2015: 8, 2016: 8, 2024: 8 + }, + { + 2: 5, 42: 6, 346: 6, 347: 5, 348: 8, 349: 7, 361: 8, 386: 8, 389: 8, 397: 8, 398: 8, 403: 8, 520: 2, 523: 6, 527: 1, 548: 8, 637: 4, 645: 8, 658: 8, 665: 8, 666: 8, 674: 2, 682: 8, 683: 8, 689: 8, 723: 8, 758: 3, 768: 6, 783: 3, 851: 8, 855: 8, 1041: 8, 1055: 2, 1104: 4, 1105: 6, 1107: 4, 1108: 8, 1111: 4, 1227: 8, 1228: 8, 1247: 4, 1266: 8, 1273: 7, 1342: 1, 1376: 6, 1401: 8, 1474: 8, 1497: 3, 1534: 6, 1792: 8, 1821: 8, 1823: 8, 1837: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 2015: 8, 2016: 8, 2024: 8 + }], + CAR.NISSAN_LEAF: [{ + 2: 5, 42: 6, 264: 3, 361: 8, 372: 8, 384: 8, 389: 8, 403: 8, 459: 7, 460: 4, 470: 8, 520: 1, 569: 8, 581: 8, 634: 7, 640: 8, 644: 8, 645: 8, 646: 5, 658: 8, 682: 8, 683: 8, 689: 8, 724: 6, 758: 3, 761: 2, 783: 3, 852: 8, 853: 8, 856: 8, 861: 8, 944: 1, 976: 6, 1008: 7, 1011: 7, 1057: 3, 1227: 8, 1228: 8, 1261: 5, 1342: 1, 1354: 8, 1361: 8, 1459: 8, 1477: 8, 1497: 3, 1549: 8, 1573: 6, 1821: 8, 1837: 8, 1856: 8, 1859: 8, 1861: 8, 1864: 8, 1874: 8, 1888: 8, 1891: 8, 1893: 8, 1906: 8, 1947: 8, 1949: 8, 1979: 8, 1981: 8, 2016: 8, 2017: 8, 2021: 8, 643: 5, 1792: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 1988: 8, 2000: 8, 2001: 8, 2004: 8, 2005: 8, 2015: 8 + }, + { + 2: 5, 42: 8, 264: 3, 361: 8, 372: 8, 384: 8, 389: 8, 403: 8, 459: 7, 460: 4, 470: 8, 520: 1, 569: 8, 581: 8, 634: 7, 640: 8, 643: 5, 644: 8, 645: 8, 646: 5, 658: 8, 682: 8, 683: 8, 689: 8, 724: 6, 758: 3, 761: 2, 772: 8, 773: 6, 774: 7, 775: 8, 776: 6, 777: 7, 778: 6, 783: 3, 852: 8, 853: 8, 856: 8, 861: 8, 943: 8, 944: 1, 976: 6, 1008: 7, 1009: 8, 1010: 8, 1011: 7, 1012: 8, 1013: 8, 1019: 8, 1020: 8, 1021: 8, 1022: 8, 1057: 3, 1227: 8, 1228: 8, 1261: 5, 1342: 1, 1354: 8, 1361: 8, 1402: 8, 1459: 8, 1477: 8, 1497: 3, 1549: 8, 1573: 6, 1821: 8, 1837: 8 + }], + CAR.NISSAN_LEAF_IC: [{ + 2: 5, 42: 6, 264: 3, 282: 8, 361: 8, 372: 8, 384: 8, 389: 8, 403: 8, 459: 7, 460: 4, 470: 8, 520: 1, 569: 8, 581: 8, 634: 7, 640: 8, 643: 5, 644: 8, 645: 8, 646: 5, 658: 8, 682: 8, 683: 8, 689: 8, 756: 5, 758: 3, 761: 2, 783: 3, 830: 2, 852: 8, 853: 8, 856: 8, 861: 8, 943: 8, 944: 1, 1001: 6, 1057: 3, 1227: 8, 1228: 8, 1229: 8, 1342: 1, 1354: 8, 1361: 8, 1459: 8, 1477: 8, 1497: 3, 1514: 6, 1549: 8, 1573: 6, 1792: 8, 1821: 8, 1822: 8, 1837: 8, 1838: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 1988: 8, 2000: 8, 2001: 8, 2004: 8, 2005: 8, 2015: 8, 2016: 8, 2017: 8 + }], + CAR.NISSAN_ROGUE: [{ + 2: 5, 42: 6, 346: 6, 347: 5, 348: 8, 349: 7, 361: 8, 386: 8, 389: 8, 397: 8, 398: 8, 403: 8, 520: 2, 523: 6, 548: 8, 634: 7, 643: 5, 645: 8, 658: 8, 665: 8, 666: 8, 674: 2, 682: 8, 683: 8, 689: 8, 723: 8, 758: 3, 772: 8, 773: 6, 774: 7, 775: 8, 776: 6, 777: 7, 778: 6, 783: 3, 851: 8, 855: 8, 1041: 8, 1042: 8, 1055: 2, 1104: 4, 1105: 6, 1107: 4, 1108: 8, 1110: 7, 1111: 7, 1227: 8, 1228: 8, 1247: 4, 1266: 8, 1273: 7, 1342: 1, 1376: 6, 1401: 8, 1474: 2, 1497: 3, 1534: 7, 1792: 8, 1821: 8, 1823: 8, 1837: 8, 1839: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 1988: 8, 2000: 8, 2001: 8, 2004: 8, 2005: 8, 2015: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8 + }], + CAR.NISSAN_ALTIMA: [{ + 2: 5, 42: 6, 346: 6, 347: 5, 348: 8, 349: 7, 361: 8, 386: 8, 389: 8, 397: 8, 398: 8, 403: 8, 438: 8, 451: 8, 517: 8, 520: 2, 522: 8, 523: 6, 539: 8, 541: 7, 542: 8, 543: 8, 544: 8, 545: 8, 546: 8, 547: 8, 548: 8, 570: 8, 576: 8, 577: 8, 582: 8, 583: 8, 584: 8, 586: 8, 587: 8, 588: 8, 589: 8, 590: 8, 591: 8, 592: 8, 600: 8, 601: 8, 610: 8, 611: 8, 612: 8, 614: 8, 615: 8, 616: 8, 617: 8, 622: 8, 623: 8, 634: 7, 638: 8, 645: 8, 648: 5, 654: 6, 658: 8, 659: 8, 660: 8, 661: 8, 665: 8, 666: 8, 674: 2, 675: 8, 676: 8, 682: 8, 683: 8, 684: 8, 685: 8, 686: 8, 687: 8, 689: 8, 690: 8, 703: 8, 708: 7, 709: 7, 711: 7, 712: 7, 713: 7, 714: 8, 715: 8, 716: 8, 717: 7, 718: 7, 719: 7, 720: 7, 723: 8, 726: 7, 727: 7, 728: 7, 735: 8, 746: 8, 748: 6, 749: 6, 750: 8, 758: 3, 772: 8, 773: 6, 774: 7, 775: 8, 776: 6, 777: 7, 778: 6, 779: 7, 781: 7, 782: 7, 783: 3, 851: 8, 855: 5, 1001: 6, 1041: 8, 1042: 8, 1055: 3, 1100: 7, 1104: 4, 1105: 6, 1107: 4, 1108: 8, 1110: 7, 1111: 7, 1144: 7, 1145: 7, 1227: 8, 1228: 8, 1229: 8, 1232: 8, 1247: 4, 1258: 8, 1259: 8, 1266: 8, 1273: 7, 1306: 1, 1314: 8, 1323: 8, 1324: 8, 1342: 1, 1376: 8, 1401: 8, 1454: 8, 1497: 3, 1514: 6, 1526: 8, 1527: 5, 1792: 8, 1821: 8, 1823: 8, 1837: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 1988: 8, 2000: 8, 2001: 8, 2004: 8, 2005: 8, 2015: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8 + }], +} + +FW_VERSIONS = { + CAR.NISSAN_ALTIMA: { + (Ecu.fwdCamera, 0x707, None): [ + b'284N86CA1D', + ], + (Ecu.eps, 0x742, None): [ + b'6CA2B\xa9A\x02\x02G8A89P90D6A\x00\x00\x01\x80', + ], + (Ecu.engine, 0x7e0, None): [ + b'237109HE2B', + ], + (Ecu.gateway, 0x18dad0f1, None): [ + b'284U29HE0A', + ], + }, + CAR.NISSAN_LEAF: { + (Ecu.abs, 0x740, None): [ + b'476605SA1C', + b'476605SA7D', + b'476605SC2D', + b'476606WK7B', + b'476606WK9B', + ], + (Ecu.eps, 0x742, None): [ + b'5SA2A\x99A\x05\x02N123F\x15b\x00\x00\x00\x00\x00\x00\x00\x80', + b'5SA2A\xb7A\x05\x02N123F\x15\xa2\x00\x00\x00\x00\x00\x00\x00\x80', + b'5SN2A\xb7A\x05\x02N123F\x15\xa2\x00\x00\x00\x00\x00\x00\x00\x80', + b'5SN2A\xb7A\x05\x02N126F\x15\xb2\x00\x00\x00\x00\x00\x00\x00\x80', + ], + (Ecu.fwdCamera, 0x707, None): [ + b'5SA0ADB\x04\x18\x00\x00\x00\x00\x00_*6\x04\x94a\x00\x00\x00\x80', + b'5SA2ADB\x04\x18\x00\x00\x00\x00\x00_*6\x04\x94a\x00\x00\x00\x80', + b'6WK2ADB\x04\x18\x00\x00\x00\x00\x00R;1\x18\x99\x10\x00\x00\x00\x80', + b'6WK2BDB\x04\x18\x00\x00\x00\x00\x00R;1\x18\x99\x10\x00\x00\x00\x80', + b'6WK2CDB\x04\x18\x00\x00\x00\x00\x00R=1\x18\x99\x10\x00\x00\x00\x80', + ], + (Ecu.gateway, 0x18dad0f1, None): [ + b'284U25SA3C', + b'284U25SP0C', + b'284U25SP1C', + b'284U26WK0A', + b'284U26WK0C', + ], + }, + CAR.NISSAN_LEAF_IC: { + (Ecu.fwdCamera, 0x707, None): [ + b'5SH1BDB\x04\x18\x00\x00\x00\x00\x00_-?\x04\x91\xf2\x00\x00\x00\x80', + b'5SH4BDB\x04\x18\x00\x00\x00\x00\x00_-?\x04\x91\xf2\x00\x00\x00\x80', + b'5SK0ADB\x04\x18\x00\x00\x00\x00\x00_(5\x07\x9aQ\x00\x00\x00\x80', + ], + (Ecu.abs, 0x740, None): [ + b'476605SD2E', + b'476605SH1D', + b'476605SK2A', + ], + (Ecu.eps, 0x742, None): [ + b'5SH2A\x99A\x05\x02N123F\x15\x81\x00\x00\x00\x00\x00\x00\x00\x80', + b'5SH2C\xb7A\x05\x02N123F\x15\xa3\x00\x00\x00\x00\x00\x00\x00\x80', + b'5SK3A\x99A\x05\x02N123F\x15u\x00\x00\x00\x00\x00\x00\x00\x80', + ], + (Ecu.gateway, 0x18dad0f1, None): [ + b'284U25SF0C', + b'284U25SH3A', + b'284U25SK2D', + ], + }, + CAR.NISSAN_XTRAIL: { + (Ecu.fwdCamera, 0x707, None): [ + b'284N86FR2A', + ], + (Ecu.abs, 0x740, None): [ + b'6FU0AD\x11\x02\x00\x02e\x95e\x80iQ#\x01\x00\x00\x00\x00\x00\x80', + b'6FU1BD\x11\x02\x00\x02e\x95e\x80iX#\x01\x00\x00\x00\x00\x00\x80', + ], + (Ecu.eps, 0x742, None): [ + b'6FP2A\x99A\x05\x02N123F\x18\x02\x00\x00\x00\x00\x00\x00\x00\x80', + ], + (Ecu.combinationMeter, 0x743, None): [ + b'6FR2A\x18B\x05\x17\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x80', + ], + (Ecu.engine, 0x7e0, None): [ + b'6FR9A\xa0A\x06\x04\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x80', + b'6FU9B\xa0A\x06\x04\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x80', + ], + (Ecu.gateway, 0x18dad0f1, None): [ + b'284U26FR0E', + ], + }, +} diff --git a/car/nissan/interface.py b/car/nissan/interface.py new file mode 100644 index 0000000000..2e9a990610 --- /dev/null +++ b/car/nissan/interface.py @@ -0,0 +1,44 @@ +from cereal import car +from panda import Panda +from openpilot.selfdrive.car import create_button_events, get_safety_config +from openpilot.selfdrive.car.interfaces import CarInterfaceBase +from openpilot.selfdrive.car.nissan.values import CAR + +ButtonType = car.CarState.ButtonEvent.Type + + +class CarInterface(CarInterfaceBase): + + @staticmethod + def _get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs): + ret.carName = "nissan" + ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.nissan)] + ret.autoResumeSng = False + + ret.steerLimitTimer = 1.0 + + ret.steerActuatorDelay = 0.1 + + ret.steerControlType = car.CarParams.SteerControlType.angle + ret.radarUnavailable = True + + if candidate == CAR.NISSAN_ALTIMA: + # Altima has EPS on C-CAN unlike the others that have it on V-CAN + ret.safetyConfigs[0].safetyParam |= Panda.FLAG_NISSAN_ALT_EPS_BUS + + return ret + + # returns a car.CarState + def _update(self, c): + ret = self.CS.update(self.cp, self.cp_adas, self.cp_cam) + + ret.buttonEvents = create_button_events(self.CS.distance_button, self.CS.prev_distance_button, {1: ButtonType.gapAdjustCruise}) + + events = self.create_common_events(ret, extra_gears=[car.CarState.GearShifter.brake]) + + if self.CS.lkas_enabled: + events.add(car.CarEvent.EventName.invalidLkasSetting) + + ret.events = events.to_msg() + + return ret diff --git a/car/nissan/nissancan.py b/car/nissan/nissancan.py new file mode 100644 index 0000000000..b9a1b4f843 --- /dev/null +++ b/car/nissan/nissancan.py @@ -0,0 +1,154 @@ +import crcmod +from openpilot.selfdrive.car.nissan.values import CAR + +# TODO: add this checksum to the CANPacker +nissan_checksum = crcmod.mkCrcFun(0x11d, initCrc=0x00, rev=False, xorOut=0xff) + + +def create_steering_control(packer, apply_steer, frame, steer_on, lkas_max_torque): + values = { + "COUNTER": frame % 0x10, + "DESIRED_ANGLE": apply_steer, + "SET_0x80_2": 0x80, + "SET_0x80": 0x80, + "MAX_TORQUE": lkas_max_torque if steer_on else 0, + "LKA_ACTIVE": steer_on, + } + + dat = packer.make_can_msg("LKAS", 0, values)[2] + + values["CHECKSUM"] = nissan_checksum(dat[:7]) + return packer.make_can_msg("LKAS", 0, values) + + +def create_acc_cancel_cmd(packer, car_fingerprint, cruise_throttle_msg): + values = {s: cruise_throttle_msg[s] for s in [ + "COUNTER", + "PROPILOT_BUTTON", + "CANCEL_BUTTON", + "GAS_PEDAL_INVERTED", + "SET_BUTTON", + "RES_BUTTON", + "FOLLOW_DISTANCE_BUTTON", + "NO_BUTTON_PRESSED", + "GAS_PEDAL", + "USER_BRAKE_PRESSED", + "NEW_SIGNAL_2", + "GAS_PRESSED_INVERTED", + "unsure1", + "unsure2", + "unsure3", + ]} + can_bus = 1 if car_fingerprint == CAR.NISSAN_ALTIMA else 2 + + values["CANCEL_BUTTON"] = 1 + values["NO_BUTTON_PRESSED"] = 0 + values["PROPILOT_BUTTON"] = 0 + values["SET_BUTTON"] = 0 + values["RES_BUTTON"] = 0 + values["FOLLOW_DISTANCE_BUTTON"] = 0 + + return packer.make_can_msg("CRUISE_THROTTLE", can_bus, values) + + +def create_cancel_msg(packer, cancel_msg, cruise_cancel): + values = {s: cancel_msg[s] for s in [ + "CANCEL_SEATBELT", + "NEW_SIGNAL_1", + "NEW_SIGNAL_2", + "NEW_SIGNAL_3", + ]} + + if cruise_cancel: + values["CANCEL_SEATBELT"] = 1 + + return packer.make_can_msg("CANCEL_MSG", 2, values) + + +def create_lkas_hud_msg(packer, lkas_hud_msg, enabled, left_line, right_line, left_lane_depart, right_lane_depart): + values = {s: lkas_hud_msg[s] for s in [ + "LARGE_WARNING_FLASHING", + "SIDE_RADAR_ERROR_FLASHING1", + "SIDE_RADAR_ERROR_FLASHING2", + "LEAD_CAR", + "LEAD_CAR_ERROR", + "FRONT_RADAR_ERROR", + "FRONT_RADAR_ERROR_FLASHING", + "SIDE_RADAR_ERROR_FLASHING3", + "LKAS_ERROR_FLASHING", + "SAFETY_SHIELD_ACTIVE", + "RIGHT_LANE_GREEN_FLASH", + "LEFT_LANE_GREEN_FLASH", + "FOLLOW_DISTANCE", + "AUDIBLE_TONE", + "SPEED_SET_ICON", + "SMALL_STEERING_WHEEL_ICON", + "unknown59", + "unknown55", + "unknown26", + "unknown28", + "unknown31", + "SET_SPEED", + "unknown43", + "unknown08", + "unknown05", + "unknown02", + ]} + + values["RIGHT_LANE_YELLOW_FLASH"] = 1 if right_lane_depart else 0 + values["LEFT_LANE_YELLOW_FLASH"] = 1 if left_lane_depart else 0 + + values["LARGE_STEERING_WHEEL_ICON"] = 2 if enabled else 0 + values["RIGHT_LANE_GREEN"] = 1 if right_line and enabled else 0 + values["LEFT_LANE_GREEN"] = 1 if left_line and enabled else 0 + + return packer.make_can_msg("PROPILOT_HUD", 0, values) + + +def create_lkas_hud_info_msg(packer, lkas_hud_info_msg, steer_hud_alert): + values = {s: lkas_hud_info_msg[s] for s in [ + "NA_HIGH_ACCEL_TEMP", + "SIDE_RADAR_NA_HIGH_CABIN_TEMP", + "SIDE_RADAR_MALFUNCTION", + "LKAS_MALFUNCTION", + "FRONT_RADAR_MALFUNCTION", + "SIDE_RADAR_NA_CLEAN_REAR_CAMERA", + "NA_POOR_ROAD_CONDITIONS", + "CURRENTLY_UNAVAILABLE", + "SAFETY_SHIELD_OFF", + "FRONT_COLLISION_NA_FRONT_RADAR_OBSTRUCTION", + "PEDAL_MISSAPPLICATION_SYSTEM_ACTIVATED", + "SIDE_IMPACT_NA_RADAR_OBSTRUCTION", + "WARNING_DO_NOT_ENTER", + "SIDE_IMPACT_SYSTEM_OFF", + "SIDE_IMPACT_MALFUNCTION", + "FRONT_COLLISION_MALFUNCTION", + "SIDE_RADAR_MALFUNCTION2", + "LKAS_MALFUNCTION2", + "FRONT_RADAR_MALFUNCTION2", + "PROPILOT_NA_MSGS", + "BOTTOM_MSG", + "HANDS_ON_WHEEL_WARNING", + "WARNING_STEP_ON_BRAKE_NOW", + "PROPILOT_NA_FRONT_CAMERA_OBSTRUCTED", + "PROPILOT_NA_HIGH_CABIN_TEMP", + "WARNING_PROPILOT_MALFUNCTION", + "ACC_UNAVAILABLE_HIGH_CABIN_TEMP", + "ACC_NA_FRONT_CAMERA_IMPARED", + "unknown07", + "unknown10", + "unknown15", + "unknown23", + "unknown19", + "unknown31", + "unknown32", + "unknown46", + "unknown61", + "unknown55", + "unknown50", + ]} + + if steer_hud_alert: + values["HANDS_ON_WHEEL_WARNING"] = 1 + + return packer.make_can_msg("PROPILOT_HUD_INFO_MSG", 0, values) diff --git a/car/nissan/radar_interface.py b/car/nissan/radar_interface.py new file mode 100644 index 0000000000..e654bd61fd --- /dev/null +++ b/car/nissan/radar_interface.py @@ -0,0 +1,4 @@ +from openpilot.selfdrive.car.interfaces import RadarInterfaceBase + +class RadarInterface(RadarInterfaceBase): + pass diff --git a/car/nissan/values.py b/car/nissan/values.py new file mode 100644 index 0000000000..eecffb21bc --- /dev/null +++ b/car/nissan/values.py @@ -0,0 +1,107 @@ +from dataclasses import dataclass, field + +from cereal import car +from panda.python import uds +from openpilot.selfdrive.car import AngleRateLimit, CarSpecs, DbcDict, PlatformConfig, Platforms, dbc_dict +from openpilot.selfdrive.car.docs_definitions import CarDocs, CarHarness, CarParts +from openpilot.selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries + +Ecu = car.CarParams.Ecu + + +class CarControllerParams: + ANGLE_RATE_LIMIT_UP = AngleRateLimit(speed_bp=[0., 5., 15.], angle_v=[5., .8, .15]) + ANGLE_RATE_LIMIT_DOWN = AngleRateLimit(speed_bp=[0., 5., 15.], angle_v=[5., 3.5, 0.4]) + LKAS_MAX_TORQUE = 1 # A value of 1 is easy to overpower + STEER_THRESHOLD = 1.0 + + def __init__(self, CP): + pass + + +@dataclass +class NissanCarDocs(CarDocs): + package: str = "ProPILOT Assist" + car_parts: CarParts = field(default_factory=CarParts.common([CarHarness.nissan_a])) + + +@dataclass(frozen=True) +class NissanCarSpecs(CarSpecs): + centerToFrontRatio: float = 0.44 + steerRatio: float = 17. + + +@dataclass +class NissanPlatformConfig(PlatformConfig): + dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict('nissan_x_trail_2017_generated', None)) + + +class CAR(Platforms): + NISSAN_XTRAIL = NissanPlatformConfig( + [NissanCarDocs("Nissan X-Trail 2017")], + NissanCarSpecs(mass=1610, wheelbase=2.705) + ) + NISSAN_LEAF = NissanPlatformConfig( + [NissanCarDocs("Nissan Leaf 2018-23", video_link="https://youtu.be/vaMbtAh_0cY")], + NissanCarSpecs(mass=1610, wheelbase=2.705), + dbc_dict('nissan_leaf_2018_generated', None), + ) + # Leaf with ADAS ECU found behind instrument cluster instead of glovebox + # Currently the only known difference between them is the inverted seatbelt signal. + NISSAN_LEAF_IC = NISSAN_LEAF.override(car_docs=[]) + NISSAN_ROGUE = NissanPlatformConfig( + [NissanCarDocs("Nissan Rogue 2018-20")], + NissanCarSpecs(mass=1610, wheelbase=2.705) + ) + NISSAN_ALTIMA = NissanPlatformConfig( + [NissanCarDocs("Nissan Altima 2019-20", car_parts=CarParts.common([CarHarness.nissan_b]))], + NissanCarSpecs(mass=1492, wheelbase=2.824) + ) + + +DBC = CAR.create_dbc_map() + +# Default diagnostic session +NISSAN_DIAGNOSTIC_REQUEST_KWP = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL, 0x81]) +NISSAN_DIAGNOSTIC_RESPONSE_KWP = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL + 0x40, 0x81]) + +# Manufacturer specific +NISSAN_DIAGNOSTIC_REQUEST_KWP_2 = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL, 0xda]) +NISSAN_DIAGNOSTIC_RESPONSE_KWP_2 = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL + 0x40, 0xda]) + +NISSAN_VERSION_REQUEST_KWP = b'\x21\x83' +NISSAN_VERSION_RESPONSE_KWP = b'\x61\x83' + +NISSAN_RX_OFFSET = 0x20 + +FW_QUERY_CONFIG = FwQueryConfig( + requests=[request for bus, logging in ((0, False), (1, True)) for request in [ + Request( + [NISSAN_DIAGNOSTIC_REQUEST_KWP, NISSAN_VERSION_REQUEST_KWP], + [NISSAN_DIAGNOSTIC_RESPONSE_KWP, NISSAN_VERSION_RESPONSE_KWP], + bus=bus, + logging=logging, + ), + Request( + [NISSAN_DIAGNOSTIC_REQUEST_KWP, NISSAN_VERSION_REQUEST_KWP], + [NISSAN_DIAGNOSTIC_RESPONSE_KWP, NISSAN_VERSION_RESPONSE_KWP], + rx_offset=NISSAN_RX_OFFSET, + bus=bus, + logging=logging, + ), + # Rogue's engine solely responds to this + Request( + [NISSAN_DIAGNOSTIC_REQUEST_KWP_2, NISSAN_VERSION_REQUEST_KWP], + [NISSAN_DIAGNOSTIC_RESPONSE_KWP_2, NISSAN_VERSION_RESPONSE_KWP], + bus=bus, + logging=logging, + ), + Request( + [StdQueries.MANUFACTURER_SOFTWARE_VERSION_REQUEST], + [StdQueries.MANUFACTURER_SOFTWARE_VERSION_RESPONSE], + rx_offset=NISSAN_RX_OFFSET, + bus=bus, + logging=logging, + ), + ]], +) diff --git a/car/subaru/__init__.py b/car/subaru/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/car/subaru/carcontroller.py b/car/subaru/carcontroller.py new file mode 100644 index 0000000000..d89ae8c639 --- /dev/null +++ b/car/subaru/carcontroller.py @@ -0,0 +1,144 @@ +from openpilot.common.numpy_fast import clip, interp +from opendbc.can.packer import CANPacker +from openpilot.selfdrive.car import apply_driver_steer_torque_limits, common_fault_avoidance +from openpilot.selfdrive.car.interfaces import CarControllerBase +from openpilot.selfdrive.car.subaru import subarucan +from openpilot.selfdrive.car.subaru.values import DBC, GLOBAL_ES_ADDR, CanBus, CarControllerParams, SubaruFlags + +# FIXME: These limits aren't exact. The real limit is more than likely over a larger time period and +# involves the total steering angle change rather than rate, but these limits work well for now +MAX_STEER_RATE = 25 # deg/s +MAX_STEER_RATE_FRAMES = 7 # tx control frames needed before torque can be cut + + +class CarController(CarControllerBase): + def __init__(self, dbc_name, CP, VM): + self.CP = CP + self.apply_steer_last = 0 + self.frame = 0 + + self.cruise_button_prev = 0 + self.steer_rate_counter = 0 + + self.p = CarControllerParams(CP) + self.packer = CANPacker(DBC[CP.carFingerprint]['pt']) + + def update(self, CC, CS, now_nanos): + actuators = CC.actuators + hud_control = CC.hudControl + pcm_cancel_cmd = CC.cruiseControl.cancel + + can_sends = [] + + # *** steering *** + if (self.frame % self.p.STEER_STEP) == 0: + apply_steer = int(round(actuators.steer * self.p.STEER_MAX)) + + # limits due to driver torque + + new_steer = int(round(apply_steer)) + apply_steer = apply_driver_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.p) + + if not CC.latActive: + apply_steer = 0 + + if self.CP.flags & SubaruFlags.PREGLOBAL: + can_sends.append(subarucan.create_preglobal_steering_control(self.packer, self.frame // self.p.STEER_STEP, apply_steer, CC.latActive)) + else: + apply_steer_req = CC.latActive + + if self.CP.flags & SubaruFlags.STEER_RATE_LIMITED: + # Steering rate fault prevention + self.steer_rate_counter, apply_steer_req = \ + common_fault_avoidance(abs(CS.out.steeringRateDeg) > MAX_STEER_RATE, apply_steer_req, + self.steer_rate_counter, MAX_STEER_RATE_FRAMES) + + can_sends.append(subarucan.create_steering_control(self.packer, apply_steer, apply_steer_req)) + + self.apply_steer_last = apply_steer + + # *** longitudinal *** + + if CC.longActive: + apply_throttle = int(round(interp(actuators.accel, CarControllerParams.THROTTLE_LOOKUP_BP, CarControllerParams.THROTTLE_LOOKUP_V))) + apply_rpm = int(round(interp(actuators.accel, CarControllerParams.RPM_LOOKUP_BP, CarControllerParams.RPM_LOOKUP_V))) + apply_brake = int(round(interp(actuators.accel, CarControllerParams.BRAKE_LOOKUP_BP, CarControllerParams.BRAKE_LOOKUP_V))) + + # limit min and max values + cruise_throttle = clip(apply_throttle, CarControllerParams.THROTTLE_MIN, CarControllerParams.THROTTLE_MAX) + cruise_rpm = clip(apply_rpm, CarControllerParams.RPM_MIN, CarControllerParams.RPM_MAX) + cruise_brake = clip(apply_brake, CarControllerParams.BRAKE_MIN, CarControllerParams.BRAKE_MAX) + else: + cruise_throttle = CarControllerParams.THROTTLE_INACTIVE + cruise_rpm = CarControllerParams.RPM_MIN + cruise_brake = CarControllerParams.BRAKE_MIN + + # *** alerts and pcm cancel *** + if self.CP.flags & SubaruFlags.PREGLOBAL: + if self.frame % 5 == 0: + # 1 = main, 2 = set shallow, 3 = set deep, 4 = resume shallow, 5 = resume deep + # disengage ACC when OP is disengaged + if pcm_cancel_cmd: + cruise_button = 1 + # turn main on if off and past start-up state + elif not CS.out.cruiseState.available and CS.ready: + cruise_button = 1 + else: + cruise_button = CS.cruise_button + + # unstick previous mocked button press + if cruise_button == 1 and self.cruise_button_prev == 1: + cruise_button = 0 + self.cruise_button_prev = cruise_button + + can_sends.append(subarucan.create_preglobal_es_distance(self.packer, cruise_button, CS.es_distance_msg)) + + else: + if self.frame % 10 == 0: + can_sends.append(subarucan.create_es_dashstatus(self.packer, self.frame // 10, CS.es_dashstatus_msg, CC.enabled, + self.CP.openpilotLongitudinalControl, CC.longActive, hud_control.leadVisible)) + + can_sends.append(subarucan.create_es_lkas_state(self.packer, self.frame // 10, CS.es_lkas_state_msg, CC.enabled, hud_control.visualAlert, + hud_control.leftLaneVisible, hud_control.rightLaneVisible, + hud_control.leftLaneDepart, hud_control.rightLaneDepart)) + + if self.CP.flags & SubaruFlags.SEND_INFOTAINMENT: + can_sends.append(subarucan.create_es_infotainment(self.packer, self.frame // 10, CS.es_infotainment_msg, hud_control.visualAlert)) + + if self.CP.openpilotLongitudinalControl: + if self.frame % 5 == 0: + can_sends.append(subarucan.create_es_status(self.packer, self.frame // 5, CS.es_status_msg, + self.CP.openpilotLongitudinalControl, CC.longActive, cruise_rpm)) + + can_sends.append(subarucan.create_es_brake(self.packer, self.frame // 5, CS.es_brake_msg, + self.CP.openpilotLongitudinalControl, CC.longActive, cruise_brake)) + + can_sends.append(subarucan.create_es_distance(self.packer, self.frame // 5, CS.es_distance_msg, 0, pcm_cancel_cmd, + self.CP.openpilotLongitudinalControl, cruise_brake > 0, cruise_throttle)) + else: + if pcm_cancel_cmd: + if not (self.CP.flags & SubaruFlags.HYBRID): + bus = CanBus.alt if self.CP.flags & SubaruFlags.GLOBAL_GEN2 else CanBus.main + can_sends.append(subarucan.create_es_distance(self.packer, CS.es_distance_msg["COUNTER"] + 1, CS.es_distance_msg, bus, pcm_cancel_cmd)) + + if self.CP.flags & SubaruFlags.DISABLE_EYESIGHT: + # Tester present (keeps eyesight disabled) + if self.frame % 100 == 0: + can_sends.append([GLOBAL_ES_ADDR, 0, b"\x02\x3E\x80\x00\x00\x00\x00\x00", CanBus.camera]) + + # Create all of the other eyesight messages to keep the rest of the car happy when eyesight is disabled + if self.frame % 5 == 0: + can_sends.append(subarucan.create_es_highbeamassist(self.packer)) + + if self.frame % 10 == 0: + can_sends.append(subarucan.create_es_static_1(self.packer)) + + if self.frame % 2 == 0: + can_sends.append(subarucan.create_es_static_2(self.packer)) + + new_actuators = actuators.as_builder() + new_actuators.steer = self.apply_steer_last / self.p.STEER_MAX + new_actuators.steerOutputCan = self.apply_steer_last + + self.frame += 1 + return new_actuators, can_sends diff --git a/car/subaru/carstate.py b/car/subaru/carstate.py new file mode 100644 index 0000000000..821ff2c151 --- /dev/null +++ b/car/subaru/carstate.py @@ -0,0 +1,229 @@ +import copy +from cereal import car +from opendbc.can.can_define import CANDefine +from openpilot.common.conversions import Conversions as CV +from openpilot.selfdrive.car.interfaces import CarStateBase +from opendbc.can.parser import CANParser +from openpilot.selfdrive.car.subaru.values import DBC, CanBus, SubaruFlags +from openpilot.selfdrive.car import CanSignalRateCalculator + + +class CarState(CarStateBase): + def __init__(self, CP): + super().__init__(CP) + can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) + self.shifter_values = can_define.dv["Transmission"]["Gear"] + + self.angle_rate_calulator = CanSignalRateCalculator(50) + + def update(self, cp, cp_cam, cp_body): + ret = car.CarState.new_message() + + throttle_msg = cp.vl["Throttle"] if not (self.CP.flags & SubaruFlags.HYBRID) else cp_body.vl["Throttle_Hybrid"] + ret.gas = throttle_msg["Throttle_Pedal"] / 255. + + ret.gasPressed = ret.gas > 1e-5 + if self.CP.flags & SubaruFlags.PREGLOBAL: + ret.brakePressed = cp.vl["Brake_Pedal"]["Brake_Pedal"] > 0 + else: + cp_brakes = cp_body if self.CP.flags & SubaruFlags.GLOBAL_GEN2 else cp + ret.brakePressed = cp_brakes.vl["Brake_Status"]["Brake"] == 1 + + cp_es_distance = cp_body if self.CP.flags & (SubaruFlags.GLOBAL_GEN2 | SubaruFlags.HYBRID) else cp_cam + if not (self.CP.flags & SubaruFlags.HYBRID): + eyesight_fault = bool(cp_es_distance.vl["ES_Distance"]["Cruise_Fault"]) + + # if openpilot is controlling long, an eyesight fault is a non-critical fault. otherwise it's an ACC fault + if self.CP.openpilotLongitudinalControl: + ret.carFaultedNonCritical = eyesight_fault + else: + ret.accFaulted = eyesight_fault + + cp_wheels = cp_body if self.CP.flags & SubaruFlags.GLOBAL_GEN2 else cp + ret.wheelSpeeds = self.get_wheel_speeds( + cp_wheels.vl["Wheel_Speeds"]["FL"], + cp_wheels.vl["Wheel_Speeds"]["FR"], + cp_wheels.vl["Wheel_Speeds"]["RL"], + cp_wheels.vl["Wheel_Speeds"]["RR"], + ) + ret.vEgoRaw = (ret.wheelSpeeds.fl + ret.wheelSpeeds.fr + ret.wheelSpeeds.rl + ret.wheelSpeeds.rr) / 4. + ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) + ret.standstill = ret.vEgoRaw == 0 + + # continuous blinker signals for assisted lane change + ret.leftBlinker, ret.rightBlinker = self.update_blinker_from_lamp(50, cp.vl["Dashlights"]["LEFT_BLINKER"], + cp.vl["Dashlights"]["RIGHT_BLINKER"]) + + if self.CP.enableBsm: + ret.leftBlindspot = (cp.vl["BSD_RCTA"]["L_ADJACENT"] == 1) or (cp.vl["BSD_RCTA"]["L_APPROACHING"] == 1) + ret.rightBlindspot = (cp.vl["BSD_RCTA"]["R_ADJACENT"] == 1) or (cp.vl["BSD_RCTA"]["R_APPROACHING"] == 1) + + cp_transmission = cp_body if self.CP.flags & SubaruFlags.HYBRID else cp + can_gear = int(cp_transmission.vl["Transmission"]["Gear"]) + ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(can_gear, None)) + + ret.steeringAngleDeg = cp.vl["Steering_Torque"]["Steering_Angle"] + + if not (self.CP.flags & SubaruFlags.PREGLOBAL): + # ideally we get this from the car, but unclear if it exists. diagnostic software doesn't even have it + ret.steeringRateDeg = self.angle_rate_calulator.update(ret.steeringAngleDeg, cp.vl["Steering_Torque"]["COUNTER"]) + + ret.steeringTorque = cp.vl["Steering_Torque"]["Steer_Torque_Sensor"] + ret.steeringTorqueEps = cp.vl["Steering_Torque"]["Steer_Torque_Output"] + + steer_threshold = 75 if self.CP.flags & SubaruFlags.PREGLOBAL else 80 + ret.steeringPressed = abs(ret.steeringTorque) > steer_threshold + + cp_cruise = cp_body if self.CP.flags & SubaruFlags.GLOBAL_GEN2 else cp + if self.CP.flags & SubaruFlags.HYBRID: + ret.cruiseState.enabled = cp_cam.vl["ES_DashStatus"]['Cruise_Activated'] != 0 + ret.cruiseState.available = cp_cam.vl["ES_DashStatus"]['Cruise_On'] != 0 + else: + ret.cruiseState.enabled = cp_cruise.vl["CruiseControl"]["Cruise_Activated"] != 0 + ret.cruiseState.available = cp_cruise.vl["CruiseControl"]["Cruise_On"] != 0 + ret.cruiseState.speed = cp_cam.vl["ES_DashStatus"]["Cruise_Set_Speed"] * CV.KPH_TO_MS + + if (self.CP.flags & SubaruFlags.PREGLOBAL and cp.vl["Dash_State2"]["UNITS"] == 1) or \ + (not (self.CP.flags & SubaruFlags.PREGLOBAL) and cp.vl["Dashlights"]["UNITS"] == 1): + ret.cruiseState.speed *= CV.MPH_TO_KPH + + ret.seatbeltUnlatched = cp.vl["Dashlights"]["SEATBELT_FL"] == 1 + ret.doorOpen = any([cp.vl["BodyInfo"]["DOOR_OPEN_RR"], + cp.vl["BodyInfo"]["DOOR_OPEN_RL"], + cp.vl["BodyInfo"]["DOOR_OPEN_FR"], + cp.vl["BodyInfo"]["DOOR_OPEN_FL"]]) + ret.steerFaultPermanent = cp.vl["Steering_Torque"]["Steer_Error_1"] == 1 + + if self.CP.flags & SubaruFlags.PREGLOBAL: + self.cruise_button = cp_cam.vl["ES_Distance"]["Cruise_Button"] + self.ready = not cp_cam.vl["ES_DashStatus"]["Not_Ready_Startup"] + else: + ret.steerFaultTemporary = cp.vl["Steering_Torque"]["Steer_Warning"] == 1 + ret.cruiseState.nonAdaptive = cp_cam.vl["ES_DashStatus"]["Conventional_Cruise"] == 1 + ret.cruiseState.standstill = cp_cam.vl["ES_DashStatus"]["Cruise_State"] == 3 + ret.stockFcw = (cp_cam.vl["ES_LKAS_State"]["LKAS_Alert"] == 1) or \ + (cp_cam.vl["ES_LKAS_State"]["LKAS_Alert"] == 2) + + self.es_lkas_state_msg = copy.copy(cp_cam.vl["ES_LKAS_State"]) + cp_es_brake = cp_body if self.CP.flags & SubaruFlags.GLOBAL_GEN2 else cp_cam + self.es_brake_msg = copy.copy(cp_es_brake.vl["ES_Brake"]) + cp_es_status = cp_body if self.CP.flags & SubaruFlags.GLOBAL_GEN2 else cp_cam + + # TODO: Hybrid cars don't have ES_Distance, need a replacement + if not (self.CP.flags & SubaruFlags.HYBRID): + # 8 is known AEB, there are a few other values related to AEB we ignore + ret.stockAeb = (cp_es_distance.vl["ES_Brake"]["AEB_Status"] == 8) and \ + (cp_es_distance.vl["ES_Brake"]["Brake_Pressure"] != 0) + + self.es_status_msg = copy.copy(cp_es_status.vl["ES_Status"]) + self.cruise_control_msg = copy.copy(cp_cruise.vl["CruiseControl"]) + + if not (self.CP.flags & SubaruFlags.HYBRID): + self.es_distance_msg = copy.copy(cp_es_distance.vl["ES_Distance"]) + + self.es_dashstatus_msg = copy.copy(cp_cam.vl["ES_DashStatus"]) + if self.CP.flags & SubaruFlags.SEND_INFOTAINMENT: + self.es_infotainment_msg = copy.copy(cp_cam.vl["ES_Infotainment"]) + + return ret + + @staticmethod + def get_common_global_body_messages(CP): + messages = [ + ("Wheel_Speeds", 50), + ("Brake_Status", 50), + ] + + if not (CP.flags & SubaruFlags.HYBRID): + messages.append(("CruiseControl", 20)) + + return messages + + @staticmethod + def get_common_global_es_messages(CP): + messages = [ + ("ES_Brake", 20), + ] + + if not (CP.flags & SubaruFlags.HYBRID): + messages += [ + ("ES_Distance", 20), + ("ES_Status", 20) + ] + + return messages + + @staticmethod + def get_common_preglobal_body_messages(): + messages = [ + ("CruiseControl", 50), + ("Wheel_Speeds", 50), + ("Dash_State2", 1), + ] + + return messages + + @staticmethod + def get_can_parser(CP): + messages = [ + # sig_address, frequency + ("Dashlights", 10), + ("Steering_Torque", 50), + ("BodyInfo", 1), + ("Brake_Pedal", 50), + ] + + if not (CP.flags & SubaruFlags.HYBRID): + messages += [ + ("Throttle", 100), + ("Transmission", 100) + ] + + if CP.enableBsm: + messages.append(("BSD_RCTA", 17)) + + if not (CP.flags & SubaruFlags.PREGLOBAL): + if not (CP.flags & SubaruFlags.GLOBAL_GEN2): + messages += CarState.get_common_global_body_messages(CP) + else: + messages += CarState.get_common_preglobal_body_messages() + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus.main) + + @staticmethod + def get_cam_can_parser(CP): + if CP.flags & SubaruFlags.PREGLOBAL: + messages = [ + ("ES_DashStatus", 20), + ("ES_Distance", 20), + ] + else: + messages = [ + ("ES_DashStatus", 10), + ("ES_LKAS_State", 10), + ] + + if not (CP.flags & SubaruFlags.GLOBAL_GEN2): + messages += CarState.get_common_global_es_messages(CP) + + if CP.flags & SubaruFlags.SEND_INFOTAINMENT: + messages.append(("ES_Infotainment", 10)) + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus.camera) + + @staticmethod + def get_body_can_parser(CP): + messages = [] + + if CP.flags & SubaruFlags.GLOBAL_GEN2: + messages += CarState.get_common_global_body_messages(CP) + messages += CarState.get_common_global_es_messages(CP) + + if CP.flags & SubaruFlags.HYBRID: + messages += [ + ("Throttle_Hybrid", 40), + ("Transmission", 100) + ] + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus.alt) + diff --git a/car/subaru/fingerprints.py b/car/subaru/fingerprints.py new file mode 100644 index 0000000000..10c713501f --- /dev/null +++ b/car/subaru/fingerprints.py @@ -0,0 +1,563 @@ +from cereal import car +from openpilot.selfdrive.car.subaru.values import CAR + +Ecu = car.CarParams.Ecu + +FW_VERSIONS = { + CAR.SUBARU_ASCENT: { + (Ecu.abs, 0x7b0, None): [ + b'\xa5 \x19\x02\x00', + b'\xa5 !\x02\x00', + ], + (Ecu.eps, 0x746, None): [ + b'\x05\xc0\xd0\x00', + b'\x85\xc0\xd0\x00', + b'\x95\xc0\xd0\x00', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\x00\x00d\xb9\x00\x00\x00\x00', + b'\x00\x00d\xb9\x1f@ \x10', + b'\x00\x00e@\x00\x00\x00\x00', + b'\x00\x00e@\x1f@ $', + b"\x00\x00e~\x1f@ '", + ], + (Ecu.engine, 0x7e0, None): [ + b'\xbb,\xa0t\x07', + b'\xd1,\xa0q\x07', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\x00>\xf0\x00\x00', + b'\x00\xfe\xf7\x00\x00', + b'\x01\xfe\xf7\x00\x00', + b'\x01\xfe\xf9\x00\x00', + b'\x01\xfe\xfa\x00\x00', + ], + }, + CAR.SUBARU_ASCENT_2023: { + (Ecu.abs, 0x7b0, None): [ + b'\xa5 #\x03\x00', + ], + (Ecu.eps, 0x746, None): [ + b'%\xc0\xd0\x11', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\x05!\x08\x1dK\x05!\x08\x01/', + ], + (Ecu.engine, 0x7a2, None): [ + b'\xe5,\xa0P\x07', + ], + (Ecu.transmission, 0x7a3, None): [ + b'\x04\xfe\xf3\x00\x00', + ], + }, + CAR.SUBARU_LEGACY: { + (Ecu.abs, 0x7b0, None): [ + b'\xa1 \x02\x01', + b'\xa1 \x02\x02', + b'\xa1 \x03\x03', + b'\xa1 \x04\x01', + ], + (Ecu.eps, 0x746, None): [ + b'\x9b\xc0\x11\x00', + b'\x9b\xc0\x11\x02', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\x00\x00e\x80\x00\x1f@ \x19\x00', + b'\x00\x00e\x9a\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xde"a0\x07', + b'\xde,\xa0@\x07', + b'\xe2"aq\x07', + b'\xe2,\xa0@\x07', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xa5\xf6\x05@\x00', + b'\xa5\xfe\xc7@\x00', + b'\xa7\xf6\x04@\x00', + b'\xa7\xfe\xc4@\x00', + ], + }, + CAR.SUBARU_IMPREZA: { + (Ecu.abs, 0x7b0, None): [ + b'z\x84\x19\x90\x00', + b'z\x94\x08\x90\x00', + b'z\x94\x08\x90\x01', + b'z\x94\x0c\x90\x00', + b'z\x94\x0c\x90\x01', + b'z\x94.\x90\x00', + b'z\x94?\x90\x00', + b'z\x9c\x19\x80\x01', + b'\xa2 \x185\x00', + b'\xa2 \x193\x00', + b'\xa2 \x194\x00', + b'\xa2 \x19`\x00', + ], + (Ecu.eps, 0x746, None): [ + b'z\xc0\x00\x00', + b'z\xc0\x04\x00', + b'z\xc0\x08\x00', + b'z\xc0\n\x00', + b'z\xc0\x0c\x00', + b'\x8a\xc0\x00\x00', + b'\x8a\xc0\x10\x00', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\x00\x00c\xf4\x00\x00\x00\x00', + b'\x00\x00c\xf4\x1f@ \x07', + b'\x00\x00d)\x00\x00\x00\x00', + b'\x00\x00d)\x1f@ \x07', + b'\x00\x00dd\x00\x00\x00\x00', + b'\x00\x00dd\x1f@ \x0e', + b'\x00\x00d\xb5\x1f@ \x0e', + b'\x00\x00d\xdc\x00\x00\x00\x00', + b'\x00\x00d\xdc\x1f@ \x0e', + b'\x00\x00e\x02\x1f@ \x14', + b'\x00\x00e\x1c\x00\x00\x00\x00', + b'\x00\x00e\x1c\x1f@ \x14', + b'\x00\x00e+\x00\x00\x00\x00', + b'\x00\x00e+\x1f@ \x14', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xaa\x00Bu\x07', + b'\xaa\x01bt\x07', + b'\xaa!`u\x07', + b'\xaa!au\x07', + b'\xaa!av\x07', + b'\xaa!aw\x07', + b'\xaa!dq\x07', + b'\xaa!ds\x07', + b'\xaa!dt\x07', + b'\xaaafs\x07', + b'\xbe!as\x07', + b'\xbe!at\x07', + b'\xbeacr\x07', + b'\xc5!`r\x07', + b'\xc5!`s\x07', + b'\xc5!ap\x07', + b'\xc5!ar\x07', + b'\xc5!as\x07', + b'\xc5!dr\x07', + b'\xc5!ds\x07', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xe3\xd0\x081\x00', + b'\xe3\xd5\x161\x00', + b'\xe3\xe5F1\x00', + b'\xe3\xf5\x06\x00\x00', + b'\xe3\xf5\x07\x00\x00', + b'\xe3\xf5C\x00\x00', + b'\xe3\xf5F\x00\x00', + b'\xe3\xf5G\x00\x00', + b'\xe4\xe5\x021\x00', + b'\xe4\xe5\x061\x00', + b'\xe4\xf5\x02\x00\x00', + b'\xe4\xf5\x07\x00\x00', + b'\xe5\xf5\x04\x00\x00', + b'\xe5\xf5$\x00\x00', + b'\xe5\xf5B\x00\x00', + ], + }, + CAR.SUBARU_IMPREZA_2020: { + (Ecu.abs, 0x7b0, None): [ + b'\xa2 \x193\x00', + b'\xa2 \x194\x00', + b'\xa2 `\x00', + b'\xa2 !3\x00', + b'\xa2 !6\x00', + b'\xa2 !`\x00', + b'\xa2 !i\x00', + ], + (Ecu.eps, 0x746, None): [ + b'\n\xc0\x04\x00', + b'\n\xc0\x04\x01', + b'\x9a\xc0\x00\x00', + b'\x9a\xc0\x04\x00', + b'\x9a\xc0\n\x01', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\x00\x00eb\x1f@ "', + b'\x00\x00eq\x00\x00\x00\x00', + b'\x00\x00eq\x1f@ "', + b'\x00\x00e\x8f\x00\x00\x00\x00', + b'\x00\x00e\x8f\x1f@ )', + b'\x00\x00e\x92\x00\x00\x00\x00', + b'\x00\x00e\xa4\x00\x00\x00\x00', + b'\x00\x00e\xa4\x1f@ (', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xca!`0\x07', + b'\xca!`p\x07', + b'\xca!ap\x07', + b'\xca!f@\x07', + b'\xca!fp\x07', + b'\xcaacp\x07', + b'\xcc!`p\x07', + b'\xcc!fp\x07', + b'\xcc"f0\x07', + b'\xe6!`@\x07', + b'\xe6!fp\x07', + b'\xe6"f0\x07', + b'\xe6"fp\x07', + b'\xf3"f@\x07', + b'\xf3"fp\x07', + b'\xf3"fr\x07', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xe6\x15\x042\x00', + b'\xe6\xf5\x04\x00\x00', + b'\xe6\xf5$\x00\x00', + b'\xe6\xf5D0\x00', + b'\xe7\xf5\x04\x00\x00', + b'\xe7\xf5D0\x00', + b'\xe7\xf6B0\x00', + b'\xe9\xf5"\x00\x00', + b'\xe9\xf5B0\x00', + b'\xe9\xf6B0\x00', + b'\xe9\xf6F0\x00', + ], + }, + CAR.SUBARU_CROSSTREK_HYBRID: { + (Ecu.abs, 0x7b0, None): [ + b'\xa2 \x19e\x01', + b'\xa2 !e\x01', + ], + (Ecu.eps, 0x746, None): [ + b'\n\xc2\x01\x00', + b'\x9a\xc2\x01\x00', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\x00\x00el\x1f@ #', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xd7!`@\x07', + b'\xd7!`p\x07', + b'\xf4!`0\x07', + ], + }, + CAR.SUBARU_FORESTER: { + (Ecu.abs, 0x7b0, None): [ + b'\xa3 \x18\x14\x00', + b'\xa3 \x18&\x00', + b'\xa3 \x19\x14\x00', + b'\xa3 \x19&\x00', + b'\xa3 \x19h\x00', + b'\xa3 \x14\x00', + b'\xa3 \x14\x01', + ], + (Ecu.eps, 0x746, None): [ + b'\x8d\xc0\x00\x00', + b'\x8d\xc0\x04\x00', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\x00\x00e!\x00\x00\x00\x00', + b'\x00\x00e!\x1f@ \x11', + b'\x00\x00e^\x00\x00\x00\x00', + b'\x00\x00e^\x1f@ !', + b'\x00\x00e`\x00\x00\x00\x00', + b'\x00\x00e`\x1f@ ', + b'\x00\x00e\x97\x00\x00\x00\x00', + b'\x00\x00e\x97\x1f@ 0', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xb6"`A\x07', + b'\xb6\xa2`A\x07', + b'\xcb"`@\x07', + b'\xcb"`p\x07', + b'\xcf"`0\x07', + b'\xcf"`p\x07', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\x1a\xe6B1\x00', + b'\x1a\xe6F1\x00', + b'\x1a\xf6B0\x00', + b'\x1a\xf6B`\x00', + b'\x1a\xf6F`\x00', + b'\x1a\xf6b0\x00', + b'\x1a\xf6b`\x00', + b'\x1a\xf6f`\x00', + ], + }, + CAR.SUBARU_FORESTER_HYBRID: { + (Ecu.abs, 0x7b0, None): [ + b'\xa3 \x19T\x00', + ], + (Ecu.eps, 0x746, None): [ + b'\x8d\xc2\x00\x00', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\x00\x00eY\x1f@ !', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xd2\xa1`r\x07', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\x1b\xa7@a\x00', + ], + }, + CAR.SUBARU_FORESTER_PREGLOBAL: { + (Ecu.abs, 0x7b0, None): [ + b'm\x97\x14@', + b'}\x97\x14@', + ], + (Ecu.eps, 0x746, None): [ + b'm\xc0\x10\x00', + b'}\xc0\x10\x00', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\x00\x00c\xe9\x00\x00\x00\x00', + b'\x00\x00c\xe9\x1f@ \x03', + b'\x00\x00d5\x1f@ \t', + b'\x00\x00d\xd3\x1f@ \t', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xa7"@0\x07', + b'\xa7"@p\x07', + b'\xa7)\xa0q\x07', + b'\xba"@@\x07', + b'\xba"@p\x07', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\x1a\xf6F`\x00', + b'\xda\xf2`\x80\x00', + b'\xda\xf2`p\x00', + b'\xda\xfd\xe0\x80\x00', + b'\xdc\xf2@`\x00', + b'\xdc\xf2``\x00', + b'\xdc\xf2`\x80\x00', + b'\xdc\xf2`\x81\x00', + ], + }, + CAR.SUBARU_LEGACY_PREGLOBAL: { + (Ecu.abs, 0x7b0, None): [ + b'[\x97D\x00', + b'[\xba\xc4\x03', + b'k\x97D\x00', + b'k\x9aD\x00', + b'{\x97D\x00', + ], + (Ecu.eps, 0x746, None): [ + b'K\xb0\x00\x01', + b'[\xb0\x00\x01', + b'k\xb0\x00\x00', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\x00\x00c\x94\x1f@\x10\x08', + b'\x00\x00c\xb7\x1f@\x10\x16', + b'\x00\x00c\xec\x1f@ \x04', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xa0"@q\x07', + b'\xa0+@p\x07', + b'\xab*@r\x07', + b'\xab+@p\x07', + b'\xb4"@0\x07', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xbd\xf2\x00`\x00', + b'\xbe\xf2\x00p\x00', + b'\xbe\xfb\xc0p\x00', + b'\xbf\xf2\x00\x80\x00', + b'\xbf\xfb\xc0\x80\x00', + ], + }, + CAR.SUBARU_OUTBACK_PREGLOBAL: { + (Ecu.abs, 0x7b0, None): [ + b'[\xba\xac\x03', + b'[\xf7\xac\x00', + b'[\xf7\xac\x03', + b'[\xf7\xbc\x03', + b'k\x97\xac\x00', + b'k\x9a\xac\x00', + b'{\x97\xac\x00', + b'{\x9a\xac\x00', + ], + (Ecu.eps, 0x746, None): [ + b'K\xb0\x00\x00', + b'K\xb0\x00\x02', + b'[\xb0\x00\x00', + b'k\xb0\x00\x00', + b'{\xb0\x00\x01', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\x00\x00c\x90\x1f@\x10\x0e', + b'\x00\x00c\x94\x00\x00\x00\x00', + b'\x00\x00c\x94\x1f@\x10\x08', + b'\x00\x00c\xb7\x1f@\x10\x16', + b'\x00\x00c\xd1\x1f@\x10\x17', + b'\x00\x00c\xec\x1f@ \x04', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xa0"@\x80\x07', + b'\xa0*@q\x07', + b'\xa0*@u\x07', + b'\xa0+@@\x07', + b'\xa0bAq\x07', + b'\xab"@@\x07', + b'\xab"@s\x07', + b'\xab*@@\x07', + b'\xab+@@\x07', + b'\xb4"@0\x07', + b'\xb4"@p\x07', + b'\xb4"@r\x07', + b'\xb4+@p\x07', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xbd\xf2@`\x00', + b'\xbd\xf2@\x81\x00', + b'\xbd\xfb\xe0\x80\x00', + b'\xbe\xf2@p\x00', + b'\xbe\xf2@\x80\x00', + b'\xbe\xfb\xe0p\x00', + b'\xbf\xe2@\x80\x00', + b'\xbf\xf2@\x80\x00', + b'\xbf\xfb\xe0b\x00', + ], + }, + CAR.SUBARU_OUTBACK_PREGLOBAL_2018: { + (Ecu.abs, 0x7b0, None): [ + b'\x8b\x97\xac\x00', + b'\x8b\x97\xbc\x00', + b'\x8b\x99\xac\x00', + b'\x8b\x9a\xac\x00', + b'\x9b\x97\xac\x00', + b'\x9b\x97\xbe\x10', + b'\x9b\x9a\xac\x00', + ], + (Ecu.eps, 0x746, None): [ + b'{\xb0\x00\x00', + b'{\xb0\x00\x01', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\x00\x00df\x1f@ \n', + b'\x00\x00d\x95\x00\x00\x00\x00', + b'\x00\x00d\x95\x1f@ \x0f', + b'\x00\x00d\xfe\x00\x00\x00\x00', + b'\x00\x00d\xfe\x1f@ \x15', + b'\x00\x00e\x19\x1f@ \x15', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xb5"@P\x07', + b'\xb5"@p\x07', + b'\xb5+@@\x07', + b'\xb5b@1\x07', + b'\xb5q\xe0@\x07', + b'\xc4"@0\x07', + b'\xc4+@0\x07', + b'\xc4b@p\x07', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xbb\xf2@`\x00', + b'\xbb\xfb\xe0`\x00', + b'\xbc\xaf\xe0`\x00', + b'\xbc\xe2@\x80\x00', + b'\xbc\xf2@\x80\x00', + b'\xbc\xf2@\x81\x00', + b'\xbc\xfb\xe0`\x00', + b'\xbc\xfb\xe0\x80\x00', + ], + }, + CAR.SUBARU_OUTBACK: { + (Ecu.abs, 0x7b0, None): [ + b'\xa1 \x06\x00', + b'\xa1 \x06\x01', + b'\xa1 \x06\x02', + b'\xa1 \x07\x00', + b'\xa1 \x07\x02', + b'\xa1 \x07\x03', + b'\xa1 \x08\x00', + b'\xa1 \x08\x01', + b'\xa1 \x08\x02', + b'\xa1 "\t\x00', + b'\xa1 "\t\x01', + ], + (Ecu.eps, 0x746, None): [ + b'\x1b\xc0\x10\x00', + b'\x9b\xc0\x10\x00', + b'\x9b\xc0\x10\x02', + b'\x9b\xc0 \x00', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\x00\x00eJ\x00\x00\x00\x00\x00\x00', + b'\x00\x00eJ\x00\x1f@ \x19\x00', + b'\x00\x00e\x80\x00\x1f@ \x19\x00', + b'\x00\x00e\x9a\x00\x00\x00\x00\x00\x00', + b'\x00\x00e\x9a\x00\x1f@ 1\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xbc"`@\x07', + b'\xbc"`q\x07', + b'\xbc,\xa0q\x07', + b'\xbc,\xa0u\x07', + b'\xde"`0\x07', + b'\xde,\xa0@\x07', + b'\xe2"`0\x07', + b'\xe2"`p\x07', + b'\xe2"`q\x07', + b'\xe3,\xa0@\x07', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xa5\xf6D@\x00', + b'\xa5\xfe\xf6@\x00', + b'\xa5\xfe\xf7@\x00', + b'\xa5\xfe\xf8@\x00', + b'\xa7\x8e\xf40\x00', + b'\xa7\xf6D@\x00', + b'\xa7\xfe\xf4@\x00', + ], + }, + CAR.SUBARU_FORESTER_2022: { + (Ecu.abs, 0x7b0, None): [ + b'\xa3 !v\x00', + b'\xa3 !x\x00', + b'\xa3 "v\x00', + b'\xa3 "x\x00', + ], + (Ecu.eps, 0x746, None): [ + b'-\xc0\x040', + b'-\xc0%0', + b'=\xc0%\x02', + b'=\xc04\x02', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\x04!\x01\x1eD\x07!\x00\x04,', + b'\x04!\x08\x01.\x07!\x08\x022', + b'\r!\x08\x017\n!\x08\x003', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xd5"`0\x07', + b'\xd5"a0\x07', + b'\xf1"`q\x07', + b'\xf1"aq\x07', + b'\xfa"ap\x07', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\x1d\x86B0\x00', + b'\x1d\xf6B0\x00', + b'\x1e\x86B0\x00', + b'\x1e\x86F0\x00', + b'\x1e\xf6D0\x00', + ], + }, + CAR.SUBARU_OUTBACK_2023: { + (Ecu.abs, 0x7b0, None): [ + b'\xa1 #\x14\x00', + b'\xa1 #\x17\x00', + ], + (Ecu.eps, 0x746, None): [ + b'+\xc0\x10\x11\x00', + b'+\xc0\x12\x11\x00', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\t!\x08\x046\x05!\x08\x01/', + ], + (Ecu.engine, 0x7a2, None): [ + b'\xed,\xa0q\x07', + b'\xed,\xa2q\x07', + ], + (Ecu.transmission, 0x7a3, None): [ + b'\xa8\x8e\xf41\x00', + b'\xa8\xfe\xf41\x00', + ], + }, +} diff --git a/car/subaru/interface.py b/car/subaru/interface.py new file mode 100644 index 0000000000..1aa4bd95ea --- /dev/null +++ b/car/subaru/interface.py @@ -0,0 +1,116 @@ +from cereal import car +from panda import Panda +from openpilot.selfdrive.car import get_safety_config +from openpilot.selfdrive.car.disable_ecu import disable_ecu +from openpilot.selfdrive.car.interfaces import CarInterfaceBase +from openpilot.selfdrive.car.subaru.values import CAR, GLOBAL_ES_ADDR, SubaruFlags + + +class CarInterface(CarInterfaceBase): + + @staticmethod + def _get_params(ret, candidate: CAR, fingerprint, car_fw, experimental_long, docs): + ret.carName = "subaru" + ret.radarUnavailable = True + # for HYBRID CARS to be upstreamed, we need: + # - replacement for ES_Distance so we can cancel the cruise control + # - to find the Cruise_Activated bit from the car + # - proper panda safety setup (use the correct cruise_activated bit, throttle from Throttle_Hybrid, etc) + ret.dashcamOnly = bool(ret.flags & (SubaruFlags.PREGLOBAL | SubaruFlags.LKAS_ANGLE | SubaruFlags.HYBRID)) + ret.autoResumeSng = False + + # Detect infotainment message sent from the camera + if not (ret.flags & SubaruFlags.PREGLOBAL) and 0x323 in fingerprint[2]: + ret.flags |= SubaruFlags.SEND_INFOTAINMENT.value + + if ret.flags & SubaruFlags.PREGLOBAL: + ret.enableBsm = 0x25c in fingerprint[0] + ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.subaruPreglobal)] + else: + ret.enableBsm = 0x228 in fingerprint[0] + ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.subaru)] + if ret.flags & SubaruFlags.GLOBAL_GEN2: + ret.safetyConfigs[0].safetyParam |= Panda.FLAG_SUBARU_GEN2 + + ret.steerLimitTimer = 0.4 + ret.steerActuatorDelay = 0.1 + + if ret.flags & SubaruFlags.LKAS_ANGLE: + ret.steerControlType = car.CarParams.SteerControlType.angle + else: + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) + + if candidate in (CAR.SUBARU_ASCENT, CAR.SUBARU_ASCENT_2023): + ret.steerActuatorDelay = 0.3 # end-to-end angle controller + ret.lateralTuning.init('pid') + ret.lateralTuning.pid.kf = 0.00003 + ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0., 20.], [0., 20.]] + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.0025, 0.1], [0.00025, 0.01]] + + elif candidate == CAR.SUBARU_IMPREZA: + ret.steerActuatorDelay = 0.4 # end-to-end angle controller + ret.lateralTuning.init('pid') + ret.lateralTuning.pid.kf = 0.00005 + ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0., 20.], [0., 20.]] + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2, 0.3], [0.02, 0.03]] + + elif candidate == CAR.SUBARU_IMPREZA_2020: + ret.lateralTuning.init('pid') + ret.lateralTuning.pid.kf = 0.00005 + ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0., 14., 23.], [0., 14., 23.]] + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.045, 0.042, 0.20], [0.04, 0.035, 0.045]] + + elif candidate == CAR.SUBARU_CROSSTREK_HYBRID: + ret.steerActuatorDelay = 0.1 + + elif candidate in (CAR.SUBARU_FORESTER, CAR.SUBARU_FORESTER_2022, CAR.SUBARU_FORESTER_HYBRID): + ret.lateralTuning.init('pid') + ret.lateralTuning.pid.kf = 0.000038 + ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0., 14., 23.], [0., 14., 23.]] + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.01, 0.065, 0.2], [0.001, 0.015, 0.025]] + + elif candidate in (CAR.SUBARU_OUTBACK, CAR.SUBARU_LEGACY, CAR.SUBARU_OUTBACK_2023): + ret.steerActuatorDelay = 0.1 + + elif candidate in (CAR.SUBARU_FORESTER_PREGLOBAL, CAR.SUBARU_OUTBACK_PREGLOBAL_2018): + ret.safetyConfigs[0].safetyParam = Panda.FLAG_SUBARU_PREGLOBAL_REVERSED_DRIVER_TORQUE # Outback 2018-2019 and Forester have reversed driver torque signal + + elif candidate == CAR.SUBARU_LEGACY_PREGLOBAL: + ret.steerActuatorDelay = 0.15 + + elif candidate == CAR.SUBARU_OUTBACK_PREGLOBAL: + pass + else: + raise ValueError(f"unknown car: {candidate}") + + ret.experimentalLongitudinalAvailable = not (ret.flags & (SubaruFlags.GLOBAL_GEN2 | SubaruFlags.PREGLOBAL | + SubaruFlags.LKAS_ANGLE | SubaruFlags.HYBRID)) + ret.openpilotLongitudinalControl = experimental_long and ret.experimentalLongitudinalAvailable + + if ret.flags & SubaruFlags.GLOBAL_GEN2 and ret.openpilotLongitudinalControl: + ret.flags |= SubaruFlags.DISABLE_EYESIGHT.value + + if ret.openpilotLongitudinalControl: + ret.longitudinalTuning.kpBP = [0., 5., 35.] + ret.longitudinalTuning.kpV = [0.8, 1.0, 1.5] + ret.longitudinalTuning.kiBP = [0., 35.] + ret.longitudinalTuning.kiV = [0.54, 0.36] + + ret.stoppingControl = True + ret.safetyConfigs[0].safetyParam |= Panda.FLAG_SUBARU_LONG + + return ret + + # returns a car.CarState + def _update(self, c): + + ret = self.CS.update(self.cp, self.cp_cam, self.cp_body) + + ret.events = self.create_common_events(ret).to_msg() + + return ret + + @staticmethod + def init(CP, logcan, sendcan): + if CP.flags & SubaruFlags.DISABLE_EYESIGHT: + disable_ecu(logcan, sendcan, bus=2, addr=GLOBAL_ES_ADDR, com_cont_req=b'\x28\x03\x01') diff --git a/car/subaru/radar_interface.py b/car/subaru/radar_interface.py new file mode 100644 index 0000000000..e654bd61fd --- /dev/null +++ b/car/subaru/radar_interface.py @@ -0,0 +1,4 @@ +from openpilot.selfdrive.car.interfaces import RadarInterfaceBase + +class RadarInterface(RadarInterfaceBase): + pass diff --git a/car/subaru/subarucan.py b/car/subaru/subarucan.py new file mode 100644 index 0000000000..86d39ff885 --- /dev/null +++ b/car/subaru/subarucan.py @@ -0,0 +1,321 @@ +from cereal import car +from openpilot.selfdrive.car.subaru.values import CanBus + +VisualAlert = car.CarControl.HUDControl.VisualAlert + + +def create_steering_control(packer, apply_steer, steer_req): + values = { + "LKAS_Output": apply_steer, + "LKAS_Request": steer_req, + "SET_1": 1 + } + return packer.make_can_msg("ES_LKAS", 0, values) + + +def create_steering_control_angle(packer, apply_steer, steer_req): + values = { + "LKAS_Output": apply_steer, + "LKAS_Request": steer_req, + "SET_3": 3 + } + return packer.make_can_msg("ES_LKAS_ANGLE", 0, values) + + +def create_steering_status(packer): + return packer.make_can_msg("ES_LKAS_State", 0, {}) + +def create_es_distance(packer, frame, es_distance_msg, bus, pcm_cancel_cmd, long_enabled = False, brake_cmd = False, cruise_throttle = 0): + values = {s: es_distance_msg[s] for s in [ + "CHECKSUM", + "Signal1", + "Cruise_Fault", + "Cruise_Throttle", + "Signal2", + "Car_Follow", + "Low_Speed_Follow", + "Cruise_Soft_Disable", + "Signal7", + "Cruise_Brake_Active", + "Distance_Swap", + "Cruise_EPB", + "Signal4", + "Close_Distance", + "Signal5", + "Cruise_Cancel", + "Cruise_Set", + "Cruise_Resume", + "Signal6", + ]} + + values["COUNTER"] = frame % 0x10 + + if long_enabled: + values["Cruise_Throttle"] = cruise_throttle + + # Do not disable openpilot on Eyesight Soft Disable, if openpilot is controlling long + values["Cruise_Soft_Disable"] = 0 + values["Cruise_Fault"] = 0 + + values["Cruise_Brake_Active"] = brake_cmd + + if pcm_cancel_cmd: + values["Cruise_Cancel"] = 1 + values["Cruise_Throttle"] = 1818 # inactive throttle + + return packer.make_can_msg("ES_Distance", bus, values) + + +def create_es_lkas_state(packer, frame, es_lkas_state_msg, enabled, visual_alert, left_line, right_line, left_lane_depart, right_lane_depart): + values = {s: es_lkas_state_msg[s] for s in [ + "CHECKSUM", + "LKAS_Alert_Msg", + "Signal1", + "LKAS_ACTIVE", + "LKAS_Dash_State", + "Signal2", + "Backward_Speed_Limit_Menu", + "LKAS_Left_Line_Enable", + "LKAS_Left_Line_Light_Blink", + "LKAS_Right_Line_Enable", + "LKAS_Right_Line_Light_Blink", + "LKAS_Left_Line_Visible", + "LKAS_Right_Line_Visible", + "LKAS_Alert", + "Signal3", + ]} + + values["COUNTER"] = frame % 0x10 + + # Filter the stock LKAS "Keep hands on wheel" alert + if values["LKAS_Alert_Msg"] == 1: + values["LKAS_Alert_Msg"] = 0 + + # Filter the stock LKAS sending an audible alert when it turns off LKAS + if values["LKAS_Alert"] == 27: + values["LKAS_Alert"] = 0 + + # Filter the stock LKAS sending an audible alert when "Keep hands on wheel" alert is active (2020+ models) + if values["LKAS_Alert"] == 28 and values["LKAS_Alert_Msg"] == 7: + values["LKAS_Alert"] = 0 + + # Filter the stock LKAS sending an audible alert when "Keep hands on wheel OFF" alert is active (2020+ models) + if values["LKAS_Alert"] == 30: + values["LKAS_Alert"] = 0 + + # Filter the stock LKAS sending "Keep hands on wheel OFF" alert (2020+ models) + if values["LKAS_Alert_Msg"] == 7: + values["LKAS_Alert_Msg"] = 0 + + # Show Keep hands on wheel alert for openpilot steerRequired alert + if visual_alert == VisualAlert.steerRequired: + values["LKAS_Alert_Msg"] = 1 + + # Ensure we don't overwrite potentially more important alerts from stock (e.g. FCW) + if visual_alert == VisualAlert.ldw and values["LKAS_Alert"] == 0: + if left_lane_depart: + values["LKAS_Alert"] = 12 # Left lane departure dash alert + elif right_lane_depart: + values["LKAS_Alert"] = 11 # Right lane departure dash alert + + if enabled: + values["LKAS_ACTIVE"] = 1 # Show LKAS lane lines + values["LKAS_Dash_State"] = 2 # Green enabled indicator + else: + values["LKAS_Dash_State"] = 0 # LKAS Not enabled + + values["LKAS_Left_Line_Visible"] = int(left_line) + values["LKAS_Right_Line_Visible"] = int(right_line) + + return packer.make_can_msg("ES_LKAS_State", CanBus.main, values) + +def create_es_dashstatus(packer, frame, dashstatus_msg, enabled, long_enabled, long_active, lead_visible): + values = {s: dashstatus_msg[s] for s in [ + "CHECKSUM", + "PCB_Off", + "LDW_Off", + "Signal1", + "Cruise_State_Msg", + "LKAS_State_Msg", + "Signal2", + "Cruise_Soft_Disable", + "Cruise_Status_Msg", + "Signal3", + "Cruise_Distance", + "Signal4", + "Conventional_Cruise", + "Signal5", + "Cruise_Disengaged", + "Cruise_Activated", + "Signal6", + "Cruise_Set_Speed", + "Cruise_Fault", + "Cruise_On", + "Display_Own_Car", + "Brake_Lights", + "Car_Follow", + "Signal7", + "Far_Distance", + "Cruise_State", + ]} + + values["COUNTER"] = frame % 0x10 + + if long_enabled: + values["Cruise_State"] = 0 + values["Cruise_Activated"] = enabled + values["Cruise_Disengaged"] = 0 + values["Car_Follow"] = int(lead_visible) + + values["PCB_Off"] = 1 # AEB is not presevered, so show the PCB_Off on dash + values["LDW_Off"] = 0 + values["Cruise_Fault"] = 0 + + # Filter stock LKAS disabled and Keep hands on steering wheel OFF alerts + if values["LKAS_State_Msg"] in (2, 3): + values["LKAS_State_Msg"] = 0 + + return packer.make_can_msg("ES_DashStatus", CanBus.main, values) + +def create_es_brake(packer, frame, es_brake_msg, long_enabled, long_active, brake_value): + values = {s: es_brake_msg[s] for s in [ + "CHECKSUM", + "Signal1", + "Brake_Pressure", + "AEB_Status", + "Cruise_Brake_Lights", + "Cruise_Brake_Fault", + "Cruise_Brake_Active", + "Cruise_Activated", + "Signal3", + ]} + + values["COUNTER"] = frame % 0x10 + + if long_enabled: + values["Cruise_Brake_Fault"] = 0 + values["Cruise_Activated"] = long_active + + values["Brake_Pressure"] = brake_value + + values["Cruise_Brake_Active"] = brake_value > 0 + values["Cruise_Brake_Lights"] = brake_value >= 70 + + return packer.make_can_msg("ES_Brake", CanBus.main, values) + +def create_es_status(packer, frame, es_status_msg, long_enabled, long_active, cruise_rpm): + values = {s: es_status_msg[s] for s in [ + "CHECKSUM", + "Signal1", + "Cruise_Fault", + "Cruise_RPM", + "Cruise_Activated", + "Brake_Lights", + "Cruise_Hold", + "Signal3", + ]} + + values["COUNTER"] = frame % 0x10 + + if long_enabled: + values["Cruise_RPM"] = cruise_rpm + values["Cruise_Fault"] = 0 + + values["Cruise_Activated"] = long_active + + return packer.make_can_msg("ES_Status", CanBus.main, values) + + +def create_es_infotainment(packer, frame, es_infotainment_msg, visual_alert): + # Filter stock LKAS disabled and Keep hands on steering wheel OFF alerts + values = {s: es_infotainment_msg[s] for s in [ + "CHECKSUM", + "LKAS_State_Infotainment", + "LKAS_Blue_Lines", + "Signal1", + "Signal2", + ]} + + values["COUNTER"] = frame % 0x10 + + if values["LKAS_State_Infotainment"] in (3, 4): + values["LKAS_State_Infotainment"] = 0 + + # Show Keep hands on wheel alert for openpilot steerRequired alert + if visual_alert == VisualAlert.steerRequired: + values["LKAS_State_Infotainment"] = 3 + + # Show Obstacle Detected for fcw + if visual_alert == VisualAlert.fcw: + values["LKAS_State_Infotainment"] = 2 + + return packer.make_can_msg("ES_Infotainment", CanBus.main, values) + + +def create_es_highbeamassist(packer): + values = { + "HBA_Available": False, + } + + return packer.make_can_msg("ES_HighBeamAssist", CanBus.main, values) + + +def create_es_static_1(packer): + values = { + "SET_3": 3, + } + + return packer.make_can_msg("ES_STATIC_1", CanBus.main, values) + + +def create_es_static_2(packer): + values = { + "SET_3": 3, + } + + return packer.make_can_msg("ES_STATIC_2", CanBus.main, values) + + +# *** Subaru Pre-global *** + +def subaru_preglobal_checksum(packer, values, addr, checksum_byte=7): + dat = packer.make_can_msg(addr, 0, values)[2] + return (sum(dat[:checksum_byte]) + sum(dat[checksum_byte+1:])) % 256 + + +def create_preglobal_steering_control(packer, frame, apply_steer, steer_req): + values = { + "COUNTER": frame % 0x08, + "LKAS_Command": apply_steer, + "LKAS_Active": steer_req, + } + values["Checksum"] = subaru_preglobal_checksum(packer, values, "ES_LKAS") + + return packer.make_can_msg("ES_LKAS", CanBus.main, values) + + +def create_preglobal_es_distance(packer, cruise_button, es_distance_msg): + values = {s: es_distance_msg[s] for s in [ + "Cruise_Throttle", + "Signal1", + "Car_Follow", + "Signal2", + "Cruise_Brake_Active", + "Distance_Swap", + "Standstill", + "Signal3", + "Close_Distance", + "Signal4", + "Standstill_2", + "Cruise_Fault", + "Signal5", + "COUNTER", + "Signal6", + "Cruise_Button", + "Signal7", + ]} + + values["Cruise_Button"] = cruise_button + values["Checksum"] = subaru_preglobal_checksum(packer, values, "ES_Distance") + + return packer.make_can_msg("ES_Distance", CanBus.main, values) diff --git a/car/subaru/tests/test_subaru.py b/car/subaru/tests/test_subaru.py new file mode 100644 index 0000000000..33040442b6 --- /dev/null +++ b/car/subaru/tests/test_subaru.py @@ -0,0 +1,16 @@ +from cereal import car +from openpilot.selfdrive.car.subaru.fingerprints import FW_VERSIONS + +Ecu = car.CarParams.Ecu + +ECU_NAME = {v: k for k, v in Ecu.schema.enumerants.items()} + + +class TestSubaruFingerprint: + def test_fw_version_format(self): + for platform, fws_per_ecu in FW_VERSIONS.items(): + for (ecu, _, _), fws in fws_per_ecu.items(): + fw_size = len(fws[0]) + for fw in fws: + assert len(fw) == fw_size, f"{platform} {ecu}: {len(fw)} {fw_size}" + diff --git a/car/subaru/values.py b/car/subaru/values.py new file mode 100644 index 0000000000..dcbea1979f --- /dev/null +++ b/car/subaru/values.py @@ -0,0 +1,275 @@ +from dataclasses import dataclass, field +from enum import Enum, IntFlag + +from cereal import car +from panda.python import uds +from openpilot.selfdrive.car import CarSpecs, DbcDict, PlatformConfig, Platforms, dbc_dict +from openpilot.selfdrive.car.docs_definitions import CarFootnote, CarHarness, CarDocs, CarParts, Tool, Column +from openpilot.selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries, p16 + +Ecu = car.CarParams.Ecu + + +class CarControllerParams: + def __init__(self, CP): + self.STEER_STEP = 2 # how often we update the steer cmd + self.STEER_DELTA_UP = 50 # torque increase per refresh, 0.8s to max + self.STEER_DELTA_DOWN = 70 # torque decrease per refresh + self.STEER_DRIVER_ALLOWANCE = 60 # allowed driver torque before start limiting + self.STEER_DRIVER_MULTIPLIER = 50 # weight driver torque heavily + self.STEER_DRIVER_FACTOR = 1 # from dbc + + if CP.flags & SubaruFlags.GLOBAL_GEN2: + self.STEER_MAX = 1000 + self.STEER_DELTA_UP = 40 + self.STEER_DELTA_DOWN = 40 + elif CP.carFingerprint == CAR.SUBARU_IMPREZA_2020: + self.STEER_MAX = 1439 + else: + self.STEER_MAX = 2047 + + THROTTLE_MIN = 808 + THROTTLE_MAX = 3400 + + THROTTLE_INACTIVE = 1818 # corresponds to zero acceleration + THROTTLE_ENGINE_BRAKE = 808 # while braking, eyesight sets throttle to this, probably for engine braking + + BRAKE_MIN = 0 + BRAKE_MAX = 600 # about -3.5m/s2 from testing + + RPM_MIN = 0 + RPM_MAX = 3600 + + RPM_INACTIVE = 600 # a good base rpm for zero acceleration + + THROTTLE_LOOKUP_BP = [0, 2] + THROTTLE_LOOKUP_V = [THROTTLE_INACTIVE, THROTTLE_MAX] + + RPM_LOOKUP_BP = [0, 2] + RPM_LOOKUP_V = [RPM_INACTIVE, RPM_MAX] + + BRAKE_LOOKUP_BP = [-3.5, 0] + BRAKE_LOOKUP_V = [BRAKE_MAX, BRAKE_MIN] + + +class SubaruFlags(IntFlag): + # Detected flags + SEND_INFOTAINMENT = 1 + DISABLE_EYESIGHT = 2 + + # Static flags + GLOBAL_GEN2 = 4 + + # Cars that temporarily fault when steering angle rate is greater than some threshold. + # Appears to be all torque-based cars produced around 2019 - present + STEER_RATE_LIMITED = 8 + PREGLOBAL = 16 + HYBRID = 32 + LKAS_ANGLE = 64 + + +GLOBAL_ES_ADDR = 0x787 +GEN2_ES_BUTTONS_DID = b'\x11\x30' + + +class CanBus: + main = 0 + alt = 1 + camera = 2 + + +class Footnote(Enum): + GLOBAL = CarFootnote( + "In the non-US market, openpilot requires the car to come equipped with EyeSight with Lane Keep Assistance.", + Column.PACKAGE) + EXP_LONG = CarFootnote( + "Enabling longitudinal control (alpha) will disable all EyeSight functionality, including AEB, LDW, and RAB.", + Column.LONGITUDINAL) + + +@dataclass +class SubaruCarDocs(CarDocs): + package: str = "EyeSight Driver Assistance" + car_parts: CarParts = field(default_factory=CarParts.common([CarHarness.subaru_a])) + footnotes: list[Enum] = field(default_factory=lambda: [Footnote.GLOBAL]) + + def init_make(self, CP: car.CarParams): + self.car_parts.parts.extend([Tool.socket_8mm_deep, Tool.pry_tool]) + + if CP.experimentalLongitudinalAvailable: + self.footnotes.append(Footnote.EXP_LONG) + + +@dataclass +class SubaruPlatformConfig(PlatformConfig): + dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict('subaru_global_2017_generated', None)) + + def init(self): + if self.flags & SubaruFlags.HYBRID: + self.dbc_dict = dbc_dict('subaru_global_2020_hybrid_generated', None) + + +@dataclass +class SubaruGen2PlatformConfig(SubaruPlatformConfig): + def init(self): + super().init() + self.flags |= SubaruFlags.GLOBAL_GEN2 + if not (self.flags & SubaruFlags.LKAS_ANGLE): + self.flags |= SubaruFlags.STEER_RATE_LIMITED + + +class CAR(Platforms): + # Global platform + SUBARU_ASCENT = SubaruPlatformConfig( + [SubaruCarDocs("Subaru Ascent 2019-21", "All")], + CarSpecs(mass=2031, wheelbase=2.89, steerRatio=13.5), + ) + SUBARU_OUTBACK = SubaruGen2PlatformConfig( + [SubaruCarDocs("Subaru Outback 2020-22", "All", car_parts=CarParts.common([CarHarness.subaru_b]))], + CarSpecs(mass=1568, wheelbase=2.67, steerRatio=17), + ) + SUBARU_LEGACY = SubaruGen2PlatformConfig( + [SubaruCarDocs("Subaru Legacy 2020-22", "All", car_parts=CarParts.common([CarHarness.subaru_b]))], + SUBARU_OUTBACK.specs, + ) + SUBARU_IMPREZA = SubaruPlatformConfig( + [ + SubaruCarDocs("Subaru Impreza 2017-19"), + SubaruCarDocs("Subaru Crosstrek 2018-19", video_link="https://youtu.be/Agww7oE1k-s?t=26"), + SubaruCarDocs("Subaru XV 2018-19", video_link="https://youtu.be/Agww7oE1k-s?t=26"), + ], + CarSpecs(mass=1568, wheelbase=2.67, steerRatio=15), + ) + SUBARU_IMPREZA_2020 = SubaruPlatformConfig( + [ + SubaruCarDocs("Subaru Impreza 2020-22"), + SubaruCarDocs("Subaru Crosstrek 2020-23"), + SubaruCarDocs("Subaru XV 2020-21"), + ], + CarSpecs(mass=1480, wheelbase=2.67, steerRatio=17), + flags=SubaruFlags.STEER_RATE_LIMITED, + ) + # TODO: is there an XV and Impreza too? + SUBARU_CROSSTREK_HYBRID = SubaruPlatformConfig( + [SubaruCarDocs("Subaru Crosstrek Hybrid 2020", car_parts=CarParts.common([CarHarness.subaru_b]))], + CarSpecs(mass=1668, wheelbase=2.67, steerRatio=17), + flags=SubaruFlags.HYBRID, + ) + SUBARU_FORESTER = SubaruPlatformConfig( + [SubaruCarDocs("Subaru Forester 2019-21", "All")], + CarSpecs(mass=1568, wheelbase=2.67, steerRatio=17), + flags=SubaruFlags.STEER_RATE_LIMITED, + ) + SUBARU_FORESTER_HYBRID = SubaruPlatformConfig( + [SubaruCarDocs("Subaru Forester Hybrid 2020")], + SUBARU_FORESTER.specs, + flags=SubaruFlags.HYBRID, + ) + # Pre-global + SUBARU_FORESTER_PREGLOBAL = SubaruPlatformConfig( + [SubaruCarDocs("Subaru Forester 2017-18")], + CarSpecs(mass=1568, wheelbase=2.67, steerRatio=20), + dbc_dict('subaru_forester_2017_generated', None), + flags=SubaruFlags.PREGLOBAL, + ) + SUBARU_LEGACY_PREGLOBAL = SubaruPlatformConfig( + [SubaruCarDocs("Subaru Legacy 2015-18")], + CarSpecs(mass=1568, wheelbase=2.67, steerRatio=12.5), + dbc_dict('subaru_outback_2015_generated', None), + flags=SubaruFlags.PREGLOBAL, + ) + SUBARU_OUTBACK_PREGLOBAL = SubaruPlatformConfig( + [SubaruCarDocs("Subaru Outback 2015-17")], + SUBARU_FORESTER_PREGLOBAL.specs, + dbc_dict('subaru_outback_2015_generated', None), + flags=SubaruFlags.PREGLOBAL, + ) + SUBARU_OUTBACK_PREGLOBAL_2018 = SubaruPlatformConfig( + [SubaruCarDocs("Subaru Outback 2018-19")], + SUBARU_FORESTER_PREGLOBAL.specs, + dbc_dict('subaru_outback_2019_generated', None), + flags=SubaruFlags.PREGLOBAL, + ) + # Angle LKAS + SUBARU_FORESTER_2022 = SubaruPlatformConfig( + [SubaruCarDocs("Subaru Forester 2022-24", "All", car_parts=CarParts.common([CarHarness.subaru_c]))], + SUBARU_FORESTER.specs, + flags=SubaruFlags.LKAS_ANGLE, + ) + SUBARU_OUTBACK_2023 = SubaruGen2PlatformConfig( + [SubaruCarDocs("Subaru Outback 2023", "All", car_parts=CarParts.common([CarHarness.subaru_d]))], + SUBARU_OUTBACK.specs, + flags=SubaruFlags.LKAS_ANGLE, + ) + SUBARU_ASCENT_2023 = SubaruGen2PlatformConfig( + [SubaruCarDocs("Subaru Ascent 2023", "All", car_parts=CarParts.common([CarHarness.subaru_d]))], + SUBARU_ASCENT.specs, + flags=SubaruFlags.LKAS_ANGLE, + ) + + +SUBARU_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ + p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_DATA_IDENTIFICATION) +SUBARU_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ + p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_DATA_IDENTIFICATION) + +# The EyeSight ECU takes 10s to respond to SUBARU_VERSION_REQUEST properly, +# log this alternate manufacturer-specific query +SUBARU_ALT_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ + p16(0xf100) +SUBARU_ALT_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ + p16(0xf100) + +FW_QUERY_CONFIG = FwQueryConfig( + requests=[ + Request( + [StdQueries.TESTER_PRESENT_REQUEST, SUBARU_VERSION_REQUEST], + [StdQueries.TESTER_PRESENT_RESPONSE, SUBARU_VERSION_RESPONSE], + whitelist_ecus=[Ecu.abs, Ecu.eps, Ecu.fwdCamera, Ecu.engine, Ecu.transmission], + logging=True, + ), + # Non-OBD requests + # Some Eyesight modules fail on TESTER_PRESENT_REQUEST + # TODO: check if this resolves the fingerprinting issue for the 2023 Ascent and other new Subaru cars + Request( + [SUBARU_VERSION_REQUEST], + [SUBARU_VERSION_RESPONSE], + whitelist_ecus=[Ecu.fwdCamera], + bus=0, + ), + Request( + [SUBARU_ALT_VERSION_REQUEST], + [SUBARU_ALT_VERSION_RESPONSE], + whitelist_ecus=[Ecu.fwdCamera], + bus=0, + logging=True, + ), + Request( + [StdQueries.DEFAULT_DIAGNOSTIC_REQUEST, StdQueries.TESTER_PRESENT_REQUEST, SUBARU_VERSION_REQUEST], + [StdQueries.DEFAULT_DIAGNOSTIC_RESPONSE, StdQueries.TESTER_PRESENT_RESPONSE, SUBARU_VERSION_RESPONSE], + whitelist_ecus=[Ecu.fwdCamera], + bus=0, + logging=True, + ), + Request( + [StdQueries.TESTER_PRESENT_REQUEST, SUBARU_VERSION_REQUEST], + [StdQueries.TESTER_PRESENT_RESPONSE, SUBARU_VERSION_RESPONSE], + whitelist_ecus=[Ecu.abs, Ecu.eps, Ecu.fwdCamera, Ecu.engine, Ecu.transmission], + bus=0, + ), + # GEN2 powertrain bus query + Request( + [StdQueries.TESTER_PRESENT_REQUEST, SUBARU_VERSION_REQUEST], + [StdQueries.TESTER_PRESENT_RESPONSE, SUBARU_VERSION_RESPONSE], + whitelist_ecus=[Ecu.abs, Ecu.eps, Ecu.fwdCamera, Ecu.engine, Ecu.transmission], + bus=1, + obd_multiplexing=False, + ), + ], + # We don't get the EPS from non-OBD queries on GEN2 cars. Note that we still attempt to match when it exists + non_essential_ecus={ + Ecu.eps: list(CAR.with_flags(SubaruFlags.GLOBAL_GEN2)), + } +) + +DBC = CAR.create_dbc_map() diff --git a/car/tesla/__init__.py b/car/tesla/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/car/tesla/carcontroller.py b/car/tesla/carcontroller.py new file mode 100644 index 0000000000..e460111e32 --- /dev/null +++ b/car/tesla/carcontroller.py @@ -0,0 +1,67 @@ +from openpilot.common.numpy_fast import clip +from opendbc.can.packer import CANPacker +from openpilot.selfdrive.car import apply_std_steer_angle_limits +from openpilot.selfdrive.car.interfaces import CarControllerBase +from openpilot.selfdrive.car.tesla.teslacan import TeslaCAN +from openpilot.selfdrive.car.tesla.values import DBC, CANBUS, CarControllerParams + + +class CarController(CarControllerBase): + def __init__(self, dbc_name, CP, VM): + self.CP = CP + self.frame = 0 + self.apply_angle_last = 0 + self.packer = CANPacker(dbc_name) + self.pt_packer = CANPacker(DBC[CP.carFingerprint]['pt']) + self.tesla_can = TeslaCAN(self.packer, self.pt_packer) + + def update(self, CC, CS, now_nanos): + actuators = CC.actuators + pcm_cancel_cmd = CC.cruiseControl.cancel + + can_sends = [] + + # Temp disable steering on a hands_on_fault, and allow for user override + hands_on_fault = CS.steer_warning == "EAC_ERROR_HANDS_ON" and CS.hands_on_level >= 3 + lkas_enabled = CC.latActive and not hands_on_fault + + if self.frame % 2 == 0: + if lkas_enabled: + # Angular rate limit based on speed + apply_angle = apply_std_steer_angle_limits(actuators.steeringAngleDeg, self.apply_angle_last, CS.out.vEgo, CarControllerParams) + + # To not fault the EPS + apply_angle = clip(apply_angle, CS.out.steeringAngleDeg - 20, CS.out.steeringAngleDeg + 20) + else: + apply_angle = CS.out.steeringAngleDeg + + self.apply_angle_last = apply_angle + can_sends.append(self.tesla_can.create_steering_control(apply_angle, lkas_enabled, (self.frame // 2) % 16)) + + # Longitudinal control (in sync with stock message, about 40Hz) + if self.CP.openpilotLongitudinalControl: + target_accel = actuators.accel + target_speed = max(CS.out.vEgo + (target_accel * CarControllerParams.ACCEL_TO_SPEED_MULTIPLIER), 0) + max_accel = 0 if target_accel < 0 else target_accel + min_accel = 0 if target_accel > 0 else target_accel + + while len(CS.das_control_counters) > 0: + can_sends.extend(self.tesla_can.create_longitudinal_commands(CS.acc_state, target_speed, min_accel, max_accel, CS.das_control_counters.popleft())) + + # Cancel on user steering override, since there is no steering torque blending + if hands_on_fault: + pcm_cancel_cmd = True + + if self.frame % 10 == 0 and pcm_cancel_cmd: + # Spam every possible counter value, otherwise it might not be accepted + for counter in range(16): + can_sends.append(self.tesla_can.create_action_request(CS.msg_stw_actn_req, pcm_cancel_cmd, CANBUS.chassis, counter)) + can_sends.append(self.tesla_can.create_action_request(CS.msg_stw_actn_req, pcm_cancel_cmd, CANBUS.autopilot_chassis, counter)) + + # TODO: HUD control + + new_actuators = actuators.as_builder() + new_actuators.steeringAngleDeg = self.apply_angle_last + + self.frame += 1 + return new_actuators, can_sends diff --git a/car/tesla/carstate.py b/car/tesla/carstate.py new file mode 100644 index 0000000000..645ea46014 --- /dev/null +++ b/car/tesla/carstate.py @@ -0,0 +1,139 @@ +import copy +from collections import deque +from cereal import car +from openpilot.common.conversions import Conversions as CV +from openpilot.selfdrive.car.tesla.values import CAR, DBC, CANBUS, GEAR_MAP, DOORS, BUTTONS +from openpilot.selfdrive.car.interfaces import CarStateBase +from opendbc.can.parser import CANParser +from opendbc.can.can_define import CANDefine + +class CarState(CarStateBase): + def __init__(self, CP): + super().__init__(CP) + self.button_states = {button.event_type: False for button in BUTTONS} + self.can_define = CANDefine(DBC[CP.carFingerprint]['chassis']) + + # Needed by carcontroller + self.msg_stw_actn_req = None + self.hands_on_level = 0 + self.steer_warning = None + self.acc_state = 0 + self.das_control_counters = deque(maxlen=32) + + def update(self, cp, cp_cam): + ret = car.CarState.new_message() + + # Vehicle speed + ret.vEgoRaw = cp.vl["ESP_B"]["ESP_vehicleSpeed"] * CV.KPH_TO_MS + ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) + ret.standstill = (ret.vEgo < 0.1) + + # Gas pedal + ret.gas = cp.vl["DI_torque1"]["DI_pedalPos"] / 100.0 + ret.gasPressed = (ret.gas > 0) + + # Brake pedal + ret.brake = 0 + ret.brakePressed = bool(cp.vl["BrakeMessage"]["driverBrakeStatus"] != 1) + + # Steering wheel + epas_status = cp_cam.vl["EPAS3P_sysStatus"] if self.CP.carFingerprint == CAR.TESLA_MODELS_RAVEN else cp.vl["EPAS_sysStatus"] + + self.hands_on_level = epas_status["EPAS_handsOnLevel"] + self.steer_warning = self.can_define.dv["EPAS_sysStatus"]["EPAS_eacErrorCode"].get(int(epas_status["EPAS_eacErrorCode"]), None) + steer_status = self.can_define.dv["EPAS_sysStatus"]["EPAS_eacStatus"].get(int(epas_status["EPAS_eacStatus"]), None) + + ret.steeringAngleDeg = -epas_status["EPAS_internalSAS"] + ret.steeringRateDeg = -cp.vl["STW_ANGLHP_STAT"]["StW_AnglHP_Spd"] # This is from a different angle sensor, and at different rate + ret.steeringTorque = -epas_status["EPAS_torsionBarTorque"] + ret.steeringPressed = (self.hands_on_level > 0) + ret.steerFaultPermanent = steer_status == "EAC_FAULT" + ret.steerFaultTemporary = (self.steer_warning not in ("EAC_ERROR_IDLE", "EAC_ERROR_HANDS_ON")) + + # Cruise state + cruise_state = self.can_define.dv["DI_state"]["DI_cruiseState"].get(int(cp.vl["DI_state"]["DI_cruiseState"]), None) + speed_units = self.can_define.dv["DI_state"]["DI_speedUnits"].get(int(cp.vl["DI_state"]["DI_speedUnits"]), None) + + acc_enabled = (cruise_state in ("ENABLED", "STANDSTILL", "OVERRIDE", "PRE_FAULT", "PRE_CANCEL")) + + ret.cruiseState.enabled = acc_enabled + if speed_units == "KPH": + ret.cruiseState.speed = cp.vl["DI_state"]["DI_digitalSpeed"] * CV.KPH_TO_MS + elif speed_units == "MPH": + ret.cruiseState.speed = cp.vl["DI_state"]["DI_digitalSpeed"] * CV.MPH_TO_MS + ret.cruiseState.available = ((cruise_state == "STANDBY") or ret.cruiseState.enabled) + ret.cruiseState.standstill = False # This needs to be false, since we can resume from stop without sending anything special + + # Gear + ret.gearShifter = GEAR_MAP[self.can_define.dv["DI_torque2"]["DI_gear"].get(int(cp.vl["DI_torque2"]["DI_gear"]), "DI_GEAR_INVALID")] + + # Buttons + buttonEvents = [] + for button in BUTTONS: + state = (cp.vl[button.can_addr][button.can_msg] in button.values) + if self.button_states[button.event_type] != state: + event = car.CarState.ButtonEvent.new_message() + event.type = button.event_type + event.pressed = state + buttonEvents.append(event) + self.button_states[button.event_type] = state + ret.buttonEvents = buttonEvents + + # Doors + ret.doorOpen = any((self.can_define.dv["GTW_carState"][door].get(int(cp.vl["GTW_carState"][door]), "OPEN") == "OPEN") for door in DOORS) + + # Blinkers + ret.leftBlinker = (cp.vl["GTW_carState"]["BC_indicatorLStatus"] == 1) + ret.rightBlinker = (cp.vl["GTW_carState"]["BC_indicatorRStatus"] == 1) + + # Seatbelt + if self.CP.carFingerprint == CAR.TESLA_MODELS_RAVEN: + ret.seatbeltUnlatched = (cp.vl["DriverSeat"]["buckleStatus"] != 1) + else: + ret.seatbeltUnlatched = (cp.vl["SDM1"]["SDM_bcklDrivStatus"] != 1) + + # TODO: blindspot + + # AEB + ret.stockAeb = (cp_cam.vl["DAS_control"]["DAS_aebEvent"] == 1) + + # Messages needed by carcontroller + self.msg_stw_actn_req = copy.copy(cp.vl["STW_ACTN_RQ"]) + self.acc_state = cp_cam.vl["DAS_control"]["DAS_accState"] + self.das_control_counters.extend(cp_cam.vl_all["DAS_control"]["DAS_controlCounter"]) + + return ret + + @staticmethod + def get_can_parser(CP): + messages = [ + # sig_address, frequency + ("ESP_B", 50), + ("DI_torque1", 100), + ("DI_torque2", 100), + ("STW_ANGLHP_STAT", 100), + ("EPAS_sysStatus", 25), + ("DI_state", 10), + ("STW_ACTN_RQ", 10), + ("GTW_carState", 10), + ("BrakeMessage", 50), + ] + + if CP.carFingerprint == CAR.TESLA_MODELS_RAVEN: + messages.append(("DriverSeat", 20)) + else: + messages.append(("SDM1", 10)) + + return CANParser(DBC[CP.carFingerprint]['chassis'], messages, CANBUS.chassis) + + @staticmethod + def get_cam_can_parser(CP): + messages = [ + # sig_address, frequency + ("DAS_control", 40), + ] + + if CP.carFingerprint == CAR.TESLA_MODELS_RAVEN: + messages.append(("EPAS3P_sysStatus", 100)) + + return CANParser(DBC[CP.carFingerprint]['chassis'], messages, CANBUS.autopilot_chassis) diff --git a/car/tesla/fingerprints.py b/car/tesla/fingerprints.py new file mode 100644 index 0000000000..68c50a62ed --- /dev/null +++ b/car/tesla/fingerprints.py @@ -0,0 +1,32 @@ +from cereal import car +from openpilot.selfdrive.car.tesla.values import CAR + +Ecu = car.CarParams.Ecu + +FW_VERSIONS = { + CAR.TESLA_AP2_MODELS: { + (Ecu.adas, 0x649, None): [ + b'\x01\x00\x8b\x07\x01\x00\x01\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x11', + ], + (Ecu.electricBrakeBooster, 0x64d, None): [ + b'1037123-00-A', + ], + (Ecu.fwdRadar, 0x671, None): [ + b'\x01\x00W\x00\x00\x00\x07\x00\x00\x00\x00\x08\x01\x00\x00\x00\x07\xff\xfe', + ], + (Ecu.eps, 0x730, None): [ + b'\x10#\x01', + ], + }, + CAR.TESLA_MODELS_RAVEN: { + (Ecu.electricBrakeBooster, 0x64d, None): [ + b'1037123-00-A', + ], + (Ecu.fwdRadar, 0x671, None): [ + b'\x01\x00\x99\x02\x01\x00\x10\x00\x00AP8.3.03\x00\x10', + ], + (Ecu.eps, 0x730, None): [ + b'SX_0.0.0 (99),SR013.7', + ], + }, +} diff --git a/car/tesla/interface.py b/car/tesla/interface.py new file mode 100755 index 0000000000..e039859263 --- /dev/null +++ b/car/tesla/interface.py @@ -0,0 +1,52 @@ +#!/usr/bin/env python3 +from cereal import car +from panda import Panda +from openpilot.selfdrive.car.tesla.values import CANBUS, CAR +from openpilot.selfdrive.car import get_safety_config +from openpilot.selfdrive.car.interfaces import CarInterfaceBase + + +class CarInterface(CarInterfaceBase): + @staticmethod + def _get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs): + ret.carName = "tesla" + + # There is no safe way to do steer blending with user torque, + # so the steering behaves like autopilot. This is not + # how openpilot should be, hence dashcamOnly + ret.dashcamOnly = True + + ret.steerControlType = car.CarParams.SteerControlType.angle + + # Set kP and kI to 0 over the whole speed range to have the planner accel as actuator command + ret.longitudinalTuning.kpBP = [0] + ret.longitudinalTuning.kpV = [0] + ret.longitudinalTuning.kiBP = [0] + ret.longitudinalTuning.kiV = [0] + ret.longitudinalActuatorDelayUpperBound = 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 + # If so, we assume that it is connected to the longitudinal harness. + flags = (Panda.FLAG_TESLA_RAVEN if candidate == CAR.TESLA_MODELS_RAVEN else 0) + if (CANBUS.autopilot_powertrain in fingerprint.keys()) and (0x2bf in fingerprint[CANBUS.autopilot_powertrain].keys()): + ret.openpilotLongitudinalControl = True + flags |= Panda.FLAG_TESLA_LONG_CONTROL + ret.safetyConfigs = [ + get_safety_config(car.CarParams.SafetyModel.tesla, flags), + get_safety_config(car.CarParams.SafetyModel.tesla, flags | Panda.FLAG_TESLA_POWERTRAIN), + ] + else: + ret.openpilotLongitudinalControl = False + ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.tesla, flags)] + + ret.steerLimitTimer = 1.0 + ret.steerActuatorDelay = 0.25 + return ret + + def _update(self, c): + ret = self.CS.update(self.cp, self.cp_cam) + + ret.events = self.create_common_events(ret).to_msg() + + return ret diff --git a/car/tesla/radar_interface.py b/car/tesla/radar_interface.py new file mode 100755 index 0000000000..ae5077824b --- /dev/null +++ b/car/tesla/radar_interface.py @@ -0,0 +1,91 @@ +#!/usr/bin/env python3 +from cereal import car +from opendbc.can.parser import CANParser +from openpilot.selfdrive.car.tesla.values import CAR, DBC, CANBUS +from openpilot.selfdrive.car.interfaces import RadarInterfaceBase + + +class RadarInterface(RadarInterfaceBase): + def __init__(self, CP): + super().__init__(CP) + self.CP = CP + + if CP.carFingerprint == CAR.TESLA_MODELS_RAVEN: + messages = [('RadarStatus', 16)] + self.num_points = 40 + self.trigger_msg = 1119 + else: + messages = [('TeslaRadarSguInfo', 10)] + self.num_points = 32 + self.trigger_msg = 878 + + for i in range(self.num_points): + messages.extend([ + (f'RadarPoint{i}_A', 16), + (f'RadarPoint{i}_B', 16), + ]) + + self.rcp = CANParser(DBC[CP.carFingerprint]['radar'], messages, CANBUS.radar) + self.updated_messages = set() + self.track_id = 0 + + def update(self, can_strings): + if self.rcp is None: + return super().update(None) + + values = self.rcp.update_strings(can_strings) + self.updated_messages.update(values) + + if self.trigger_msg not in self.updated_messages: + return None + + ret = car.RadarData.new_message() + + # Errors + errors = [] + if not self.rcp.can_valid: + errors.append('canError') + + if self.CP.carFingerprint == CAR.TESLA_MODELS_RAVEN: + radar_status = self.rcp.vl['RadarStatus'] + if radar_status['sensorBlocked'] or radar_status['shortTermUnavailable'] or radar_status['vehDynamicsError']: + errors.append('fault') + else: + radar_status = self.rcp.vl['TeslaRadarSguInfo'] + if radar_status['RADC_HWFail'] or radar_status['RADC_SGUFail'] or radar_status['RADC_SensorDirty']: + errors.append('fault') + + ret.errors = errors + + # Radar tracks + for i in range(self.num_points): + msg_a = self.rcp.vl[f'RadarPoint{i}_A'] + msg_b = self.rcp.vl[f'RadarPoint{i}_B'] + + # Make sure msg A and B are together + if msg_a['Index'] != msg_b['Index2']: + continue + + # Check if it's a valid track + if not msg_a['Tracked']: + if i in self.pts: + del self.pts[i] + continue + + # New track! + if i not in self.pts: + self.pts[i] = car.RadarData.RadarPoint.new_message() + self.pts[i].trackId = self.track_id + self.track_id += 1 + + # Parse track data + self.pts[i].dRel = msg_a['LongDist'] + self.pts[i].yRel = msg_a['LatDist'] + self.pts[i].vRel = msg_a['LongSpeed'] + self.pts[i].aRel = msg_a['LongAccel'] + self.pts[i].yvRel = msg_b['LatSpeed'] + self.pts[i].measured = bool(msg_a['Meas']) + + ret.points = list(self.pts.values()) + self.updated_messages.clear() + return ret diff --git a/car/tesla/teslacan.py b/car/tesla/teslacan.py new file mode 100644 index 0000000000..6bb27b995f --- /dev/null +++ b/car/tesla/teslacan.py @@ -0,0 +1,94 @@ +import crcmod + +from openpilot.common.conversions import Conversions as CV +from openpilot.selfdrive.car.tesla.values import CANBUS, CarControllerParams + + +class TeslaCAN: + def __init__(self, packer, pt_packer): + self.packer = packer + self.pt_packer = pt_packer + self.crc = crcmod.mkCrcFun(0x11d, initCrc=0x00, rev=False, xorOut=0xff) + + @staticmethod + def checksum(msg_id, dat): + # TODO: get message ID from name instead + ret = (msg_id & 0xFF) + ((msg_id >> 8) & 0xFF) + ret += sum(dat) + return ret & 0xFF + + def create_steering_control(self, angle, enabled, counter): + values = { + "DAS_steeringAngleRequest": -angle, + "DAS_steeringHapticRequest": 0, + "DAS_steeringControlType": 1 if enabled else 0, + "DAS_steeringControlCounter": counter, + } + + data = self.packer.make_can_msg("DAS_steeringControl", CANBUS.chassis, values)[2] + values["DAS_steeringControlChecksum"] = self.checksum(0x488, data[:3]) + return self.packer.make_can_msg("DAS_steeringControl", CANBUS.chassis, values) + + def create_action_request(self, msg_stw_actn_req, cancel, bus, counter): + # We copy this whole message when spamming cancel + values = {s: msg_stw_actn_req[s] for s in [ + "SpdCtrlLvr_Stat", + "VSL_Enbl_Rq", + "SpdCtrlLvrStat_Inv", + "DTR_Dist_Rq", + "TurnIndLvr_Stat", + "HiBmLvr_Stat", + "WprWashSw_Psd", + "WprWash_R_Sw_Posn_V2", + "StW_Lvr_Stat", + "StW_Cond_Flt", + "StW_Cond_Psd", + "HrnSw_Psd", + "StW_Sw00_Psd", + "StW_Sw01_Psd", + "StW_Sw02_Psd", + "StW_Sw03_Psd", + "StW_Sw04_Psd", + "StW_Sw05_Psd", + "StW_Sw06_Psd", + "StW_Sw07_Psd", + "StW_Sw08_Psd", + "StW_Sw09_Psd", + "StW_Sw10_Psd", + "StW_Sw11_Psd", + "StW_Sw12_Psd", + "StW_Sw13_Psd", + "StW_Sw14_Psd", + "StW_Sw15_Psd", + "WprSw6Posn", + "MC_STW_ACTN_RQ", + "CRC_STW_ACTN_RQ", + ]} + + if cancel: + values["SpdCtrlLvr_Stat"] = 1 + values["MC_STW_ACTN_RQ"] = counter + + data = self.packer.make_can_msg("STW_ACTN_RQ", bus, values)[2] + values["CRC_STW_ACTN_RQ"] = self.crc(data[:7]) + return self.packer.make_can_msg("STW_ACTN_RQ", bus, values) + + def create_longitudinal_commands(self, acc_state, speed, min_accel, max_accel, cnt): + messages = [] + values = { + "DAS_setSpeed": speed * CV.MS_TO_KPH, + "DAS_accState": acc_state, + "DAS_aebEvent": 0, + "DAS_jerkMin": CarControllerParams.JERK_LIMIT_MIN, + "DAS_jerkMax": CarControllerParams.JERK_LIMIT_MAX, + "DAS_accelMin": min_accel, + "DAS_accelMax": max_accel, + "DAS_controlCounter": cnt, + "DAS_controlChecksum": 0, + } + + for packer, bus in [(self.packer, CANBUS.chassis), (self.pt_packer, CANBUS.powertrain)]: + data = packer.make_can_msg("DAS_control", bus, values)[2] + values["DAS_controlChecksum"] = self.checksum(0x2b9, data[:7]) + messages.append(packer.make_can_msg("DAS_control", bus, values)) + return messages diff --git a/car/tesla/values.py b/car/tesla/values.py new file mode 100644 index 0000000000..0f9cd00f63 --- /dev/null +++ b/car/tesla/values.py @@ -0,0 +1,98 @@ +from collections import namedtuple + +from cereal import car +from openpilot.selfdrive.car import AngleRateLimit, CarSpecs, PlatformConfig, Platforms, dbc_dict +from openpilot.selfdrive.car.docs_definitions import CarDocs +from openpilot.selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries + +Ecu = car.CarParams.Ecu + +Button = namedtuple('Button', ['event_type', 'can_addr', 'can_msg', 'values']) + +class CAR(Platforms): + TESLA_AP1_MODELS = PlatformConfig( + [CarDocs("Tesla AP1 Model S", "All")], + CarSpecs(mass=2100., wheelbase=2.959, steerRatio=15.0), + dbc_dict('tesla_powertrain', 'tesla_radar_bosch_generated', chassis_dbc='tesla_can') + ) + TESLA_AP2_MODELS = PlatformConfig( + [CarDocs("Tesla AP2 Model S", "All")], + TESLA_AP1_MODELS.specs, + TESLA_AP1_MODELS.dbc_dict + ) + TESLA_MODELS_RAVEN = PlatformConfig( + [CarDocs("Tesla Model S Raven", "All")], + TESLA_AP1_MODELS.specs, + dbc_dict('tesla_powertrain', 'tesla_radar_continental_generated', chassis_dbc='tesla_can') + ) + +FW_QUERY_CONFIG = FwQueryConfig( + requests=[ + Request( + [StdQueries.TESTER_PRESENT_REQUEST, StdQueries.UDS_VERSION_REQUEST], + [StdQueries.TESTER_PRESENT_RESPONSE, StdQueries.UDS_VERSION_RESPONSE], + whitelist_ecus=[Ecu.eps], + rx_offset=0x08, + bus=0, + ), + Request( + [StdQueries.TESTER_PRESENT_REQUEST, StdQueries.SUPPLIER_SOFTWARE_VERSION_REQUEST], + [StdQueries.TESTER_PRESENT_RESPONSE, StdQueries.SUPPLIER_SOFTWARE_VERSION_RESPONSE], + whitelist_ecus=[Ecu.eps], + rx_offset=0x08, + bus=0, + ), + Request( + [StdQueries.TESTER_PRESENT_REQUEST, StdQueries.UDS_VERSION_REQUEST], + [StdQueries.TESTER_PRESENT_RESPONSE, StdQueries.UDS_VERSION_RESPONSE], + whitelist_ecus=[Ecu.adas, Ecu.electricBrakeBooster, Ecu.fwdRadar], + rx_offset=0x10, + bus=0, + ), + ] +) + +class CANBUS: + # Lateral harness + chassis = 0 + radar = 1 + autopilot_chassis = 2 + + # Longitudinal harness + powertrain = 4 + private = 5 + autopilot_powertrain = 6 + +GEAR_MAP = { + "DI_GEAR_INVALID": car.CarState.GearShifter.unknown, + "DI_GEAR_P": car.CarState.GearShifter.park, + "DI_GEAR_R": car.CarState.GearShifter.reverse, + "DI_GEAR_N": car.CarState.GearShifter.neutral, + "DI_GEAR_D": car.CarState.GearShifter.drive, + "DI_GEAR_SNA": car.CarState.GearShifter.unknown, +} + +DOORS = ["DOOR_STATE_FL", "DOOR_STATE_FR", "DOOR_STATE_RL", "DOOR_STATE_RR", "DOOR_STATE_FrontTrunk", "BOOT_STATE"] + +# Make sure the message and addr is also in the CAN parser! +BUTTONS = [ + Button(car.CarState.ButtonEvent.Type.leftBlinker, "STW_ACTN_RQ", "TurnIndLvr_Stat", [1]), + Button(car.CarState.ButtonEvent.Type.rightBlinker, "STW_ACTN_RQ", "TurnIndLvr_Stat", [2]), + Button(car.CarState.ButtonEvent.Type.accelCruise, "STW_ACTN_RQ", "SpdCtrlLvr_Stat", [4, 16]), + Button(car.CarState.ButtonEvent.Type.decelCruise, "STW_ACTN_RQ", "SpdCtrlLvr_Stat", [8, 32]), + Button(car.CarState.ButtonEvent.Type.cancel, "STW_ACTN_RQ", "SpdCtrlLvr_Stat", [1]), + Button(car.CarState.ButtonEvent.Type.resumeCruise, "STW_ACTN_RQ", "SpdCtrlLvr_Stat", [2]), +] + +class CarControllerParams: + ANGLE_RATE_LIMIT_UP = AngleRateLimit(speed_bp=[0., 5., 15.], angle_v=[10., 1.6, .3]) + ANGLE_RATE_LIMIT_DOWN = AngleRateLimit(speed_bp=[0., 5., 15.], angle_v=[10., 7.0, 0.8]) + JERK_LIMIT_MAX = 8 + JERK_LIMIT_MIN = -8 + ACCEL_TO_SPEED_MULTIPLIER = 3 + + def __init__(self, CP): + pass + + +DBC = CAR.create_dbc_map() diff --git a/car/toyota/__init__.py b/car/toyota/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/car/toyota/carcontroller.py b/car/toyota/carcontroller.py new file mode 100644 index 0000000000..f9b7a478e0 --- /dev/null +++ b/car/toyota/carcontroller.py @@ -0,0 +1,179 @@ +from cereal import car +from openpilot.common.numpy_fast import clip +from openpilot.selfdrive.car import apply_meas_steer_torque_limits, apply_std_steer_angle_limits, common_fault_avoidance, make_can_msg +from openpilot.selfdrive.car.interfaces import CarControllerBase +from openpilot.selfdrive.car.toyota import toyotacan +from openpilot.selfdrive.car.toyota.values import CAR, STATIC_DSU_MSGS, NO_STOP_TIMER_CAR, TSS2_CAR, \ + CarControllerParams, ToyotaFlags, \ + UNSUPPORTED_DSU_CAR +from opendbc.can.packer import CANPacker + +SteerControlType = car.CarParams.SteerControlType +VisualAlert = car.CarControl.HUDControl.VisualAlert + +# LKA limits +# EPS faults if you apply torque while the steering rate is above 100 deg/s for too long +MAX_STEER_RATE = 100 # deg/s +MAX_STEER_RATE_FRAMES = 18 # tx control frames needed before torque can be cut + +# EPS allows user torque above threshold for 50 frames before permanently faulting +MAX_USER_TORQUE = 500 + +# LTA limits +# EPS ignores commands above this angle and causes PCS to fault +MAX_LTA_ANGLE = 94.9461 # deg +MAX_LTA_DRIVER_TORQUE_ALLOWANCE = 150 # slightly above steering pressed allows some resistance when changing lanes + + +class CarController(CarControllerBase): + def __init__(self, dbc_name, CP, VM): + self.CP = CP + self.params = CarControllerParams(self.CP) + self.frame = 0 + self.last_steer = 0 + self.last_angle = 0 + self.alert_active = False + self.last_standstill = False + self.standstill_req = False + self.steer_rate_counter = 0 + self.distance_button = 0 + + self.packer = CANPacker(dbc_name) + self.gas = 0 + self.accel = 0 + + def update(self, CC, CS, now_nanos): + actuators = CC.actuators + hud_control = CC.hudControl + pcm_cancel_cmd = CC.cruiseControl.cancel + lat_active = CC.latActive and abs(CS.out.steeringTorque) < MAX_USER_TORQUE + + # *** control msgs *** + can_sends = [] + + # *** steer torque *** + new_steer = int(round(actuators.steer * self.params.STEER_MAX)) + apply_steer = apply_meas_steer_torque_limits(new_steer, self.last_steer, CS.out.steeringTorqueEps, self.params) + + # >100 degree/sec steering fault prevention + self.steer_rate_counter, apply_steer_req = common_fault_avoidance(abs(CS.out.steeringRateDeg) >= MAX_STEER_RATE, lat_active, + self.steer_rate_counter, MAX_STEER_RATE_FRAMES) + + if not lat_active: + apply_steer = 0 + + # *** steer angle *** + if self.CP.steerControlType == SteerControlType.angle: + # If using LTA control, disable LKA and set steering angle command + apply_steer = 0 + apply_steer_req = False + if self.frame % 2 == 0: + # EPS uses the torque sensor angle to control with, offset to compensate + apply_angle = actuators.steeringAngleDeg + CS.out.steeringAngleOffsetDeg + + # Angular rate limit based on speed + apply_angle = apply_std_steer_angle_limits(apply_angle, self.last_angle, CS.out.vEgoRaw, self.params) + + if not lat_active: + apply_angle = CS.out.steeringAngleDeg + CS.out.steeringAngleOffsetDeg + + self.last_angle = clip(apply_angle, -MAX_LTA_ANGLE, MAX_LTA_ANGLE) + + self.last_steer = apply_steer + + # toyota can trace shows STEERING_LKA at 42Hz, with counter adding alternatively 1 and 2; + # sending it at 100Hz seem to allow a higher rate limit, as the rate limit seems imposed + # on consecutive messages + can_sends.append(toyotacan.create_steer_command(self.packer, apply_steer, apply_steer_req)) + + # STEERING_LTA does not seem to allow more rate by sending faster, and may wind up easier + if self.frame % 2 == 0 and self.CP.carFingerprint in TSS2_CAR: + lta_active = lat_active and self.CP.steerControlType == SteerControlType.angle + # cut steering torque with TORQUE_WIND_DOWN when either EPS torque or driver torque is above + # the threshold, to limit max lateral acceleration and for driver torque blending respectively. + full_torque_condition = (abs(CS.out.steeringTorqueEps) < self.params.STEER_MAX and + abs(CS.out.steeringTorque) < MAX_LTA_DRIVER_TORQUE_ALLOWANCE) + + # TORQUE_WIND_DOWN at 0 ramps down torque at roughly the max down rate of 1500 units/sec + torque_wind_down = 100 if lta_active and full_torque_condition else 0 + can_sends.append(toyotacan.create_lta_steer_command(self.packer, self.CP.steerControlType, self.last_angle, + lta_active, self.frame // 2, torque_wind_down)) + + # *** gas and brake *** + pcm_accel_cmd = clip(actuators.accel, self.params.ACCEL_MIN, self.params.ACCEL_MAX) + + # on entering standstill, send standstill request + if CS.out.standstill and not self.last_standstill and (self.CP.carFingerprint not in NO_STOP_TIMER_CAR): + self.standstill_req = True + if CS.pcm_acc_status != 8: + # pcm entered standstill or it's disabled + self.standstill_req = False + + self.last_standstill = CS.out.standstill + + # handle UI messages + fcw_alert = hud_control.visualAlert == VisualAlert.fcw + steer_alert = hud_control.visualAlert in (VisualAlert.steerRequired, VisualAlert.ldw) + + # we can spam can to cancel the system even if we are using lat only control + if (self.frame % 3 == 0 and self.CP.openpilotLongitudinalControl) or pcm_cancel_cmd: + lead = hud_control.leadVisible or CS.out.vEgo < 12. # at low speed we always assume the lead is present so ACC can be engaged + + # Press distance button until we are at the correct bar length. Only change while enabled to avoid skipping startup popup + if self.frame % 6 == 0 and self.CP.openpilotLongitudinalControl: + desired_distance = 4 - hud_control.leadDistanceBars + if CS.out.cruiseState.enabled and CS.pcm_follow_distance != desired_distance: + self.distance_button = not self.distance_button + else: + self.distance_button = 0 + + # Lexus IS uses a different cancellation message + if pcm_cancel_cmd and self.CP.carFingerprint in UNSUPPORTED_DSU_CAR: + can_sends.append(toyotacan.create_acc_cancel_command(self.packer)) + elif self.CP.openpilotLongitudinalControl: + can_sends.append(toyotacan.create_accel_command(self.packer, pcm_accel_cmd, pcm_cancel_cmd, self.standstill_req, lead, CS.acc_type, fcw_alert, + self.distance_button)) + self.accel = pcm_accel_cmd + else: + can_sends.append(toyotacan.create_accel_command(self.packer, 0, pcm_cancel_cmd, False, lead, CS.acc_type, False, self.distance_button)) + + # *** hud ui *** + if self.CP.carFingerprint != CAR.TOYOTA_PRIUS_V: + # ui mesg is at 1Hz but we send asap if: + # - there is something to display + # - there is something to stop displaying + send_ui = False + if ((fcw_alert or steer_alert) and not self.alert_active) or \ + (not (fcw_alert or steer_alert) and self.alert_active): + send_ui = True + self.alert_active = not self.alert_active + elif pcm_cancel_cmd: + # forcing the pcm to disengage causes a bad fault sound so play a good sound instead + send_ui = True + + if self.frame % 20 == 0 or send_ui: + can_sends.append(toyotacan.create_ui_command(self.packer, steer_alert, pcm_cancel_cmd, hud_control.leftLaneVisible, + hud_control.rightLaneVisible, hud_control.leftLaneDepart, + hud_control.rightLaneDepart, CC.enabled, CS.lkas_hud)) + + if (self.frame % 100 == 0 or send_ui) and (self.CP.enableDsu or self.CP.flags & ToyotaFlags.DISABLE_RADAR.value): + can_sends.append(toyotacan.create_fcw_command(self.packer, fcw_alert)) + + # *** static msgs *** + for addr, cars, bus, fr_step, vl in STATIC_DSU_MSGS: + if self.frame % fr_step == 0 and self.CP.enableDsu and self.CP.carFingerprint in cars: + can_sends.append(make_can_msg(addr, vl, bus)) + + # keep radar disabled + if self.frame % 20 == 0 and self.CP.flags & ToyotaFlags.DISABLE_RADAR.value: + can_sends.append([0x750, 0, b"\x0F\x02\x3E\x00\x00\x00\x00\x00", 0]) + + new_actuators = actuators.as_builder() + new_actuators.steer = apply_steer / self.params.STEER_MAX + new_actuators.steerOutputCan = apply_steer + new_actuators.steeringAngleDeg = self.last_angle + new_actuators.accel = self.accel + new_actuators.gas = self.gas + + self.frame += 1 + return new_actuators, can_sends diff --git a/car/toyota/carstate.py b/car/toyota/carstate.py new file mode 100644 index 0000000000..8315f24ae4 --- /dev/null +++ b/car/toyota/carstate.py @@ -0,0 +1,247 @@ +import copy + +from cereal import car +from openpilot.common.conversions import Conversions as CV +from openpilot.common.numpy_fast import mean +from openpilot.common.filter_simple import FirstOrderFilter +from openpilot.common.realtime import DT_CTRL +from opendbc.can.can_define import CANDefine +from opendbc.can.parser import CANParser +from openpilot.selfdrive.car.interfaces import CarStateBase +from openpilot.selfdrive.car.toyota.values import ToyotaFlags, CAR, DBC, STEER_THRESHOLD, NO_STOP_TIMER_CAR, \ + TSS2_CAR, RADAR_ACC_CAR, EPS_SCALE, UNSUPPORTED_DSU_CAR + +SteerControlType = car.CarParams.SteerControlType + +# These steering fault definitions seem to be common across LKA (torque) and LTA (angle): +# - high steer rate fault: goes to 21 or 25 for 1 frame, then 9 for 2 seconds +# - lka/lta msg drop out: goes to 9 then 11 for a combined total of 2 seconds, then 3. +# if using the other control command, goes directly to 3 after 1.5 seconds +# - initializing: LTA can report 0 as long as STEER_TORQUE_SENSOR->STEER_ANGLE_INITIALIZING is 1, +# and is a catch-all for LKA +TEMP_STEER_FAULTS = (0, 9, 11, 21, 25) +# - lka/lta msg drop out: 3 (recoverable) +# - prolonged high driver torque: 17 (permanent) +PERM_STEER_FAULTS = (3, 17) + + +class CarState(CarStateBase): + def __init__(self, CP): + super().__init__(CP) + can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) + self.shifter_values = can_define.dv["GEAR_PACKET"]["GEAR"] + self.eps_torque_scale = EPS_SCALE[CP.carFingerprint] / 100. + self.cluster_speed_hyst_gap = CV.KPH_TO_MS / 2. + self.cluster_min_speed = CV.KPH_TO_MS / 2. + + # On cars with cp.vl["STEER_TORQUE_SENSOR"]["STEER_ANGLE"] + # the signal is zeroed to where the steering angle is at start. + # Need to apply an offset as soon as the steering angle measurements are both received + self.accurate_steer_angle_seen = False + self.angle_offset = FirstOrderFilter(None, 60.0, DT_CTRL, initialized=False) + + self.prev_distance_button = 0 + self.distance_button = 0 + + self.pcm_follow_distance = 0 + + self.low_speed_lockout = False + self.acc_type = 1 + self.lkas_hud = {} + + def update(self, cp, cp_cam): + ret = car.CarState.new_message() + + ret.doorOpen = any([cp.vl["BODY_CONTROL_STATE"]["DOOR_OPEN_FL"], cp.vl["BODY_CONTROL_STATE"]["DOOR_OPEN_FR"], + cp.vl["BODY_CONTROL_STATE"]["DOOR_OPEN_RL"], cp.vl["BODY_CONTROL_STATE"]["DOOR_OPEN_RR"]]) + ret.seatbeltUnlatched = cp.vl["BODY_CONTROL_STATE"]["SEATBELT_DRIVER_UNLATCHED"] != 0 + ret.parkingBrake = cp.vl["BODY_CONTROL_STATE"]["PARKING_BRAKE"] == 1 + + ret.brakePressed = cp.vl["BRAKE_MODULE"]["BRAKE_PRESSED"] != 0 + ret.brakeHoldActive = cp.vl["ESP_CONTROL"]["BRAKE_HOLD_ACTIVE"] == 1 + + ret.gasPressed = cp.vl["PCM_CRUISE"]["GAS_RELEASED"] == 0 + + ret.wheelSpeeds = self.get_wheel_speeds( + cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_FL"], + cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_FR"], + cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_RL"], + cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_RR"], + ) + 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.vEgoCluster = ret.vEgo * 1.015 # minimum of all the cars + + ret.standstill = abs(ret.vEgoRaw) < 1e-3 + + ret.steeringAngleDeg = cp.vl["STEER_ANGLE_SENSOR"]["STEER_ANGLE"] + cp.vl["STEER_ANGLE_SENSOR"]["STEER_FRACTION"] + ret.steeringRateDeg = cp.vl["STEER_ANGLE_SENSOR"]["STEER_RATE"] + torque_sensor_angle_deg = cp.vl["STEER_TORQUE_SENSOR"]["STEER_ANGLE"] + + # On some cars, the angle measurement is non-zero while initializing + if abs(torque_sensor_angle_deg) > 1e-3 and not bool(cp.vl["STEER_TORQUE_SENSOR"]["STEER_ANGLE_INITIALIZING"]): + self.accurate_steer_angle_seen = True + + if self.accurate_steer_angle_seen: + # Offset seems to be invalid for large steering angles and high angle rates + if abs(ret.steeringAngleDeg) < 90 and abs(ret.steeringRateDeg) < 100 and cp.can_valid: + self.angle_offset.update(torque_sensor_angle_deg - ret.steeringAngleDeg) + + if self.angle_offset.initialized: + ret.steeringAngleOffsetDeg = self.angle_offset.x + ret.steeringAngleDeg = torque_sensor_angle_deg - self.angle_offset.x + + can_gear = int(cp.vl["GEAR_PACKET"]["GEAR"]) + ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(can_gear, None)) + ret.leftBlinker = cp.vl["BLINKERS_STATE"]["TURN_SIGNALS"] == 1 + ret.rightBlinker = cp.vl["BLINKERS_STATE"]["TURN_SIGNALS"] == 2 + + if self.CP.carFingerprint != CAR.TOYOTA_MIRAI: + ret.engineRpm = cp.vl["ENGINE_RPM"]["RPM"] + + ret.steeringTorque = cp.vl["STEER_TORQUE_SENSOR"]["STEER_TORQUE_DRIVER"] + ret.steeringTorqueEps = cp.vl["STEER_TORQUE_SENSOR"]["STEER_TORQUE_EPS"] * self.eps_torque_scale + # we could use the override bit from dbc, but it's triggered at too high torque values + ret.steeringPressed = abs(ret.steeringTorque) > STEER_THRESHOLD + + # Check EPS LKA/LTA fault status + ret.steerFaultTemporary = cp.vl["EPS_STATUS"]["LKA_STATE"] in TEMP_STEER_FAULTS + ret.steerFaultPermanent = cp.vl["EPS_STATUS"]["LKA_STATE"] in PERM_STEER_FAULTS + + if self.CP.steerControlType == SteerControlType.angle: + ret.steerFaultTemporary = ret.steerFaultTemporary or cp.vl["EPS_STATUS"]["LTA_STATE"] in TEMP_STEER_FAULTS + ret.steerFaultPermanent = ret.steerFaultPermanent or cp.vl["EPS_STATUS"]["LTA_STATE"] in PERM_STEER_FAULTS + + if self.CP.carFingerprint in UNSUPPORTED_DSU_CAR: + # TODO: find the bit likely in DSU_CRUISE that describes an ACC fault. one may also exist in CLUTCH + ret.cruiseState.available = cp.vl["DSU_CRUISE"]["MAIN_ON"] != 0 + ret.cruiseState.speed = cp.vl["DSU_CRUISE"]["SET_SPEED"] * CV.KPH_TO_MS + cluster_set_speed = cp.vl["PCM_CRUISE_ALT"]["UI_SET_SPEED"] + else: + ret.accFaulted = cp.vl["PCM_CRUISE_2"]["ACC_FAULTED"] != 0 + ret.cruiseState.available = cp.vl["PCM_CRUISE_2"]["MAIN_ON"] != 0 + ret.cruiseState.speed = cp.vl["PCM_CRUISE_2"]["SET_SPEED"] * CV.KPH_TO_MS + cluster_set_speed = cp.vl["PCM_CRUISE_SM"]["UI_SET_SPEED"] + + # UI_SET_SPEED is always non-zero when main is on, hide until first enable + if ret.cruiseState.speed != 0: + is_metric = cp.vl["BODY_CONTROL_STATE_2"]["UNITS"] in (1, 2) + conversion_factor = CV.KPH_TO_MS if is_metric else CV.MPH_TO_MS + ret.cruiseState.speedCluster = cluster_set_speed * conversion_factor + + cp_acc = cp_cam if self.CP.carFingerprint in (TSS2_CAR - RADAR_ACC_CAR) else cp + + if self.CP.carFingerprint in TSS2_CAR and not self.CP.flags & ToyotaFlags.DISABLE_RADAR.value: + if not (self.CP.flags & ToyotaFlags.SMART_DSU.value): + self.acc_type = cp_acc.vl["ACC_CONTROL"]["ACC_TYPE"] + ret.stockFcw = bool(cp_acc.vl["PCS_HUD"]["FCW"]) + + # some TSS2 cars have low speed lockout permanently set, so ignore on those cars + # these cars are identified by an ACC_TYPE value of 2. + # TODO: it is possible to avoid the lockout and gain stop and go if you + # send your own ACC_CONTROL msg on startup with ACC_TYPE set to 1 + if (self.CP.carFingerprint not in TSS2_CAR and self.CP.carFingerprint not in UNSUPPORTED_DSU_CAR) or \ + (self.CP.carFingerprint in TSS2_CAR and self.acc_type == 1): + self.low_speed_lockout = cp.vl["PCM_CRUISE_2"]["LOW_SPEED_LOCKOUT"] == 2 + + self.pcm_acc_status = cp.vl["PCM_CRUISE"]["CRUISE_STATE"] + if self.CP.carFingerprint not in (NO_STOP_TIMER_CAR - TSS2_CAR): + # ignore standstill state in certain vehicles, since pcm allows to restart with just an acceleration request + ret.cruiseState.standstill = self.pcm_acc_status == 7 + ret.cruiseState.enabled = bool(cp.vl["PCM_CRUISE"]["CRUISE_ACTIVE"]) + ret.cruiseState.nonAdaptive = self.pcm_acc_status in (1, 2, 3, 4, 5, 6) + + ret.genericToggle = bool(cp.vl["LIGHT_STALK"]["AUTO_HIGH_BEAM"]) + ret.espDisabled = cp.vl["ESP_CONTROL"]["TC_DISABLED"] != 0 + + if not self.CP.enableDsu and not self.CP.flags & ToyotaFlags.DISABLE_RADAR.value: + ret.stockAeb = bool(cp_acc.vl["PRE_COLLISION"]["PRECOLLISION_ACTIVE"] and cp_acc.vl["PRE_COLLISION"]["FORCE"] < -1e-5) + + if self.CP.enableBsm: + ret.leftBlindspot = (cp.vl["BSM"]["L_ADJACENT"] == 1) or (cp.vl["BSM"]["L_APPROACHING"] == 1) + ret.rightBlindspot = (cp.vl["BSM"]["R_ADJACENT"] == 1) or (cp.vl["BSM"]["R_APPROACHING"] == 1) + + if self.CP.carFingerprint != CAR.TOYOTA_PRIUS_V: + self.lkas_hud = copy.copy(cp_cam.vl["LKAS_HUD"]) + + if self.CP.carFingerprint not in UNSUPPORTED_DSU_CAR: + self.pcm_follow_distance = cp.vl["PCM_CRUISE_2"]["PCM_FOLLOW_DISTANCE"] + + if self.CP.carFingerprint in (TSS2_CAR - RADAR_ACC_CAR) or (self.CP.flags & ToyotaFlags.SMART_DSU and not self.CP.flags & ToyotaFlags.RADAR_CAN_FILTER): + # distance button is wired to the ACC module (camera or radar) + self.prev_distance_button = self.distance_button + if self.CP.carFingerprint in (TSS2_CAR - RADAR_ACC_CAR): + self.distance_button = cp_acc.vl["ACC_CONTROL"]["DISTANCE"] + else: + self.distance_button = cp.vl["SDSU"]["FD_BUTTON"] + + return ret + + @staticmethod + def get_can_parser(CP): + messages = [ + ("GEAR_PACKET", 1), + ("LIGHT_STALK", 1), + ("BLINKERS_STATE", 0.15), + ("BODY_CONTROL_STATE", 3), + ("BODY_CONTROL_STATE_2", 2), + ("ESP_CONTROL", 3), + ("EPS_STATUS", 25), + ("BRAKE_MODULE", 40), + ("WHEEL_SPEEDS", 80), + ("STEER_ANGLE_SENSOR", 80), + ("PCM_CRUISE", 33), + ("PCM_CRUISE_SM", 1), + ("STEER_TORQUE_SENSOR", 50), + ] + + if CP.carFingerprint != CAR.TOYOTA_MIRAI: + messages.append(("ENGINE_RPM", 42)) + + if CP.carFingerprint in UNSUPPORTED_DSU_CAR: + messages.append(("DSU_CRUISE", 5)) + messages.append(("PCM_CRUISE_ALT", 1)) + else: + messages.append(("PCM_CRUISE_2", 33)) + + if CP.enableBsm: + messages.append(("BSM", 1)) + + if CP.carFingerprint in RADAR_ACC_CAR and not CP.flags & ToyotaFlags.DISABLE_RADAR.value: + if not CP.flags & ToyotaFlags.SMART_DSU.value: + messages += [ + ("ACC_CONTROL", 33), + ] + messages += [ + ("PCS_HUD", 1), + ] + + if CP.carFingerprint not in (TSS2_CAR - RADAR_ACC_CAR) and not CP.enableDsu and not CP.flags & ToyotaFlags.DISABLE_RADAR.value: + messages += [ + ("PRE_COLLISION", 33), + ] + + if CP.flags & ToyotaFlags.SMART_DSU and not CP.flags & ToyotaFlags.RADAR_CAN_FILTER: + messages += [ + ("SDSU", 100), + ] + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, 0) + + @staticmethod + def get_cam_can_parser(CP): + messages = [] + + if CP.carFingerprint != CAR.TOYOTA_PRIUS_V: + messages += [ + ("LKAS_HUD", 1), + ] + + if CP.carFingerprint in (TSS2_CAR - RADAR_ACC_CAR): + messages += [ + ("PRE_COLLISION", 33), + ("ACC_CONTROL", 33), + ("PCS_HUD", 1), + ] + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, 2) diff --git a/car/toyota/fingerprints.py b/car/toyota/fingerprints.py new file mode 100644 index 0000000000..0866a4d43c --- /dev/null +++ b/car/toyota/fingerprints.py @@ -0,0 +1,1681 @@ +from cereal import car +from openpilot.selfdrive.car.toyota.values import CAR + +Ecu = car.CarParams.Ecu + +FW_VERSIONS = { + CAR.TOYOTA_AVALON: { + (Ecu.abs, 0x7b0, None): [ + b'F152607060\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'881510701300\x00\x00\x00\x00', + b'881510705100\x00\x00\x00\x00', + b'881510705200\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B41051\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\x0230721100\x00\x00\x00\x00\x00\x00\x00\x00A0C01000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0230721200\x00\x00\x00\x00\x00\x00\x00\x00A0C01000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4702000\x00\x00\x00\x00', + b'8821F4702100\x00\x00\x00\x00', + b'8821F4702300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F0701100\x00\x00\x00\x00', + b'8646F0703000\x00\x00\x00\x00', + ], + }, + CAR.TOYOTA_AVALON_2019: { + (Ecu.abs, 0x7b0, None): [ + b'F152607110\x00\x00\x00\x00\x00\x00', + b'F152607140\x00\x00\x00\x00\x00\x00', + b'F152607171\x00\x00\x00\x00\x00\x00', + b'F152607180\x00\x00\x00\x00\x00\x00', + b'F152641040\x00\x00\x00\x00\x00\x00', + b'F152641050\x00\x00\x00\x00\x00\x00', + b'F152641060\x00\x00\x00\x00\x00\x00', + b'F152641061\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'881510703200\x00\x00\x00\x00', + b'881510704200\x00\x00\x00\x00', + b'881514107100\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B07010\x00\x00\x00\x00\x00\x00', + b'8965B41070\x00\x00\x00\x00\x00\x00', + b'8965B41080\x00\x00\x00\x00\x00\x00', + b'8965B41090\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x700, None): [ + b'\x01896630725100\x00\x00\x00\x00', + b'\x01896630725200\x00\x00\x00\x00', + b'\x01896630725300\x00\x00\x00\x00', + b'\x01896630725400\x00\x00\x00\x00', + b'\x01896630735100\x00\x00\x00\x00', + b'\x01896630738000\x00\x00\x00\x00', + b'\x02896630724000\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', + b'\x02896630728000\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', + b'\x02896630734000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', + b'\x02896630737000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4702300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F0702100\x00\x00\x00\x00', + ], + }, + CAR.TOYOTA_AVALON_TSS2: { + (Ecu.abs, 0x7b0, None): [ + b'\x01F152607240\x00\x00\x00\x00\x00\x00', + b'\x01F152607250\x00\x00\x00\x00\x00\x00', + b'\x01F152607280\x00\x00\x00\x00\x00\x00', + b'F152641080\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B41110\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x700, None): [ + b'\x018966306Q6000\x00\x00\x00\x00', + b'\x01896630742000\x00\x00\x00\x00', + b'\x01896630743000\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F6201200\x00\x00\x00\x00', + b'\x018821F6201300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F4104100\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', + b'\x028646F4104100\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', + ], + }, + CAR.TOYOTA_CAMRY: { + (Ecu.engine, 0x700, None): [ + b'\x018966306L3100\x00\x00\x00\x00', + b'\x018966306L4200\x00\x00\x00\x00', + b'\x018966306L5200\x00\x00\x00\x00', + b'\x018966306L9000\x00\x00\x00\x00', + b'\x018966306P8000\x00\x00\x00\x00', + b'\x018966306Q3100\x00\x00\x00\x00', + b'\x018966306Q4000\x00\x00\x00\x00', + b'\x018966306Q4100\x00\x00\x00\x00', + b'\x018966306Q4200\x00\x00\x00\x00', + b'\x018966306Q6000\x00\x00\x00\x00', + b'\x018966333N1100\x00\x00\x00\x00', + b'\x018966333N4300\x00\x00\x00\x00', + b'\x018966333P3100\x00\x00\x00\x00', + b'\x018966333P3200\x00\x00\x00\x00', + b'\x018966333P4200\x00\x00\x00\x00', + b'\x018966333P4300\x00\x00\x00\x00', + b'\x018966333P4400\x00\x00\x00\x00', + b'\x018966333P4500\x00\x00\x00\x00', + b'\x018966333P4700\x00\x00\x00\x00', + b'\x018966333P4900\x00\x00\x00\x00', + b'\x018966333Q6000\x00\x00\x00\x00', + b'\x018966333Q6200\x00\x00\x00\x00', + b'\x018966333Q6300\x00\x00\x00\x00', + b'\x018966333Q6500\x00\x00\x00\x00', + b'\x018966333Q9200\x00\x00\x00\x00', + b'\x018966333W6000\x00\x00\x00\x00', + b'\x018966333X0000\x00\x00\x00\x00', + b'\x018966333X4000\x00\x00\x00\x00', + b'\x01896633T16000\x00\x00\x00\x00', + b'\x028966306B2100\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', + b'\x028966306B2300\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', + b'\x028966306B2500\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', + b'\x028966306N8100\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', + b'\x028966306N8200\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', + b'\x028966306N8300\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', + b'\x028966306N8400\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', + b'\x028966306R5000\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', + b'\x028966306R5000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', + b'\x028966306R6000\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', + b'\x028966306R6000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', + b'\x028966306S0000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', + b'\x028966306S0100\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', + b'\x028966306S1100\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\x02333P1100\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'8821F0601200 ', + b'8821F0601300 ', + b'8821F0601400 ', + b'8821F0601500 ', + b'8821F0602000 ', + b'8821F0603300 ', + b'8821F0603400 ', + b'8821F0604000 ', + b'8821F0604100 ', + b'8821F0604200 ', + b'8821F0605200 ', + b'8821F0606200 ', + b'8821F0607200 ', + b'8821F0608000 ', + b'8821F0608200 ', + b'8821F0609000 ', + b'8821F0609100 ', + ], + (Ecu.abs, 0x7b0, None): [ + b'F152606210\x00\x00\x00\x00\x00\x00', + b'F152606230\x00\x00\x00\x00\x00\x00', + b'F152606270\x00\x00\x00\x00\x00\x00', + b'F152606290\x00\x00\x00\x00\x00\x00', + b'F152606410\x00\x00\x00\x00\x00\x00', + b'F152633214\x00\x00\x00\x00\x00\x00', + b'F152633540\x00\x00\x00\x00\x00\x00', + b'F152633660\x00\x00\x00\x00\x00\x00', + b'F152633712\x00\x00\x00\x00\x00\x00', + b'F152633713\x00\x00\x00\x00\x00\x00', + b'F152633A10\x00\x00\x00\x00\x00\x00', + b'F152633A20\x00\x00\x00\x00\x00\x00', + b'F152633B51\x00\x00\x00\x00\x00\x00', + b'F152633B60\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B33540\x00\x00\x00\x00\x00\x00', + b'8965B33542\x00\x00\x00\x00\x00\x00', + b'8965B33550\x00\x00\x00\x00\x00\x00', + b'8965B33551\x00\x00\x00\x00\x00\x00', + b'8965B33580\x00\x00\x00\x00\x00\x00', + b'8965B33581\x00\x00\x00\x00\x00\x00', + b'8965B33611\x00\x00\x00\x00\x00\x00', + b'8965B33621\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F0601200 ', + b'8821F0601300 ', + b'8821F0601400 ', + b'8821F0601500 ', + b'8821F0602000 ', + b'8821F0603300 ', + b'8821F0603400 ', + b'8821F0604000 ', + b'8821F0604100 ', + b'8821F0604200 ', + b'8821F0605200 ', + b'8821F0606200 ', + b'8821F0607200 ', + b'8821F0608000 ', + b'8821F0608200 ', + b'8821F0609000 ', + b'8821F0609100 ', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F0601200 ', + b'8646F0601300 ', + b'8646F0601400 ', + b'8646F0603400 ', + b'8646F0603500 ', + b'8646F0604000 ', + b'8646F0604100 ', + b'8646F0605000 ', + b'8646F0606000 ', + b'8646F0606100 ', + b'8646F0607000 ', + b'8646F0607100 ', + ], + }, + CAR.TOYOTA_CAMRY_TSS2: { + (Ecu.eps, 0x7a1, None): [ + b'8965B33630\x00\x00\x00\x00\x00\x00', + b'8965B33640\x00\x00\x00\x00\x00\x00', + b'8965B33650\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'\x01F152606370\x00\x00\x00\x00\x00\x00', + b'\x01F152606390\x00\x00\x00\x00\x00\x00', + b'\x01F152606400\x00\x00\x00\x00\x00\x00', + b'\x01F152606431\x00\x00\x00\x00\x00\x00', + b'F152633310\x00\x00\x00\x00\x00\x00', + b'F152633D00\x00\x00\x00\x00\x00\x00', + b'F152633D60\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x700, None): [ + b'\x018966306Q5000\x00\x00\x00\x00', + b'\x018966306Q6000\x00\x00\x00\x00', + b'\x018966306Q7000\x00\x00\x00\x00', + b'\x018966306Q9000\x00\x00\x00\x00', + b'\x018966306R3000\x00\x00\x00\x00', + b'\x018966306R8000\x00\x00\x00\x00', + b'\x018966306T0000\x00\x00\x00\x00', + b'\x018966306T3100\x00\x00\x00\x00', + b'\x018966306T3200\x00\x00\x00\x00', + b'\x018966306T4000\x00\x00\x00\x00', + b'\x018966306T4100\x00\x00\x00\x00', + b'\x018966306V1000\x00\x00\x00\x00', + b'\x01896633T20000\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F6201200\x00\x00\x00\x00', + b'\x018821F6201300\x00\x00\x00\x00', + b'\x018821F6201400\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F0602100\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', + b'\x028646F0602200\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', + b'\x028646F0602300\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', + b'\x028646F3305200\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', + b'\x028646F3305200\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', + b'\x028646F3305300\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', + b'\x028646F3305300\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', + b'\x028646F3305500\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', + ], + }, + CAR.TOYOTA_CHR: { + (Ecu.engine, 0x700, None): [ + b'\x01896631017100\x00\x00\x00\x00', + b'\x01896631017200\x00\x00\x00\x00', + b'\x01896631021100\x00\x00\x00\x00', + b'\x0189663F413100\x00\x00\x00\x00', + b'\x0189663F414100\x00\x00\x00\x00', + b'\x0189663F438000\x00\x00\x00\x00', + b'\x02896631013200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x0289663F405000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x0289663F405100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x0289663F418000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x0289663F423000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x0289663F431000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'8821F0W01000 ', + b'8821F0W01100 ', + b'8821FF401600 ', + b'8821FF402300 ', + b'8821FF402400 ', + b'8821FF404000 ', + b'8821FF404100 ', + b'8821FF405000 ', + b'8821FF405100 ', + b'8821FF406000 ', + b'8821FF407100 ', + ], + (Ecu.abs, 0x7b0, None): [ + b'F152610012\x00\x00\x00\x00\x00\x00', + b'F152610013\x00\x00\x00\x00\x00\x00', + b'F152610014\x00\x00\x00\x00\x00\x00', + b'F152610020\x00\x00\x00\x00\x00\x00', + b'F152610040\x00\x00\x00\x00\x00\x00', + b'F152610153\x00\x00\x00\x00\x00\x00', + b'F152610190\x00\x00\x00\x00\x00\x00', + b'F152610200\x00\x00\x00\x00\x00\x00', + b'F152610210\x00\x00\x00\x00\x00\x00', + b'F152610220\x00\x00\x00\x00\x00\x00', + b'F152610230\x00\x00\x00\x00\x00\x00', + b'F1526F4034\x00\x00\x00\x00\x00\x00', + b'F1526F4044\x00\x00\x00\x00\x00\x00', + b'F1526F4073\x00\x00\x00\x00\x00\x00', + b'F1526F4121\x00\x00\x00\x00\x00\x00', + b'F1526F4122\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B10011\x00\x00\x00\x00\x00\x00', + b'8965B10020\x00\x00\x00\x00\x00\x00', + b'8965B10040\x00\x00\x00\x00\x00\x00', + b'8965B10050\x00\x00\x00\x00\x00\x00', + b'8965B10070\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\x0331024000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203202\x00\x00\x00\x00', + b'\x0331024000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', + b'\x0331036000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', + b'\x033F401100\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203102\x00\x00\x00\x00', + b'\x033F401200\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203202\x00\x00\x00\x00', + b'\x033F424000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203202\x00\x00\x00\x00', + b'\x033F424000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F0W01000 ', + b'8821F0W01100 ', + b'8821FF401600 ', + b'8821FF402300 ', + b'8821FF402400 ', + b'8821FF404000 ', + b'8821FF404100 ', + b'8821FF405000 ', + b'8821FF405100 ', + b'8821FF406000 ', + b'8821FF407100 ', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646FF401700 ', + b'8646FF401800 ', + b'8646FF402100 ', + b'8646FF404000 ', + b'8646FF406000 ', + b'8646FF407000 ', + b'8646FF407100 ', + ], + }, + CAR.TOYOTA_CHR_TSS2: { + (Ecu.abs, 0x7b0, None): [ + b'F152610041\x00\x00\x00\x00\x00\x00', + b'F152610260\x00\x00\x00\x00\x00\x00', + b'F1526F4270\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B10091\x00\x00\x00\x00\x00\x00', + b'8965B10092\x00\x00\x00\x00\x00\x00', + b'8965B10110\x00\x00\x00\x00\x00\x00', + b'8965B10111\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x700, None): [ + b'\x0189663F438000\x00\x00\x00\x00', + b'\x0189663F459000\x00\x00\x00\x00', + b'\x02896631025000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x0289663F453000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\x0331014000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821FF410200\x00\x00\x00\x00', + b'\x018821FF410300\x00\x00\x00\x00', + b'\x018821FF410400\x00\x00\x00\x00', + b'\x018821FF410500\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646FF410200\x00\x00\x00\x008646GF408200\x00\x00\x00\x00', + b'\x028646FF411100\x00\x00\x00\x008646GF409000\x00\x00\x00\x00', + b'\x028646FF413100\x00\x00\x00\x008646GF411100\x00\x00\x00\x00', + ], + }, + CAR.TOYOTA_COROLLA: { + (Ecu.engine, 0x7e0, None): [ + b'\x0230ZC2000\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0230ZC2100\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0230ZC2200\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0230ZC2300\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0230ZC3000\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0230ZC3100\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0230ZC3200\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0230ZC3300\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0330ZC1200\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00895231203202\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'881510201100\x00\x00\x00\x00', + b'881510201200\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'F152602190\x00\x00\x00\x00\x00\x00', + b'F152602191\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B02181\x00\x00\x00\x00\x00\x00', + b'8965B02191\x00\x00\x00\x00\x00\x00', + b'8965B48150\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4702100\x00\x00\x00\x00', + b'8821F4702300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F0201101\x00\x00\x00\x00', + b'8646F0201200\x00\x00\x00\x00', + ], + }, + CAR.TOYOTA_COROLLA_TSS2: { + (Ecu.engine, 0x700, None): [ + b'\x01896630A22000\x00\x00\x00\x00', + b'\x01896630ZG2000\x00\x00\x00\x00', + b'\x01896630ZG5000\x00\x00\x00\x00', + b'\x01896630ZG5100\x00\x00\x00\x00', + b'\x01896630ZG5200\x00\x00\x00\x00', + b'\x01896630ZG5300\x00\x00\x00\x00', + b'\x01896630ZJ1000\x00\x00\x00\x00', + b'\x01896630ZP1000\x00\x00\x00\x00', + b'\x01896630ZP2000\x00\x00\x00\x00', + b'\x01896630ZQ5000\x00\x00\x00\x00', + b'\x01896630ZU8000\x00\x00\x00\x00', + b'\x01896630ZU9000\x00\x00\x00\x00', + b'\x01896630ZX4000\x00\x00\x00\x00', + b'\x018966312L8000\x00\x00\x00\x00', + b'\x018966312M0000\x00\x00\x00\x00', + b'\x018966312M9000\x00\x00\x00\x00', + b'\x018966312P9000\x00\x00\x00\x00', + b'\x018966312P9100\x00\x00\x00\x00', + b'\x018966312P9200\x00\x00\x00\x00', + b'\x018966312P9300\x00\x00\x00\x00', + b'\x018966312Q2300\x00\x00\x00\x00', + b'\x018966312Q8000\x00\x00\x00\x00', + b'\x018966312R0000\x00\x00\x00\x00', + b'\x018966312R0100\x00\x00\x00\x00', + b'\x018966312R0200\x00\x00\x00\x00', + b'\x018966312R1000\x00\x00\x00\x00', + b'\x018966312R1100\x00\x00\x00\x00', + b'\x018966312R3100\x00\x00\x00\x00', + b'\x018966312S5000\x00\x00\x00\x00', + b'\x018966312S7000\x00\x00\x00\x00', + b'\x018966312W3000\x00\x00\x00\x00', + b'\x018966312W9000\x00\x00\x00\x00', + b'\x01896637621000\x00\x00\x00\x00', + b'\x01896637623000\x00\x00\x00\x00', + b'\x01896637624000\x00\x00\x00\x00', + b'\x01896637626000\x00\x00\x00\x00', + b'\x01896637639000\x00\x00\x00\x00', + b'\x01896637643000\x00\x00\x00\x00', + b'\x01896637644000\x00\x00\x00\x00', + b'\x01896637648000\x00\x00\x00\x00', + b'\x02896630A07000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896630A21000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896630ZJ5000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896630ZK8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896630ZN8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896630ZQ3000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896630ZR2000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896630ZT8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896630ZT9000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896630ZZ0000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x028966312K6000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x028966312L0000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x028966312Q3000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x028966312Q3100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x028966312Q4000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x038966312L7000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF1205001\x00\x00\x00\x00', + b'\x038966312N1000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00', + b'\x038966312T3000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF1205001\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\x0230A10000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0230A11000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0230ZN4000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0230ZN5000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02312K4000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02312U5000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x03312K7000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00', + b'\x03312M3000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00', + b'\x03312N6000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203202\x00\x00\x00\x00', + b'\x03312N6000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', + b'\x03312N6000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00', + b'\x03312N6100\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', + b'\x03312N6100\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00', + b'\x03312N6200\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203202\x00\x00\x00\x00', + b'\x03312N6200\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', + b'\x03312N6200\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'\x018965B12350\x00\x00\x00\x00\x00\x00', + b'\x018965B12470\x00\x00\x00\x00\x00\x00', + b'\x018965B12490\x00\x00\x00\x00\x00\x00', + b'\x018965B12500\x00\x00\x00\x00\x00\x00', + b'\x018965B12510\x00\x00\x00\x00\x00\x00', + b'\x018965B12520\x00\x00\x00\x00\x00\x00', + b'\x018965B12530\x00\x00\x00\x00\x00\x00', + b'\x018965B1254000\x00\x00\x00\x00', + b'\x018965B1255000\x00\x00\x00\x00', + b'\x018965B1256000\x00\x00\x00\x00', + b'8965B12361\x00\x00\x00\x00\x00\x00', + b'8965B12451\x00\x00\x00\x00\x00\x00', + b'8965B16011\x00\x00\x00\x00\x00\x00', + b'8965B16101\x00\x00\x00\x00\x00\x00', + b'8965B16170\x00\x00\x00\x00\x00\x00', + b'8965B76012\x00\x00\x00\x00\x00\x00', + b'8965B76050\x00\x00\x00\x00\x00\x00', + b'8965B76091\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'\x01F152602280\x00\x00\x00\x00\x00\x00', + b'\x01F152602281\x00\x00\x00\x00\x00\x00', + b'\x01F152602470\x00\x00\x00\x00\x00\x00', + b'\x01F152602560\x00\x00\x00\x00\x00\x00', + b'\x01F152602590\x00\x00\x00\x00\x00\x00', + b'\x01F152602650\x00\x00\x00\x00\x00\x00', + b'\x01F15260A010\x00\x00\x00\x00\x00\x00', + b'\x01F15260A050\x00\x00\x00\x00\x00\x00', + b'\x01F15260A070\x00\x00\x00\x00\x00\x00', + b'\x01F152612641\x00\x00\x00\x00\x00\x00', + b'\x01F152612651\x00\x00\x00\x00\x00\x00', + b'\x01F152612862\x00\x00\x00\x00\x00\x00', + b'\x01F152612B10\x00\x00\x00\x00\x00\x00', + b'\x01F152612B51\x00\x00\x00\x00\x00\x00', + b'\x01F152612B60\x00\x00\x00\x00\x00\x00', + b'\x01F152612B61\x00\x00\x00\x00\x00\x00', + b'\x01F152612B62\x00\x00\x00\x00\x00\x00', + b'\x01F152612B70\x00\x00\x00\x00\x00\x00', + b'\x01F152612B71\x00\x00\x00\x00\x00\x00', + b'\x01F152612B81\x00\x00\x00\x00\x00\x00', + b'\x01F152612B90\x00\x00\x00\x00\x00\x00', + b'\x01F152612B91\x00\x00\x00\x00\x00\x00', + b'\x01F152612C00\x00\x00\x00\x00\x00\x00', + b'\x01F152676250\x00\x00\x00\x00\x00\x00', + b'F152612590\x00\x00\x00\x00\x00\x00', + b'F152612691\x00\x00\x00\x00\x00\x00', + b'F152612692\x00\x00\x00\x00\x00\x00', + b'F152612700\x00\x00\x00\x00\x00\x00', + b'F152612710\x00\x00\x00\x00\x00\x00', + b'F152612790\x00\x00\x00\x00\x00\x00', + b'F152612800\x00\x00\x00\x00\x00\x00', + b'F152612820\x00\x00\x00\x00\x00\x00', + b'F152612840\x00\x00\x00\x00\x00\x00', + b'F152612842\x00\x00\x00\x00\x00\x00', + b'F152612890\x00\x00\x00\x00\x00\x00', + b'F152612A00\x00\x00\x00\x00\x00\x00', + b'F152612A10\x00\x00\x00\x00\x00\x00', + b'F152612D00\x00\x00\x00\x00\x00\x00', + b'F152616011\x00\x00\x00\x00\x00\x00', + b'F152616030\x00\x00\x00\x00\x00\x00', + b'F152616060\x00\x00\x00\x00\x00\x00', + b'F152642540\x00\x00\x00\x00\x00\x00', + b'F152676293\x00\x00\x00\x00\x00\x00', + b'F152676303\x00\x00\x00\x00\x00\x00', + b'F152676304\x00\x00\x00\x00\x00\x00', + b'F152676371\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F3301100\x00\x00\x00\x00', + b'\x018821F3301200\x00\x00\x00\x00', + b'\x018821F3301300\x00\x00\x00\x00', + b'\x018821F3301400\x00\x00\x00\x00', + b'\x018821F6201400\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F12010C0\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', + b'\x028646F12010D0\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', + b'\x028646F1201100\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', + b'\x028646F1201200\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', + b'\x028646F1201300\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + b'\x028646F1201400\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', + b'\x028646F1202000\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', + b'\x028646F1202100\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + b'\x028646F1202200\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', + b'\x028646F1206000\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', + b'\x028646F1601100\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + b'\x028646F1601200\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + b'\x028646F1601300\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + b'\x028646F4203400\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', + b'\x028646F76020C0\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', + b'\x028646F7603100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', + b'\x028646F7603200\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + b'\x028646F7603300\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + b'\x028646F7605100\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', + ], + }, + CAR.TOYOTA_HIGHLANDER: { + (Ecu.engine, 0x700, None): [ + b'\x01896630E09000\x00\x00\x00\x00', + b'\x01896630E43000\x00\x00\x00\x00', + b'\x01896630E43100\x00\x00\x00\x00', + b'\x01896630E43200\x00\x00\x00\x00', + b'\x01896630E44200\x00\x00\x00\x00', + b'\x01896630E44400\x00\x00\x00\x00', + b'\x01896630E45000\x00\x00\x00\x00', + b'\x01896630E45100\x00\x00\x00\x00', + b'\x01896630E45200\x00\x00\x00\x00', + b'\x01896630E46000\x00\x00\x00\x00', + b'\x01896630E46200\x00\x00\x00\x00', + b'\x01896630E74000\x00\x00\x00\x00', + b'\x01896630E75000\x00\x00\x00\x00', + b'\x01896630E76000\x00\x00\x00\x00', + b'\x01896630E77000\x00\x00\x00\x00', + b'\x01896630E83000\x00\x00\x00\x00', + b'\x01896630E84000\x00\x00\x00\x00', + b'\x01896630E85000\x00\x00\x00\x00', + b'\x01896630E86000\x00\x00\x00\x00', + b'\x01896630E88000\x00\x00\x00\x00', + b'\x01896630EA0000\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\x0230E40000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0230E40100\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0230E51000\x00\x00\x00\x00\x00\x00\x00\x0050E17000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0230EA2000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0230EA2100\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B48140\x00\x00\x00\x00\x00\x00', + b'8965B48150\x00\x00\x00\x00\x00\x00', + b'8965B48160\x00\x00\x00\x00\x00\x00', + b'8965B48210\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'F15260E011\x00\x00\x00\x00\x00\x00', + b'F152648541\x00\x00\x00\x00\x00\x00', + b'F152648542\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'881510E01100\x00\x00\x00\x00', + b'881510E01200\x00\x00\x00\x00', + b'881510E02200\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4702100\x00\x00\x00\x00', + b'8821F4702300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F0E01200\x00\x00\x00\x00', + b'8646F0E01300\x00\x00\x00\x00', + ], + }, + CAR.TOYOTA_HIGHLANDER_TSS2: { + (Ecu.eps, 0x7a1, None): [ + b'8965B48241\x00\x00\x00\x00\x00\x00', + b'8965B48310\x00\x00\x00\x00\x00\x00', + b'8965B48320\x00\x00\x00\x00\x00\x00', + b'8965B48400\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'\x01F15260E051\x00\x00\x00\x00\x00\x00', + b'\x01F15260E05300\x00\x00\x00\x00', + b'\x01F15260E061\x00\x00\x00\x00\x00\x00', + b'\x01F15260E110\x00\x00\x00\x00\x00\x00', + b'\x01F15260E170\x00\x00\x00\x00\x00\x00', + b'\x01F15264872300\x00\x00\x00\x00', + b'\x01F15264872400\x00\x00\x00\x00', + b'\x01F15264872500\x00\x00\x00\x00', + b'\x01F15264872600\x00\x00\x00\x00', + b'\x01F15264872700\x00\x00\x00\x00', + b'\x01F15264873500\x00\x00\x00\x00', + b'\x01F152648C6300\x00\x00\x00\x00', + b'\x01F152648J4000\x00\x00\x00\x00', + b'\x01F152648J5000\x00\x00\x00\x00', + b'\x01F152648J6000\x00\x00\x00\x00', + b'\x01F152648J7000\x00\x00\x00\x00', + b'\x01F152648L5000\x00\x00\x00\x00', + ], + (Ecu.engine, 0x700, None): [ + b'\x01896630E62100\x00\x00\x00\x00', + b'\x01896630E62200\x00\x00\x00\x00', + b'\x01896630E64100\x00\x00\x00\x00', + b'\x01896630E64200\x00\x00\x00\x00', + b'\x01896630E64400\x00\x00\x00\x00', + b'\x01896630E67000\x00\x00\x00\x00', + b'\x01896630EA1000\x00\x00\x00\x00', + b'\x01896630EB1000\x00\x00\x00\x00', + b'\x01896630EB1100\x00\x00\x00\x00', + b'\x01896630EB1200\x00\x00\x00\x00', + b'\x01896630EB1300\x00\x00\x00\x00', + b'\x01896630EB2000\x00\x00\x00\x00', + b'\x01896630EB2100\x00\x00\x00\x00', + b'\x01896630EB2200\x00\x00\x00\x00', + b'\x01896630EC4000\x00\x00\x00\x00', + b'\x01896630ED9000\x00\x00\x00\x00', + b'\x01896630ED9100\x00\x00\x00\x00', + b'\x01896630EE1000\x00\x00\x00\x00', + b'\x01896630EE1100\x00\x00\x00\x00', + b'\x01896630EE4000\x00\x00\x00\x00', + b'\x01896630EE4100\x00\x00\x00\x00', + b'\x01896630EE5000\x00\x00\x00\x00', + b'\x01896630EE6000\x00\x00\x00\x00', + b'\x01896630EE7000\x00\x00\x00\x00', + b'\x01896630EF8000\x00\x00\x00\x00', + b'\x01896630EG3000\x00\x00\x00\x00', + b'\x01896630EG5000\x00\x00\x00\x00', + b'\x02896630E66000\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', + b'\x02896630E66100\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', + b'\x02896630EB3000\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', + b'\x02896630EB3100\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F3301400\x00\x00\x00\x00', + b'\x018821F6201200\x00\x00\x00\x00', + b'\x018821F6201300\x00\x00\x00\x00', + b'\x018821F6201400\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F0E02100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', + b'\x028646F4803000\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', + b'\x028646F4803000\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', + b'\x028646F4803200\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', + ], + }, + CAR.LEXUS_IS: { + (Ecu.engine, 0x700, None): [ + b'\x018966353M7000\x00\x00\x00\x00', + b'\x018966353M7100\x00\x00\x00\x00', + b'\x018966353Q2000\x00\x00\x00\x00', + b'\x018966353Q2100\x00\x00\x00\x00', + b'\x018966353Q2300\x00\x00\x00\x00', + b'\x018966353Q4000\x00\x00\x00\x00', + b'\x018966353R1100\x00\x00\x00\x00', + b'\x018966353R7100\x00\x00\x00\x00', + b'\x018966353R8000\x00\x00\x00\x00', + b'\x018966353R8100\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\x0232480000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02353P7000\x00\x00\x00\x00\x00\x00\x00\x00530J5000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02353P9000\x00\x00\x00\x00\x00\x00\x00\x00553C1000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'F152653300\x00\x00\x00\x00\x00\x00', + b'F152653301\x00\x00\x00\x00\x00\x00', + b'F152653310\x00\x00\x00\x00\x00\x00', + b'F152653330\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'881515306200\x00\x00\x00\x00', + b'881515306400\x00\x00\x00\x00', + b'881515306500\x00\x00\x00\x00', + b'881515307400\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B53270\x00\x00\x00\x00\x00\x00', + b'8965B53271\x00\x00\x00\x00\x00\x00', + b'8965B53280\x00\x00\x00\x00\x00\x00', + b'8965B53281\x00\x00\x00\x00\x00\x00', + b'8965B53311\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4702100\x00\x00\x00\x00', + b'8821F4702300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F5301101\x00\x00\x00\x00', + b'8646F5301200\x00\x00\x00\x00', + b'8646F5301300\x00\x00\x00\x00', + b'8646F5301400\x00\x00\x00\x00', + ], + }, + CAR.LEXUS_IS_TSS2: { + (Ecu.engine, 0x700, None): [ + b'\x018966353S1000\x00\x00\x00\x00', + b'\x018966353S2000\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\x02353U0000\x00\x00\x00\x00\x00\x00\x00\x0052422000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'\x01F15265337200\x00\x00\x00\x00', + b'\x01F15265342000\x00\x00\x00\x00', + b'\x01F15265343000\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B53450\x00\x00\x00\x00\x00\x00', + b'8965B53800\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F6201200\x00\x00\x00\x00', + b'\x018821F6201300\x00\x00\x00\x00', + b'\x018821F6201400\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F5303300\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', + b'\x028646F5303400\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', + ], + }, + CAR.TOYOTA_PRIUS: { + (Ecu.engine, 0x700, None): [ + b'\x02896634761000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634761100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634761200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634762000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634762100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634763000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634763100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634765000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634765100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634769000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634769100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634769200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634770000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634770100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634774000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634774100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634774200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634782000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x02896634784000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x028966347A0000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x028966347A5000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x028966347A8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x028966347B0000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x03896634759100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', + b'\x03896634759200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', + b'\x03896634759200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701004\x00\x00\x00\x00', + b'\x03896634759300\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', + b'\x03896634759300\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701004\x00\x00\x00\x00', + b'\x03896634760000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701002\x00\x00\x00\x00', + b'\x03896634760000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', + b'\x03896634760000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701004\x00\x00\x00\x00', + b'\x03896634760100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', + b'\x03896634760200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', + b'\x03896634760200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701004\x00\x00\x00\x00', + b'\x03896634760300\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701004\x00\x00\x00\x00', + b'\x03896634768000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4703001\x00\x00\x00\x00', + b'\x03896634768000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4703002\x00\x00\x00\x00', + b'\x03896634768100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4703002\x00\x00\x00\x00', + b'\x03896634785000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4705001\x00\x00\x00\x00', + b'\x03896634785000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710001\x00\x00\x00\x00', + b'\x03896634786000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4705001\x00\x00\x00\x00', + b'\x03896634786000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710001\x00\x00\x00\x00', + b'\x03896634789000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4703002\x00\x00\x00\x00', + b'\x038966347A3000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', + b'\x038966347A3000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4707001\x00\x00\x00\x00', + b'\x038966347B6000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710001\x00\x00\x00\x00', + b'\x038966347B7000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710001\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B47021\x00\x00\x00\x00\x00\x00', + b'8965B47022\x00\x00\x00\x00\x00\x00', + b'8965B47023\x00\x00\x00\x00\x00\x00', + b'8965B47050\x00\x00\x00\x00\x00\x00', + b'8965B47060\x00\x00\x00\x00\x00\x00', + b'8965B47070\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'F152647290\x00\x00\x00\x00\x00\x00', + b'F152647300\x00\x00\x00\x00\x00\x00', + b'F152647310\x00\x00\x00\x00\x00\x00', + b'F152647414\x00\x00\x00\x00\x00\x00', + b'F152647415\x00\x00\x00\x00\x00\x00', + b'F152647416\x00\x00\x00\x00\x00\x00', + b'F152647417\x00\x00\x00\x00\x00\x00', + b'F152647470\x00\x00\x00\x00\x00\x00', + b'F152647490\x00\x00\x00\x00\x00\x00', + b'F152647682\x00\x00\x00\x00\x00\x00', + b'F152647683\x00\x00\x00\x00\x00\x00', + b'F152647684\x00\x00\x00\x00\x00\x00', + b'F152647862\x00\x00\x00\x00\x00\x00', + b'F152647863\x00\x00\x00\x00\x00\x00', + b'F152647864\x00\x00\x00\x00\x00\x00', + b'F152647865\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'881514702300\x00\x00\x00\x00', + b'881514702400\x00\x00\x00\x00', + b'881514703100\x00\x00\x00\x00', + b'881514704100\x00\x00\x00\x00', + b'881514706000\x00\x00\x00\x00', + b'881514706100\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4702000\x00\x00\x00\x00', + b'8821F4702100\x00\x00\x00\x00', + b'8821F4702300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F4701300\x00\x00\x00\x00', + b'8646F4702001\x00\x00\x00\x00', + b'8646F4702100\x00\x00\x00\x00', + b'8646F4702200\x00\x00\x00\x00', + b'8646F4705000\x00\x00\x00\x00', + b'8646F4705200\x00\x00\x00\x00', + ], + }, + CAR.TOYOTA_PRIUS_V: { + (Ecu.abs, 0x7b0, None): [ + b'F152647280\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\x0234781000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'881514705100\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4702300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F4703300\x00\x00\x00\x00', + ], + }, + CAR.TOYOTA_RAV4: { + (Ecu.engine, 0x7e0, None): [ + b'\x02342Q1000\x00\x00\x00\x00\x00\x00\x00\x0054212000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02342Q1100\x00\x00\x00\x00\x00\x00\x00\x0054212000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02342Q1200\x00\x00\x00\x00\x00\x00\x00\x0054212000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02342Q1300\x00\x00\x00\x00\x00\x00\x00\x0054212000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02342Q2000\x00\x00\x00\x00\x00\x00\x00\x0054213000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02342Q2100\x00\x00\x00\x00\x00\x00\x00\x0054213000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02342Q2200\x00\x00\x00\x00\x00\x00\x00\x0054213000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02342Q4000\x00\x00\x00\x00\x00\x00\x00\x0054215000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B42063\x00\x00\x00\x00\x00\x00', + b'8965B42073\x00\x00\x00\x00\x00\x00', + b'8965B42082\x00\x00\x00\x00\x00\x00', + b'8965B42083\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'F15260R102\x00\x00\x00\x00\x00\x00', + b'F15260R103\x00\x00\x00\x00\x00\x00', + b'F152642492\x00\x00\x00\x00\x00\x00', + b'F152642493\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'881514201200\x00\x00\x00\x00', + b'881514201300\x00\x00\x00\x00', + b'881514201400\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4702000\x00\x00\x00\x00', + b'8821F4702100\x00\x00\x00\x00', + b'8821F4702300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F4201100\x00\x00\x00\x00', + b'8646F4201200\x00\x00\x00\x00', + b'8646F4202001\x00\x00\x00\x00', + b'8646F4202100\x00\x00\x00\x00', + b'8646F4204000\x00\x00\x00\x00', + ], + }, + CAR.TOYOTA_RAV4H: { + (Ecu.engine, 0x7e0, None): [ + b'\x02342N9000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02342N9100\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02342P0000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B42102\x00\x00\x00\x00\x00\x00', + b'8965B42103\x00\x00\x00\x00\x00\x00', + b'8965B42112\x00\x00\x00\x00\x00\x00', + b'8965B42162\x00\x00\x00\x00\x00\x00', + b'8965B42163\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'F152642090\x00\x00\x00\x00\x00\x00', + b'F152642110\x00\x00\x00\x00\x00\x00', + b'F152642120\x00\x00\x00\x00\x00\x00', + b'F152642400\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'881514202200\x00\x00\x00\x00', + b'881514202300\x00\x00\x00\x00', + b'881514202400\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4702000\x00\x00\x00\x00', + b'8821F4702100\x00\x00\x00\x00', + b'8821F4702300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F4201100\x00\x00\x00\x00', + b'8646F4201200\x00\x00\x00\x00', + b'8646F4202001\x00\x00\x00\x00', + b'8646F4202100\x00\x00\x00\x00', + b'8646F4204000\x00\x00\x00\x00', + ], + }, + CAR.TOYOTA_RAV4_TSS2: { + (Ecu.engine, 0x700, None): [ + b'\x01896630R58000\x00\x00\x00\x00', + b'\x01896630R58100\x00\x00\x00\x00', + b'\x018966342E2000\x00\x00\x00\x00', + b'\x018966342M5000\x00\x00\x00\x00', + b'\x018966342M8000\x00\x00\x00\x00', + b'\x018966342S9000\x00\x00\x00\x00', + b'\x018966342T1000\x00\x00\x00\x00', + b'\x018966342T6000\x00\x00\x00\x00', + b'\x018966342T9000\x00\x00\x00\x00', + b'\x018966342U4000\x00\x00\x00\x00', + b'\x018966342U4100\x00\x00\x00\x00', + b'\x018966342U5100\x00\x00\x00\x00', + b'\x018966342V0000\x00\x00\x00\x00', + b'\x018966342V3000\x00\x00\x00\x00', + b'\x018966342V3100\x00\x00\x00\x00', + b'\x018966342V3200\x00\x00\x00\x00', + b'\x018966342W5000\x00\x00\x00\x00', + b'\x018966342W7000\x00\x00\x00\x00', + b'\x018966342W8000\x00\x00\x00\x00', + b'\x018966342X5000\x00\x00\x00\x00', + b'\x018966342X6000\x00\x00\x00\x00', + b'\x01896634A05000\x00\x00\x00\x00', + b'\x01896634A15000\x00\x00\x00\x00', + b'\x01896634A19000\x00\x00\x00\x00', + b'\x01896634A19100\x00\x00\x00\x00', + b'\x01896634A20000\x00\x00\x00\x00', + b'\x01896634A20100\x00\x00\x00\x00', + b'\x01896634A22000\x00\x00\x00\x00', + b'\x01896634A22100\x00\x00\x00\x00', + b'\x01896634A25000\x00\x00\x00\x00', + b'\x01896634A30000\x00\x00\x00\x00', + b'\x01896634A44000\x00\x00\x00\x00', + b'\x01896634A45000\x00\x00\x00\x00', + b'\x01896634A46000\x00\x00\x00\x00', + b'\x028966342M7000\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', + b'\x028966342T0000\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', + b'\x028966342V1000\x00\x00\x00\x00897CF1202001\x00\x00\x00\x00', + b'\x028966342W4001\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00', + b'\x028966342Y8000\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', + b'\x028966342Z8000\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', + b'\x02896634A13000\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02896634A13001\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', + b'\x02896634A13101\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', + b'\x02896634A13201\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', + b'\x02896634A14001\x00\x00\x00\x00897CF0R01000\x00\x00\x00\x00', + b'\x02896634A14001\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00', + b'\x02896634A14001\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', + b'\x02896634A14101\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', + b'\x02896634A18000\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', + b'\x02896634A18100\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', + b'\x02896634A23000\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02896634A23001\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00', + b'\x02896634A23101\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00', + b'\x02896634A43000\x00\x00\x00\x00897CF4201001\x00\x00\x00\x00', + b'\x02896634A47000\x00\x00\x00\x00897CF4201001\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'\x01F15260R210\x00\x00\x00\x00\x00\x00', + b'\x01F15260R220\x00\x00\x00\x00\x00\x00', + b'\x01F15260R290\x00\x00\x00\x00\x00\x00', + b'\x01F15260R292\x00\x00\x00\x00\x00\x00', + b'\x01F15260R300\x00\x00\x00\x00\x00\x00', + b'\x01F15260R302\x00\x00\x00\x00\x00\x00', + b'\x01F152642551\x00\x00\x00\x00\x00\x00', + b'\x01F152642561\x00\x00\x00\x00\x00\x00', + b'\x01F152642601\x00\x00\x00\x00\x00\x00', + b'\x01F152642700\x00\x00\x00\x00\x00\x00', + b'\x01F152642701\x00\x00\x00\x00\x00\x00', + b'\x01F152642710\x00\x00\x00\x00\x00\x00', + b'\x01F152642711\x00\x00\x00\x00\x00\x00', + b'\x01F152642750\x00\x00\x00\x00\x00\x00', + b'\x01F152642751\x00\x00\x00\x00\x00\x00', + b'F152642290\x00\x00\x00\x00\x00\x00', + b'F152642291\x00\x00\x00\x00\x00\x00', + b'F152642322\x00\x00\x00\x00\x00\x00', + b'F152642330\x00\x00\x00\x00\x00\x00', + b'F152642331\x00\x00\x00\x00\x00\x00', + b'F152642520\x00\x00\x00\x00\x00\x00', + b'F152642521\x00\x00\x00\x00\x00\x00', + b'F152642531\x00\x00\x00\x00\x00\x00', + b'F152642532\x00\x00\x00\x00\x00\x00', + b'F152642540\x00\x00\x00\x00\x00\x00', + b'F152642541\x00\x00\x00\x00\x00\x00', + b'F152642542\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'\x028965B0R01200\x00\x00\x00\x008965B0R02200\x00\x00\x00\x00', + b'\x028965B0R01300\x00\x00\x00\x008965B0R02300\x00\x00\x00\x00', + b'\x028965B0R01400\x00\x00\x00\x008965B0R02400\x00\x00\x00\x00', + b'8965B42170\x00\x00\x00\x00\x00\x00', + b'8965B42171\x00\x00\x00\x00\x00\x00', + b'8965B42180\x00\x00\x00\x00\x00\x00', + b'8965B42181\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F3301100\x00\x00\x00\x00', + b'\x018821F3301200\x00\x00\x00\x00', + b'\x018821F3301300\x00\x00\x00\x00', + b'\x018821F3301400\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F4203200\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', + b'\x028646F4203300\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', + b'\x028646F4203400\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', + b'\x028646F4203500\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', + b'\x028646F4203700\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + b'\x028646F4203800\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', + ], + }, + CAR.TOYOTA_RAV4_TSS2_2022: { + (Ecu.abs, 0x7b0, None): [ + b'\x01F15260R350\x00\x00\x00\x00\x00\x00', + b'\x01F15260R361\x00\x00\x00\x00\x00\x00', + b'\x01F15264283100\x00\x00\x00\x00', + b'\x01F15264283200\x00\x00\x00\x00', + b'\x01F15264286100\x00\x00\x00\x00', + b'\x01F15264286200\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'\x028965B0R01500\x00\x00\x00\x008965B0R02500\x00\x00\x00\x00', + b'8965B42172\x00\x00\x00\x00\x00\x00', + b'8965B42182\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x700, None): [ + b'\x01896634A02001\x00\x00\x00\x00', + b'\x01896634A03000\x00\x00\x00\x00', + b'\x01896634A08000\x00\x00\x00\x00', + b'\x01896634A61000\x00\x00\x00\x00', + b'\x01896634A62000\x00\x00\x00\x00', + b'\x01896634A62100\x00\x00\x00\x00', + b'\x01896634A63000\x00\x00\x00\x00', + b'\x01896634A88000\x00\x00\x00\x00', + b'\x01896634A89000\x00\x00\x00\x00', + b'\x01896634A89100\x00\x00\x00\x00', + b'\x01896634AA0000\x00\x00\x00\x00', + b'\x01896634AA0100\x00\x00\x00\x00', + b'\x01896634AA1000\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F0R01100\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F0R02100\x00\x00\x00\x008646G0R01100\x00\x00\x00\x00', + ], + }, + CAR.TOYOTA_RAV4_TSS2_2023: { + (Ecu.abs, 0x7b0, None): [ + b'\x01F15260R450\x00\x00\x00\x00\x00\x00', + b'\x01F15260R50000\x00\x00\x00\x00', + b'\x01F15260R51000\x00\x00\x00\x00', + b'\x01F15264283200\x00\x00\x00\x00', + b'\x01F15264283300\x00\x00\x00\x00', + b'\x01F152642F1000\x00\x00\x00\x00', + b'\x01F152642F8000\x00\x00\x00\x00', + b'\x01F152642F8100\x00\x00\x00\x00', + b'\x01F152642F9000\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'\x028965B0R11000\x00\x00\x00\x008965B0R12000\x00\x00\x00\x00', + b'8965B42371\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x700, None): [ + b'\x01896634A61000\x00\x00\x00\x00', + b'\x01896634A88100\x00\x00\x00\x00', + b'\x01896634A89100\x00\x00\x00\x00', + b'\x01896634AE1001\x00\x00\x00\x00', + b'\x01896634AF0000\x00\x00\x00\x00', + b'\x01896634AJ2000\x00\x00\x00\x00', + b'\x01896634AL5000\x00\x00\x00\x00', + b'\x01896634AL6000\x00\x00\x00\x00', + b'\x01896634AL8000\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F0R03100\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F0R05100\x00\x00\x00\x008646G0R02100\x00\x00\x00\x00', + b'\x028646F0R05200\x00\x00\x00\x008646G0R02200\x00\x00\x00\x00', + b'\x028646F0R11000\x00\x00\x00\x008646G0R04000\x00\x00\x00\x00', + ], + }, + CAR.TOYOTA_SIENNA: { + (Ecu.engine, 0x700, None): [ + b'\x01896630832100\x00\x00\x00\x00', + b'\x01896630832200\x00\x00\x00\x00', + b'\x01896630838000\x00\x00\x00\x00', + b'\x01896630838100\x00\x00\x00\x00', + b'\x01896630842000\x00\x00\x00\x00', + b'\x01896630843000\x00\x00\x00\x00', + b'\x01896630851000\x00\x00\x00\x00', + b'\x01896630851100\x00\x00\x00\x00', + b'\x01896630851200\x00\x00\x00\x00', + b'\x01896630852000\x00\x00\x00\x00', + b'\x01896630852100\x00\x00\x00\x00', + b'\x01896630859000\x00\x00\x00\x00', + b'\x01896630860000\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B45070\x00\x00\x00\x00\x00\x00', + b'8965B45080\x00\x00\x00\x00\x00\x00', + b'8965B45082\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'F152608130\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'881510801100\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4702100\x00\x00\x00\x00', + b'8821F4702200\x00\x00\x00\x00', + b'8821F4702300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F0801100\x00\x00\x00\x00', + ], + }, + CAR.LEXUS_CTH: { + (Ecu.dsu, 0x791, None): [ + b'881517601100\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'F152676144\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\x0237635000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4702300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F7601100\x00\x00\x00\x00', + ], + }, + CAR.LEXUS_ES_TSS2: { + (Ecu.engine, 0x700, None): [ + b'\x018966306U6000\x00\x00\x00\x00', + b'\x018966333T5000\x00\x00\x00\x00', + b'\x018966333T5100\x00\x00\x00\x00', + b'\x018966333X6000\x00\x00\x00\x00', + b'\x01896633T07000\x00\x00\x00\x00', + b'\x01896633T38000\x00\x00\x00\x00', + b'\x01896633T58000\x00\x00\x00\x00', + b'\x028966333S8000\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', + b'\x028966333S8000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', + b'\x028966333T0100\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', + b'\x028966333V4000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', + b'\x028966333W1000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', + b'\x02896633T09000\x00\x00\x00\x00897CF3307001\x00\x00\x00\x00', + b'\x02896633T10000\x00\x00\x00\x00897CF3307001\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'\x01F152606281\x00\x00\x00\x00\x00\x00', + b'\x01F152606340\x00\x00\x00\x00\x00\x00', + b'\x01F152606461\x00\x00\x00\x00\x00\x00', + b'\x01F15260646200\x00\x00\x00\x00', + b'F152633423\x00\x00\x00\x00\x00\x00', + b'F152633680\x00\x00\x00\x00\x00\x00', + b'F152633681\x00\x00\x00\x00\x00\x00', + b'F152633F50\x00\x00\x00\x00\x00\x00', + b'F152633F51\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B33252\x00\x00\x00\x00\x00\x00', + b'8965B33590\x00\x00\x00\x00\x00\x00', + b'8965B33690\x00\x00\x00\x00\x00\x00', + b'8965B33721\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F3301100\x00\x00\x00\x00', + b'\x018821F3301200\x00\x00\x00\x00', + b'\x018821F3301300\x00\x00\x00\x00', + b'\x018821F3301400\x00\x00\x00\x00', + b'\x018821F6201200\x00\x00\x00\x00', + b'\x018821F6201300\x00\x00\x00\x00', + b'\x018821F6201400\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F0610000\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', + b'\x028646F33030D0\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', + b'\x028646F3303100\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', + b'\x028646F3303200\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', + b'\x028646F3304100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', + b'\x028646F3304200\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + b'\x028646F3304300\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', + b'\x028646F3309100\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', + b'\x028646F3309100\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', + ], + }, + CAR.LEXUS_ES: { + (Ecu.engine, 0x7e0, None): [ + b'\x02333M4100\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02333M4200\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02333R0000\x00\x00\x00\x00\x00\x00\x00\x00A0C01000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'F152606202\x00\x00\x00\x00\x00\x00', + b'F152633171\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'881513309400\x00\x00\x00\x00', + b'881513309500\x00\x00\x00\x00', + b'881513310400\x00\x00\x00\x00', + b'881513310500\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B33502\x00\x00\x00\x00\x00\x00', + b'8965B33512\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4701100\x00\x00\x00\x00', + b'8821F4701200\x00\x00\x00\x00', + b'8821F4701300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F3302001\x00\x00\x00\x00', + b'8646F3302100\x00\x00\x00\x00', + b'8646F3302200\x00\x00\x00\x00', + ], + }, + CAR.LEXUS_GS_F: { + (Ecu.engine, 0x7e0, None): [ + b'\x0233075200\x00\x00\x00\x00\x00\x00\x00\x00530B9000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'F152630700\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'881513016200\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B30551\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4702000\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F3002100\x00\x00\x00\x00', + ], + }, + CAR.LEXUS_NX: { + (Ecu.engine, 0x700, None): [ + b'\x01896637850000\x00\x00\x00\x00', + b'\x01896637851000\x00\x00\x00\x00', + b'\x01896637852000\x00\x00\x00\x00', + b'\x01896637854000\x00\x00\x00\x00', + b'\x01896637873000\x00\x00\x00\x00', + b'\x01896637878000\x00\x00\x00\x00', + b'\x01896637878100\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\x0237841000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0237842000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0237880000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0237882000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0237886000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'F152678130\x00\x00\x00\x00\x00\x00', + b'F152678140\x00\x00\x00\x00\x00\x00', + b'F152678160\x00\x00\x00\x00\x00\x00', + b'F152678170\x00\x00\x00\x00\x00\x00', + b'F152678171\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'881517803100\x00\x00\x00\x00', + b'881517803300\x00\x00\x00\x00', + b'881517804100\x00\x00\x00\x00', + b'881517804300\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B78060\x00\x00\x00\x00\x00\x00', + b'8965B78080\x00\x00\x00\x00\x00\x00', + b'8965B78100\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4702100\x00\x00\x00\x00', + b'8821F4702300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F7801100\x00\x00\x00\x00', + b'8646F7801300\x00\x00\x00\x00', + ], + }, + CAR.LEXUS_NX_TSS2: { + (Ecu.engine, 0x700, None): [ + b'\x018966378B2000\x00\x00\x00\x00', + b'\x018966378B2100\x00\x00\x00\x00', + b'\x018966378B3000\x00\x00\x00\x00', + b'\x018966378B3100\x00\x00\x00\x00', + b'\x018966378B4100\x00\x00\x00\x00', + b'\x018966378G2000\x00\x00\x00\x00', + b'\x018966378G3000\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\x0237881000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0237887000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02378A0000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02378F4000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'\x01F152678221\x00\x00\x00\x00\x00\x00', + b'F152678200\x00\x00\x00\x00\x00\x00', + b'F152678210\x00\x00\x00\x00\x00\x00', + b'F152678211\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B78110\x00\x00\x00\x00\x00\x00', + b'8965B78120\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F3301200\x00\x00\x00\x00', + b'\x018821F3301300\x00\x00\x00\x00', + b'\x018821F3301400\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F78030A0\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', + b'\x028646F7803100\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + ], + }, + CAR.LEXUS_LC_TSS2: { + (Ecu.engine, 0x7e0, None): [ + b'\x0131130000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'F152611390\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B11091\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F6201400\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F1104200\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', + b'\x028646F1105200\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', + ], + }, + CAR.LEXUS_RC: { + (Ecu.engine, 0x700, None): [ + b'\x01896632461100\x00\x00\x00\x00', + b'\x01896632478100\x00\x00\x00\x00', + b'\x01896632478200\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\x0232484000\x00\x00\x00\x00\x00\x00\x00\x0052422000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'F152624150\x00\x00\x00\x00\x00\x00', + b'F152624221\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'881512404100\x00\x00\x00\x00', + b'881512407000\x00\x00\x00\x00', + b'881512409100\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B24081\x00\x00\x00\x00\x00\x00', + b'8965B24240\x00\x00\x00\x00\x00\x00', + b'8965B24320\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4702300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F2401100\x00\x00\x00\x00', + b'8646F2401200\x00\x00\x00\x00', + b'8646F2402200\x00\x00\x00\x00', + ], + }, + CAR.LEXUS_RX: { + (Ecu.engine, 0x700, None): [ + b'\x01896630E36100\x00\x00\x00\x00', + b'\x01896630E36200\x00\x00\x00\x00', + b'\x01896630E36300\x00\x00\x00\x00', + b'\x01896630E37100\x00\x00\x00\x00', + b'\x01896630E37200\x00\x00\x00\x00', + b'\x01896630E37300\x00\x00\x00\x00', + b'\x01896630E41000\x00\x00\x00\x00', + b'\x01896630E41100\x00\x00\x00\x00', + b'\x01896630E41200\x00\x00\x00\x00', + b'\x01896630E41500\x00\x00\x00\x00', + b'\x01896630EA3100\x00\x00\x00\x00', + b'\x01896630EA3300\x00\x00\x00\x00', + b'\x01896630EA3400\x00\x00\x00\x00', + b'\x01896630EA4100\x00\x00\x00\x00', + b'\x01896630EA4300\x00\x00\x00\x00', + b'\x01896630EA4400\x00\x00\x00\x00', + b'\x01896630EA6300\x00\x00\x00\x00', + b'\x018966348R1300\x00\x00\x00\x00', + b'\x018966348R8500\x00\x00\x00\x00', + b'\x018966348W1300\x00\x00\x00\x00', + b'\x018966348W2300\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\x02348J7000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02348N0000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02348Q4000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02348Q4100\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02348T1000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02348T1100\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02348T1200\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02348T3000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02348V6000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02348Z3000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'F152648361\x00\x00\x00\x00\x00\x00', + b'F152648472\x00\x00\x00\x00\x00\x00', + b'F152648473\x00\x00\x00\x00\x00\x00', + b'F152648474\x00\x00\x00\x00\x00\x00', + b'F152648492\x00\x00\x00\x00\x00\x00', + b'F152648493\x00\x00\x00\x00\x00\x00', + b'F152648494\x00\x00\x00\x00\x00\x00', + b'F152648501\x00\x00\x00\x00\x00\x00', + b'F152648502\x00\x00\x00\x00\x00\x00', + b'F152648504\x00\x00\x00\x00\x00\x00', + b'F152648630\x00\x00\x00\x00\x00\x00', + b'F152648740\x00\x00\x00\x00\x00\x00', + b'F152648A30\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'881514810300\x00\x00\x00\x00', + b'881514810500\x00\x00\x00\x00', + b'881514810700\x00\x00\x00\x00', + b'881514811300\x00\x00\x00\x00', + b'881514811500\x00\x00\x00\x00', + b'881514811700\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B0E011\x00\x00\x00\x00\x00\x00', + b'8965B0E012\x00\x00\x00\x00\x00\x00', + b'8965B48102\x00\x00\x00\x00\x00\x00', + b'8965B48111\x00\x00\x00\x00\x00\x00', + b'8965B48112\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4701000\x00\x00\x00\x00', + b'8821F4701100\x00\x00\x00\x00', + b'8821F4701200\x00\x00\x00\x00', + b'8821F4701300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F4801100\x00\x00\x00\x00', + b'8646F4801200\x00\x00\x00\x00', + b'8646F4802001\x00\x00\x00\x00', + b'8646F4802100\x00\x00\x00\x00', + b'8646F4802200\x00\x00\x00\x00', + b'8646F4809000\x00\x00\x00\x00', + ], + }, + CAR.LEXUS_RX_TSS2: { + (Ecu.engine, 0x700, None): [ + b'\x01896630EA9000\x00\x00\x00\x00', + b'\x01896630EB0000\x00\x00\x00\x00', + b'\x01896630EC9000\x00\x00\x00\x00', + b'\x01896630EC9100\x00\x00\x00\x00', + b'\x01896630ED0000\x00\x00\x00\x00', + b'\x01896630ED0100\x00\x00\x00\x00', + b'\x01896630ED5000\x00\x00\x00\x00', + b'\x01896630ED6000\x00\x00\x00\x00', + b'\x018966348R9200\x00\x00\x00\x00', + b'\x018966348T8000\x00\x00\x00\x00', + b'\x018966348W5100\x00\x00\x00\x00', + b'\x018966348W9000\x00\x00\x00\x00', + b'\x018966348X0000\x00\x00\x00\x00', + b'\x01896634D11000\x00\x00\x00\x00', + b'\x01896634D12000\x00\x00\x00\x00', + b'\x01896634D12100\x00\x00\x00\x00', + b'\x01896634D43000\x00\x00\x00\x00', + b'\x01896634D44000\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\x02348U2000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02348X4000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02348X5000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02348X8000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x02348Y3000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0234D14000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0234D16000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'\x01F15260E031\x00\x00\x00\x00\x00\x00', + b'\x01F15260E041\x00\x00\x00\x00\x00\x00', + b'\x01F152648781\x00\x00\x00\x00\x00\x00', + b'\x01F152648801\x00\x00\x00\x00\x00\x00', + b'F152648493\x00\x00\x00\x00\x00\x00', + b'F152648811\x00\x00\x00\x00\x00\x00', + b'F152648831\x00\x00\x00\x00\x00\x00', + b'F152648891\x00\x00\x00\x00\x00\x00', + b'F152648C80\x00\x00\x00\x00\x00\x00', + b'F152648D00\x00\x00\x00\x00\x00\x00', + b'F152648D60\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B48261\x00\x00\x00\x00\x00\x00', + b'8965B48271\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F3301100\x00\x00\x00\x00', + b'\x018821F3301300\x00\x00\x00\x00', + b'\x018821F3301400\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F4810100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', + b'\x028646F4810200\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + b'\x028646F4810300\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + b'\x028646F4810400\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + ], + }, + CAR.TOYOTA_PRIUS_TSS2: { + (Ecu.engine, 0x700, None): [ + b'\x028966347B1000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x028966347C4000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x028966347C6000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x028966347C7000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x028966347C8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', + b'\x038966347C0000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710101\x00\x00\x00\x00', + b'\x038966347C1000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710101\x00\x00\x00\x00', + b'\x038966347C5000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4707101\x00\x00\x00\x00', + b'\x038966347C5100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4707101\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'F152647500\x00\x00\x00\x00\x00\x00', + b'F152647510\x00\x00\x00\x00\x00\x00', + b'F152647520\x00\x00\x00\x00\x00\x00', + b'F152647521\x00\x00\x00\x00\x00\x00', + b'F152647531\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B47070\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F3301400\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F4707000\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + b'\x028646F4710000\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', + b'\x028646F4712000\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', + ], + }, + CAR.TOYOTA_MIRAI: { + (Ecu.abs, 0x7d1, None): [ + b'\x01898A36203000\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'\x01F15266203200\x00\x00\x00\x00', + b'\x01F15266203500\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'\x028965B6204100\x00\x00\x00\x008965B6203100\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F6201200\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F6201400\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', + ], + }, + CAR.TOYOTA_ALPHARD_TSS2: { + (Ecu.engine, 0x7e0, None): [ + b'\x0235870000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0235879000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0235883000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B58040\x00\x00\x00\x00\x00\x00', + b'8965B58052\x00\x00\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'F152658320\x00\x00\x00\x00\x00\x00', + b'F152658341\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F3301200\x00\x00\x00\x00', + b'\x018821F3301400\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F58010C0\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', + b'\x028646F5803200\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + b'\x028646FV201000\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + ], + }, +} diff --git a/car/toyota/interface.py b/car/toyota/interface.py new file mode 100644 index 0000000000..3ea05f9fef --- /dev/null +++ b/car/toyota/interface.py @@ -0,0 +1,202 @@ +from cereal import car +from panda import Panda +from panda.python import uds +from openpilot.selfdrive.car.toyota.values import Ecu, CAR, DBC, ToyotaFlags, CarControllerParams, TSS2_CAR, RADAR_ACC_CAR, NO_DSU_CAR, \ + MIN_ACC_SPEED, EPS_SCALE, UNSUPPORTED_DSU_CAR, NO_STOP_TIMER_CAR, ANGLE_CONTROL_CAR +from openpilot.selfdrive.car import create_button_events, get_safety_config +from openpilot.selfdrive.car.disable_ecu import disable_ecu +from openpilot.selfdrive.car.interfaces import CarInterfaceBase + +ButtonType = car.CarState.ButtonEvent.Type +EventName = car.CarEvent.EventName +SteerControlType = car.CarParams.SteerControlType + + +class CarInterface(CarInterfaceBase): + @staticmethod + def get_pid_accel_limits(CP, current_speed, cruise_speed): + return CarControllerParams.ACCEL_MIN, CarControllerParams.ACCEL_MAX + + @staticmethod + def _get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs): + ret.carName = "toyota" + ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.toyota)] + ret.safetyConfigs[0].safetyParam = EPS_SCALE[candidate] + + # BRAKE_MODULE is on a different address for these cars + if DBC[candidate]["pt"] == "toyota_new_mc_pt_generated": + ret.safetyConfigs[0].safetyParam |= Panda.FLAG_TOYOTA_ALT_BRAKE + + if candidate in ANGLE_CONTROL_CAR: + ret.steerControlType = SteerControlType.angle + ret.safetyConfigs[0].safetyParam |= Panda.FLAG_TOYOTA_LTA + + # LTA control can be more delayed and winds up more often + ret.steerActuatorDelay = 0.18 + ret.steerLimitTimer = 0.8 + else: + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) + + ret.steerActuatorDelay = 0.12 # Default delay, Prius has larger delay + ret.steerLimitTimer = 0.4 + + ret.stoppingControl = False # Toyota starts braking more when it thinks you want to stop + + stop_and_go = candidate in TSS2_CAR + + # Detect smartDSU, which intercepts ACC_CMD from the DSU (or radar) allowing openpilot to send it + # 0x2AA is sent by a similar device which intercepts the radar instead of DSU on NO_DSU_CARs + if 0x2FF in fingerprint[0] or (0x2AA in fingerprint[0] and candidate in NO_DSU_CAR): + ret.flags |= ToyotaFlags.SMART_DSU.value + + if 0x2AA in fingerprint[0] and candidate in NO_DSU_CAR: + ret.flags |= ToyotaFlags.RADAR_CAN_FILTER.value + + # In TSS2 cars, the camera does long control + found_ecus = [fw.ecu for fw in car_fw] + ret.enableDsu = len(found_ecus) > 0 and Ecu.dsu not in found_ecus and candidate not in (NO_DSU_CAR | UNSUPPORTED_DSU_CAR) \ + and not (ret.flags & ToyotaFlags.SMART_DSU) + + if candidate == CAR.TOYOTA_PRIUS: + stop_and_go = True + # Only give steer angle deadzone to for bad angle sensor prius + for fw in car_fw: + if fw.ecu == "eps" and not fw.fwVersion == b'8965B47060\x00\x00\x00\x00\x00\x00': + ret.steerActuatorDelay = 0.25 + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning, steering_angle_deadzone_deg=0.2) + + elif candidate in (CAR.LEXUS_RX, CAR.LEXUS_RX_TSS2): + stop_and_go = True + ret.wheelSpeedFactor = 1.035 + + elif candidate in (CAR.TOYOTA_AVALON, CAR.TOYOTA_AVALON_2019, CAR.TOYOTA_AVALON_TSS2): + # starting from 2019, all Avalon variants have stop and go + # https://engage.toyota.com/static/images/toyota_safety_sense/TSS_Applicability_Chart.pdf + stop_and_go = candidate != CAR.TOYOTA_AVALON + + elif candidate in (CAR.TOYOTA_RAV4_TSS2, CAR.TOYOTA_RAV4_TSS2_2022, CAR.TOYOTA_RAV4_TSS2_2023): + ret.lateralTuning.init('pid') + ret.lateralTuning.pid.kiBP = [0.0] + ret.lateralTuning.pid.kpBP = [0.0] + ret.lateralTuning.pid.kpV = [0.6] + ret.lateralTuning.pid.kiV = [0.1] + ret.lateralTuning.pid.kf = 0.00007818594 + + # 2019+ RAV4 TSS2 uses two different steering racks and specific tuning seems to be necessary. + # See https://github.com/commaai/openpilot/pull/21429#issuecomment-873652891 + for fw in car_fw: + if fw.ecu == "eps" and (fw.fwVersion.startswith(b'\x02') or fw.fwVersion in [b'8965B42181\x00\x00\x00\x00\x00\x00']): + ret.lateralTuning.pid.kpV = [0.15] + ret.lateralTuning.pid.kiV = [0.05] + ret.lateralTuning.pid.kf = 0.00004 + break + + elif candidate in (CAR.TOYOTA_CHR, CAR.TOYOTA_CAMRY, CAR.TOYOTA_SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_NX): + # TODO: Some of these platforms are not advertised to have full range ACC, are they similar to SNG_WITHOUT_DSU cars? + stop_and_go = True + + # TODO: these models can do stop and go, but unclear if it requires sDSU or unplugging DSU. + # For now, don't list stop and go functionality in the docs + if ret.flags & ToyotaFlags.SNG_WITHOUT_DSU: + stop_and_go = stop_and_go or bool(ret.flags & ToyotaFlags.SMART_DSU.value) or (ret.enableDsu and not docs) + + ret.centerToFront = ret.wheelbase * 0.44 + + # TODO: Some TSS-P platforms have BSM, but are flipped based on region or driving direction. + # Detect flipped signals and enable for C-HR and others + ret.enableBsm = 0x3F6 in fingerprint[0] and candidate in TSS2_CAR + + # No radar dbc for cars without DSU which are not TSS 2.0 + # TODO: make an adas dbc file for dsu-less models + ret.radarUnavailable = DBC[candidate]['radar'] is None or candidate in (NO_DSU_CAR - TSS2_CAR) + + # if the smartDSU is detected, openpilot can send ACC_CONTROL and the smartDSU will block it from the DSU or radar. + # since we don't yet parse radar on TSS2/TSS-P radar-based ACC cars, gate longitudinal behind experimental toggle + use_sdsu = bool(ret.flags & ToyotaFlags.SMART_DSU) + if candidate in (RADAR_ACC_CAR | NO_DSU_CAR): + ret.experimentalLongitudinalAvailable = use_sdsu or candidate in RADAR_ACC_CAR + + if not use_sdsu: + # Disabling radar is only supported on TSS2 radar-ACC cars + if experimental_long and candidate in RADAR_ACC_CAR: + ret.flags |= ToyotaFlags.DISABLE_RADAR.value + else: + use_sdsu = use_sdsu and experimental_long + + # openpilot longitudinal enabled by default: + # - non-(TSS2 radar ACC cars) w/ smartDSU installed + # - cars w/ DSU disconnected + # - TSS2 cars with camera sending ACC_CONTROL where we can block it + # openpilot longitudinal behind experimental long toggle: + # - TSS2 radar ACC cars w/ smartDSU installed + # - TSS2 radar ACC cars w/o smartDSU installed (disables radar) + # - TSS-P DSU-less cars w/ CAN filter installed (no radar parser yet) + ret.openpilotLongitudinalControl = use_sdsu or ret.enableDsu or candidate in (TSS2_CAR - RADAR_ACC_CAR) or bool(ret.flags & ToyotaFlags.DISABLE_RADAR.value) + ret.autoResumeSng = ret.openpilotLongitudinalControl and candidate in NO_STOP_TIMER_CAR + + if not ret.openpilotLongitudinalControl: + ret.safetyConfigs[0].safetyParam |= Panda.FLAG_TOYOTA_STOCK_LONGITUDINAL + + # min speed to enable ACC. if car can do stop and go, then set enabling speed + # to a negative value, so it won't matter. + ret.minEnableSpeed = -1. if stop_and_go else MIN_ACC_SPEED + + tune = ret.longitudinalTuning + tune.deadzoneBP = [0., 9.] + tune.deadzoneV = [.0, .15] + if candidate in TSS2_CAR: + tune.kpBP = [0., 5., 20.] + tune.kpV = [1.3, 1.0, 0.7] + tune.kiBP = [0., 5., 12., 20., 27.] + tune.kiV = [.35, .23, .20, .17, .1] + if candidate in TSS2_CAR: + ret.vEgoStopping = 0.25 + ret.vEgoStarting = 0.25 + ret.stoppingDecelRate = 0.3 # reach stopping target smoothly + else: + tune.kpBP = [0., 5., 35.] + tune.kiBP = [0., 35.] + tune.kpV = [3.6, 2.4, 1.5] + tune.kiV = [0.54, 0.36] + + return ret + + @staticmethod + def init(CP, logcan, sendcan): + # disable radar if alpha longitudinal toggled on radar-ACC car without CAN filter/smartDSU + if CP.flags & ToyotaFlags.DISABLE_RADAR.value: + communication_control = bytes([uds.SERVICE_TYPE.COMMUNICATION_CONTROL, uds.CONTROL_TYPE.ENABLE_RX_DISABLE_TX, uds.MESSAGE_TYPE.NORMAL]) + disable_ecu(logcan, sendcan, bus=0, addr=0x750, sub_addr=0xf, com_cont_req=communication_control) + + # returns a car.CarState + def _update(self, c): + ret = self.CS.update(self.cp, self.cp_cam) + + if self.CP.carFingerprint in (TSS2_CAR - RADAR_ACC_CAR) or (self.CP.flags & ToyotaFlags.SMART_DSU and not self.CP.flags & ToyotaFlags.RADAR_CAN_FILTER): + ret.buttonEvents = create_button_events(self.CS.distance_button, self.CS.prev_distance_button, {1: ButtonType.gapAdjustCruise}) + + # events + events = self.create_common_events(ret) + + # Lane Tracing Assist control is unavailable (EPS_STATUS->LTA_STATE=0) until + # the more accurate angle sensor signal is initialized + if self.CP.steerControlType == SteerControlType.angle and not self.CS.accurate_steer_angle_seen: + events.add(EventName.vehicleSensorsInvalid) + + if self.CP.openpilotLongitudinalControl: + if ret.cruiseState.standstill and not ret.brakePressed: + events.add(EventName.resumeRequired) + if self.CS.low_speed_lockout: + events.add(EventName.lowSpeedLockout) + if ret.vEgo < self.CP.minEnableSpeed: + events.add(EventName.belowEngageSpeed) + if c.actuators.accel > 0.3: + # some margin on the actuator to not false trigger cancellation while stopping + events.add(EventName.speedTooLow) + if ret.vEgo < 0.001: + # while in standstill, send a user alert + events.add(EventName.manualRestart) + + ret.events = events.to_msg() + + return ret diff --git a/car/toyota/radar_interface.py b/car/toyota/radar_interface.py new file mode 100755 index 0000000000..fae6eecaf6 --- /dev/null +++ b/car/toyota/radar_interface.py @@ -0,0 +1,94 @@ +#!/usr/bin/env python3 +from opendbc.can.parser import CANParser +from cereal import car +from openpilot.selfdrive.car.toyota.values import DBC, TSS2_CAR +from openpilot.selfdrive.car.interfaces import RadarInterfaceBase + + +def _create_radar_can_parser(car_fingerprint): + if car_fingerprint in TSS2_CAR: + RADAR_A_MSGS = list(range(0x180, 0x190)) + RADAR_B_MSGS = list(range(0x190, 0x1a0)) + else: + RADAR_A_MSGS = list(range(0x210, 0x220)) + RADAR_B_MSGS = list(range(0x220, 0x230)) + + msg_a_n = len(RADAR_A_MSGS) + msg_b_n = len(RADAR_B_MSGS) + messages = list(zip(RADAR_A_MSGS + RADAR_B_MSGS, [20] * (msg_a_n + msg_b_n), strict=True)) + + return CANParser(DBC[car_fingerprint]['radar'], messages, 1) + +class RadarInterface(RadarInterfaceBase): + def __init__(self, CP): + super().__init__(CP) + self.track_id = 0 + self.radar_ts = CP.radarTimeStep + + if CP.carFingerprint in TSS2_CAR: + self.RADAR_A_MSGS = list(range(0x180, 0x190)) + self.RADAR_B_MSGS = list(range(0x190, 0x1a0)) + else: + self.RADAR_A_MSGS = list(range(0x210, 0x220)) + self.RADAR_B_MSGS = list(range(0x220, 0x230)) + + self.valid_cnt = {key: 0 for key in self.RADAR_A_MSGS} + + self.rcp = None if CP.radarUnavailable else _create_radar_can_parser(CP.carFingerprint) + self.trigger_msg = self.RADAR_B_MSGS[-1] + self.updated_messages = set() + + def update(self, can_strings): + if self.rcp is None: + return super().update(None) + + vls = self.rcp.update_strings(can_strings) + self.updated_messages.update(vls) + + if self.trigger_msg not in self.updated_messages: + return None + + rr = self._update(self.updated_messages) + self.updated_messages.clear() + + return rr + + def _update(self, updated_messages): + ret = car.RadarData.new_message() + errors = [] + if not self.rcp.can_valid: + errors.append("canError") + ret.errors = errors + + for ii in sorted(updated_messages): + if ii in self.RADAR_A_MSGS: + cpt = self.rcp.vl[ii] + + if cpt['LONG_DIST'] >= 255 or cpt['NEW_TRACK']: + self.valid_cnt[ii] = 0 # reset counter + if cpt['VALID'] and cpt['LONG_DIST'] < 255: + self.valid_cnt[ii] += 1 + else: + self.valid_cnt[ii] = max(self.valid_cnt[ii] - 1, 0) + + score = self.rcp.vl[ii+16]['SCORE'] + # print ii, self.valid_cnt[ii], score, cpt['VALID'], cpt['LONG_DIST'], cpt['LAT_DIST'] + + # radar point only valid if it's a valid measurement and score is above 50 + if cpt['VALID'] or (score > 50 and cpt['LONG_DIST'] < 255 and self.valid_cnt[ii] > 0): + if ii not in self.pts or cpt['NEW_TRACK']: + self.pts[ii] = car.RadarData.RadarPoint.new_message() + self.pts[ii].trackId = self.track_id + self.track_id += 1 + self.pts[ii].dRel = cpt['LONG_DIST'] # from front of car + self.pts[ii].yRel = -cpt['LAT_DIST'] # in car frame's y axis, left is positive + self.pts[ii].vRel = cpt['REL_SPEED'] + self.pts[ii].aRel = float('nan') + self.pts[ii].yvRel = float('nan') + self.pts[ii].measured = bool(cpt['VALID']) + else: + if ii in self.pts: + del self.pts[ii] + + ret.points = list(self.pts.values()) + return ret diff --git a/car/toyota/tests/__init__.py b/car/toyota/tests/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/car/toyota/tests/print_platform_codes.py b/car/toyota/tests/print_platform_codes.py new file mode 100755 index 0000000000..9ec7a14cd3 --- /dev/null +++ b/car/toyota/tests/print_platform_codes.py @@ -0,0 +1,35 @@ +#!/usr/bin/env python3 +from collections import defaultdict +from cereal import car +from openpilot.selfdrive.car.toyota.values import PLATFORM_CODE_ECUS, get_platform_codes +from openpilot.selfdrive.car.toyota.fingerprints import FW_VERSIONS + +Ecu = car.CarParams.Ecu +ECU_NAME = {v: k for k, v in Ecu.schema.enumerants.items()} + +if __name__ == "__main__": + parts_for_ecu: dict = defaultdict(set) + cars_for_code: dict = defaultdict(lambda: defaultdict(set)) + for car_model, ecus in FW_VERSIONS.items(): + print() + print(car_model) + for ecu in sorted(ecus, key=lambda x: int(x[0])): + if ecu[0] not in PLATFORM_CODE_ECUS: + continue + + platform_codes = get_platform_codes(ecus[ecu]) + parts_for_ecu[ecu] |= {code.split(b'-')[0] for code in platform_codes if code.count(b'-') > 1} + for code in platform_codes: + cars_for_code[ecu][b'-'.join(code.split(b'-')[:2])] |= {car_model} + print(f' (Ecu.{ECU_NAME[ecu[0]]}, {hex(ecu[1])}, {ecu[2]}):') + print(f' Codes: {platform_codes}') + + print('\nECU parts:') + for ecu, parts in parts_for_ecu.items(): + print(f' (Ecu.{ECU_NAME[ecu[0]]}, {hex(ecu[1])}, {ecu[2]}): {parts}') + + print('\nCar models vs. platform codes (no major versions):') + for ecu, codes in cars_for_code.items(): + print(f' (Ecu.{ECU_NAME[ecu[0]]}, {hex(ecu[1])}, {ecu[2]}):') + for code, cars in codes.items(): + print(f' {code!r}: {sorted(cars)}') diff --git a/car/toyota/tests/test_toyota.py b/car/toyota/tests/test_toyota.py new file mode 100644 index 0000000000..0217a0fbc1 --- /dev/null +++ b/car/toyota/tests/test_toyota.py @@ -0,0 +1,166 @@ +from hypothesis import given, settings, strategies as st + +from cereal import car +from openpilot.selfdrive.car.fw_versions import build_fw_dict +from openpilot.selfdrive.car.toyota.fingerprints import FW_VERSIONS +from openpilot.selfdrive.car.toyota.values import CAR, DBC, TSS2_CAR, ANGLE_CONTROL_CAR, RADAR_ACC_CAR, \ + FW_QUERY_CONFIG, PLATFORM_CODE_ECUS, FUZZY_EXCLUDED_PLATFORMS, \ + get_platform_codes + +Ecu = car.CarParams.Ecu +ECU_NAME = {v: k for k, v in Ecu.schema.enumerants.items()} + + +def check_fw_version(fw_version: bytes) -> bool: + return b'?' not in fw_version + + +class TestToyotaInterfaces: + def test_car_sets(self): + assert len(ANGLE_CONTROL_CAR - TSS2_CAR) == 0 + assert len(RADAR_ACC_CAR - TSS2_CAR) == 0 + + def test_lta_platforms(self): + # At this time, only RAV4 2023 is expected to use LTA/angle control + assert ANGLE_CONTROL_CAR == {CAR.TOYOTA_RAV4_TSS2_2023} + + def test_tss2_dbc(self): + # We make some assumptions about TSS2 platforms, + # like looking up certain signals only in this DBC + for car_model, dbc in DBC.items(): + if car_model in TSS2_CAR: + assert dbc["pt"] == "toyota_nodsu_pt_generated" + + def test_essential_ecus(self, subtests): + # Asserts standard ECUs exist for each platform + common_ecus = {Ecu.fwdRadar, Ecu.fwdCamera} + for car_model, ecus in FW_VERSIONS.items(): + with subtests.test(car_model=car_model.value): + present_ecus = {ecu[0] for ecu in ecus} + missing_ecus = common_ecus - present_ecus + assert len(missing_ecus) == 0 + + # Some exceptions for other common ECUs + if car_model not in (CAR.TOYOTA_ALPHARD_TSS2,): + assert Ecu.abs in present_ecus + + if car_model not in (CAR.TOYOTA_MIRAI,): + assert Ecu.engine in present_ecus + + if car_model not in (CAR.TOYOTA_PRIUS_V, CAR.LEXUS_CTH): + assert Ecu.eps in present_ecus + + +class TestToyotaFingerprint: + def test_non_essential_ecus(self, subtests): + # Ensures only the cars that have multiple engine ECUs are in the engine non-essential ECU list + for car_model, ecus in FW_VERSIONS.items(): + with subtests.test(car_model=car_model.value): + engine_ecus = {ecu for ecu in ecus if ecu[0] == Ecu.engine} + assert (len(engine_ecus) > 1) == (car_model in FW_QUERY_CONFIG.non_essential_ecus[Ecu.engine]), \ + f"Car model unexpectedly {'not ' if len(engine_ecus) > 1 else ''}in non-essential list" + + def test_valid_fw_versions(self, subtests): + # Asserts all FW versions are valid + for car_model, ecus in FW_VERSIONS.items(): + with subtests.test(car_model=car_model.value): + for fws in ecus.values(): + for fw in fws: + assert check_fw_version(fw), fw + + # Tests for part numbers, platform codes, and sub-versions which Toyota will use to fuzzy + # fingerprint in the absence of full FW matches: + @settings(max_examples=100) + @given(data=st.data()) + def test_platform_codes_fuzzy_fw(self, data): + fw_strategy = st.lists(st.binary()) + fws = data.draw(fw_strategy) + get_platform_codes(fws) + + def test_platform_code_ecus_available(self, subtests): + # Asserts ECU keys essential for fuzzy fingerprinting are available on all platforms + for car_model, ecus in FW_VERSIONS.items(): + with subtests.test(car_model=car_model.value): + for platform_code_ecu in PLATFORM_CODE_ECUS: + if platform_code_ecu == Ecu.eps and car_model in (CAR.TOYOTA_PRIUS_V, CAR.LEXUS_CTH,): + continue + if platform_code_ecu == Ecu.abs and car_model in (CAR.TOYOTA_ALPHARD_TSS2,): + continue + assert platform_code_ecu in [e[0] for e in ecus] + + def test_fw_format(self, subtests): + # Asserts: + # - every supported ECU FW version returns one platform code + # - every supported ECU FW version has a part number + # - expected parsing of ECU sub-versions + + for car_model, ecus in FW_VERSIONS.items(): + with subtests.test(car_model=car_model.value): + for ecu, fws in ecus.items(): + if ecu[0] not in PLATFORM_CODE_ECUS: + continue + + codes = dict() + for fw in fws: + result = get_platform_codes([fw]) + # Check only one platform code and sub-version + assert 1 == len(result), f"Unable to parse FW: {fw}" + assert 1 == len(list(result.values())[0]), f"Unable to parse FW: {fw}" + codes |= result + + # Toyota places the ECU part number in their FW versions, assert all parsable + # Note that there is only one unique part number per ECU across the fleet, so this + # is not important for identification, just a sanity check. + assert all(code.count(b"-") > 1 for code in codes), f"FW does not have part number: {fw} {codes}" + + def test_platform_codes_spot_check(self): + # Asserts basic platform code parsing behavior for a few cases + results = get_platform_codes([ + b"F152607140\x00\x00\x00\x00\x00\x00", + b"F152607171\x00\x00\x00\x00\x00\x00", + b"F152607110\x00\x00\x00\x00\x00\x00", + b"F152607180\x00\x00\x00\x00\x00\x00", + ]) + assert results == {b"F1526-07-1": {b"10", b"40", b"71", b"80"}} + + results = get_platform_codes([ + b"\x028646F4104100\x00\x00\x00\x008646G5301200\x00\x00\x00\x00", + b"\x028646F4104100\x00\x00\x00\x008646G3304000\x00\x00\x00\x00", + ]) + assert results == {b"8646F-41-04": {b"100"}} + + # Short version has no part number + results = get_platform_codes([ + b"\x0235870000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00", + b"\x0235883000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00", + ]) + assert results == {b"58-70": {b"000"}, b"58-83": {b"000"}} + + results = get_platform_codes([ + b"F152607110\x00\x00\x00\x00\x00\x00", + b"F152607140\x00\x00\x00\x00\x00\x00", + b"\x028646F4104100\x00\x00\x00\x008646G5301200\x00\x00\x00\x00", + b"\x0235879000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00", + ]) + assert results == {b"F1526-07-1": {b"10", b"40"}, b"8646F-41-04": {b"100"}, b"58-79": {b"000"}} + + def test_fuzzy_excluded_platforms(self): + # Asserts a list of platforms that will not fuzzy fingerprint with platform codes due to them being shared. + platforms_with_shared_codes = set() + for platform, fw_by_addr in FW_VERSIONS.items(): + car_fw = [] + for ecu, fw_versions in fw_by_addr.items(): + ecu_name, addr, sub_addr = ecu + for fw in fw_versions: + car_fw.append({"ecu": ecu_name, "fwVersion": fw, "address": addr, + "subAddress": 0 if sub_addr is None else sub_addr}) + + CP = car.CarParams.new_message(carFw=car_fw) + matches = FW_QUERY_CONFIG.match_fw_to_car_fuzzy(build_fw_dict(CP.carFw), CP.carVin, FW_VERSIONS) + if len(matches) == 1: + assert list(matches)[0] == platform + else: + # If a platform has multiple matches, add it and its matches + platforms_with_shared_codes |= {str(platform), *matches} + + assert platforms_with_shared_codes == FUZZY_EXCLUDED_PLATFORMS, (len(platforms_with_shared_codes), len(FW_VERSIONS)) diff --git a/car/toyota/toyotacan.py b/car/toyota/toyotacan.py new file mode 100644 index 0000000000..1cc99b41b5 --- /dev/null +++ b/car/toyota/toyotacan.py @@ -0,0 +1,118 @@ +from cereal import car + +SteerControlType = car.CarParams.SteerControlType + + +def create_steer_command(packer, steer, steer_req): + """Creates a CAN message for the Toyota Steer Command.""" + + values = { + "STEER_REQUEST": steer_req, + "STEER_TORQUE_CMD": steer, + "SET_ME_1": 1, + } + return packer.make_can_msg("STEERING_LKA", 0, values) + + +def create_lta_steer_command(packer, steer_control_type, steer_angle, steer_req, frame, torque_wind_down): + """Creates a CAN message for the Toyota LTA Steer Command.""" + + values = { + "COUNTER": frame + 128, + "SETME_X1": 1, # suspected LTA feature availability + # 1 for TSS 2.5 cars, 3 for TSS 2.0. Send based on whether we're using LTA for lateral control + "SETME_X3": 1 if steer_control_type == SteerControlType.angle else 3, + "PERCENTAGE": 100, + "TORQUE_WIND_DOWN": torque_wind_down, + "ANGLE": 0, + "STEER_ANGLE_CMD": steer_angle, + "STEER_REQUEST": steer_req, + "STEER_REQUEST_2": steer_req, + "CLEAR_HOLD_STEERING_ALERT": 0, + } + return packer.make_can_msg("STEERING_LTA", 0, values) + + +def create_accel_command(packer, accel, pcm_cancel, standstill_req, lead, acc_type, fcw_alert, distance): + # TODO: find the exact canceling bit that does not create a chime + values = { + "ACCEL_CMD": accel, + "ACC_TYPE": acc_type, + "DISTANCE": distance, + "MINI_CAR": lead, + "PERMIT_BRAKING": 1, + "RELEASE_STANDSTILL": not standstill_req, + "CANCEL_REQ": pcm_cancel, + "ALLOW_LONG_PRESS": 1, + "ACC_CUT_IN": fcw_alert, # only shown when ACC enabled + } + return packer.make_can_msg("ACC_CONTROL", 0, values) + + +def create_acc_cancel_command(packer): + values = { + "GAS_RELEASED": 0, + "CRUISE_ACTIVE": 0, + "ACC_BRAKING": 0, + "ACCEL_NET": 0, + "CRUISE_STATE": 0, + "CANCEL_REQ": 1, + } + return packer.make_can_msg("PCM_CRUISE", 0, values) + + +def create_fcw_command(packer, fcw): + values = { + "PCS_INDICATOR": 1, # PCS turned off + "FCW": fcw, + "SET_ME_X20": 0x20, + "SET_ME_X10": 0x10, + "PCS_OFF": 1, + "PCS_SENSITIVITY": 0, + } + return packer.make_can_msg("PCS_HUD", 0, values) + + +def create_ui_command(packer, steer, chime, left_line, right_line, left_lane_depart, right_lane_depart, enabled, stock_lkas_hud): + values = { + "TWO_BEEPS": chime, + "LDA_ALERT": steer, + "RIGHT_LINE": 3 if right_lane_depart else 1 if right_line else 2, + "LEFT_LINE": 3 if left_lane_depart else 1 if left_line else 2, + "BARRIERS": 1 if enabled else 0, + + # static signals + "SET_ME_X02": 2, + "SET_ME_X01": 1, + "LKAS_STATUS": 1, + "REPEATED_BEEPS": 0, + "LANE_SWAY_FLD": 7, + "LANE_SWAY_BUZZER": 0, + "LANE_SWAY_WARNING": 0, + "LDA_FRONT_CAMERA_BLOCKED": 0, + "TAKE_CONTROL": 0, + "LANE_SWAY_SENSITIVITY": 2, + "LANE_SWAY_TOGGLE": 1, + "LDA_ON_MESSAGE": 0, + "LDA_MESSAGES": 0, + "LDA_SA_TOGGLE": 1, + "LDA_SENSITIVITY": 2, + "LDA_UNAVAILABLE": 0, + "LDA_MALFUNCTION": 0, + "LDA_UNAVAILABLE_QUIET": 0, + "ADJUSTING_CAMERA": 0, + "LDW_EXIST": 1, + } + + # lane sway functionality + # not all cars have LKAS_HUD — update with camera values if available + if len(stock_lkas_hud): + values.update({s: stock_lkas_hud[s] for s in [ + "LANE_SWAY_FLD", + "LANE_SWAY_BUZZER", + "LANE_SWAY_WARNING", + "LANE_SWAY_SENSITIVITY", + "LANE_SWAY_TOGGLE", + ]}) + + return packer.make_can_msg("LKAS_HUD", 0, values) diff --git a/car/toyota/values.py b/car/toyota/values.py new file mode 100644 index 0000000000..dbab2e9255 --- /dev/null +++ b/car/toyota/values.py @@ -0,0 +1,575 @@ +import re +from collections import defaultdict +from dataclasses import dataclass, field +from enum import Enum, IntFlag + +from cereal import car +from openpilot.common.conversions import Conversions as CV +from openpilot.selfdrive.car import CarSpecs, PlatformConfig, Platforms +from openpilot.selfdrive.car import AngleRateLimit, dbc_dict +from openpilot.selfdrive.car.docs_definitions import CarFootnote, CarDocs, Column, CarParts, CarHarness +from openpilot.selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries + +Ecu = car.CarParams.Ecu +MIN_ACC_SPEED = 19. * CV.MPH_TO_MS +PEDAL_TRANSITION = 10. * CV.MPH_TO_MS + + +class CarControllerParams: + ACCEL_MAX = 1.5 # m/s2, lower than allowed 2.0 m/s2 for tuning reasons + ACCEL_MIN = -3.5 # m/s2 + + STEER_STEP = 1 + STEER_MAX = 1500 + STEER_ERROR_MAX = 350 # max delta between torque cmd and torque motor + + # Lane Tracing Assist (LTA) control limits + # Assuming a steering ratio of 13.7: + # Limit to ~2.0 m/s^3 up (7.5 deg/s), ~3.5 m/s^3 down (13 deg/s) at 75 mph + # Worst case, the low speed limits will allow ~4.0 m/s^3 up (15 deg/s) and ~4.9 m/s^3 down (18 deg/s) at 75 mph, + # however the EPS has its own internal limits at all speeds which are less than that: + # Observed internal torque rate limit on TSS 2.5 Camry and RAV4 is ~1500 units/sec up and down when using LTA + ANGLE_RATE_LIMIT_UP = AngleRateLimit(speed_bp=[5, 25], angle_v=[0.3, 0.15]) + ANGLE_RATE_LIMIT_DOWN = AngleRateLimit(speed_bp=[5, 25], angle_v=[0.36, 0.26]) + + def __init__(self, CP): + if CP.lateralTuning.which == 'torque': + self.STEER_DELTA_UP = 15 # 1.0s time to peak torque + self.STEER_DELTA_DOWN = 25 # always lower than 45 otherwise the Rav4 faults (Prius seems ok with 50) + else: + self.STEER_DELTA_UP = 10 # 1.5s time to peak torque + self.STEER_DELTA_DOWN = 25 # always lower than 45 otherwise the Rav4 faults (Prius seems ok with 50) + + +class ToyotaFlags(IntFlag): + # Detected flags + HYBRID = 1 + SMART_DSU = 2 + DISABLE_RADAR = 4 + RADAR_CAN_FILTER = 1024 + + # Static flags + TSS2 = 8 + NO_DSU = 16 + UNSUPPORTED_DSU = 32 + RADAR_ACC = 64 + # these cars use the Lane Tracing Assist (LTA) message for lateral control + ANGLE_CONTROL = 128 + NO_STOP_TIMER = 256 + # these cars are speculated to allow stop and go when the DSU is unplugged or disabled with sDSU + SNG_WITHOUT_DSU = 512 + + +class Footnote(Enum): + CAMRY = CarFootnote( + "openpilot operates above 28mph for Camry 4CYL L, 4CYL LE and 4CYL SE which don't have Full-Speed Range Dynamic Radar Cruise Control.", + Column.FSR_LONGITUDINAL) + + +@dataclass +class ToyotaCarDocs(CarDocs): + package: str = "All" + car_parts: CarParts = field(default_factory=CarParts.common([CarHarness.toyota_a])) + + +@dataclass +class ToyotaTSS2PlatformConfig(PlatformConfig): + dbc_dict: dict = field(default_factory=lambda: dbc_dict('toyota_nodsu_pt_generated', 'toyota_tss2_adas')) + + def init(self): + self.flags |= ToyotaFlags.TSS2 | ToyotaFlags.NO_STOP_TIMER | ToyotaFlags.NO_DSU + + if self.flags & ToyotaFlags.RADAR_ACC: + self.dbc_dict = dbc_dict('toyota_nodsu_pt_generated', None) + + +class CAR(Platforms): + # Toyota + TOYOTA_ALPHARD_TSS2 = ToyotaTSS2PlatformConfig( + [ + ToyotaCarDocs("Toyota Alphard 2019-20"), + ToyotaCarDocs("Toyota Alphard Hybrid 2021"), + ], + CarSpecs(mass=4305. * CV.LB_TO_KG, wheelbase=3.0, steerRatio=14.2, tireStiffnessFactor=0.444), + ) + TOYOTA_AVALON = PlatformConfig( + [ + ToyotaCarDocs("Toyota Avalon 2016", "Toyota Safety Sense P"), + ToyotaCarDocs("Toyota Avalon 2017-18"), + ], + CarSpecs(mass=3505. * CV.LB_TO_KG, wheelbase=2.82, steerRatio=14.8, tireStiffnessFactor=0.7983), + dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), + ) + TOYOTA_AVALON_2019 = PlatformConfig( + [ + ToyotaCarDocs("Toyota Avalon 2019-21"), + ToyotaCarDocs("Toyota Avalon Hybrid 2019-21"), + ], + TOYOTA_AVALON.specs, + dbc_dict('toyota_nodsu_pt_generated', 'toyota_adas'), + ) + TOYOTA_AVALON_TSS2 = ToyotaTSS2PlatformConfig( # TSS 2.5 + [ + ToyotaCarDocs("Toyota Avalon 2022"), + ToyotaCarDocs("Toyota Avalon Hybrid 2022"), + ], + TOYOTA_AVALON.specs, + ) + TOYOTA_CAMRY = PlatformConfig( + [ + ToyotaCarDocs("Toyota Camry 2018-20", video_link="https://www.youtube.com/watch?v=fkcjviZY9CM", footnotes=[Footnote.CAMRY]), + ToyotaCarDocs("Toyota Camry Hybrid 2018-20", video_link="https://www.youtube.com/watch?v=Q2DYY0AWKgk"), + ], + CarSpecs(mass=3400. * CV.LB_TO_KG, wheelbase=2.82448, steerRatio=13.7, tireStiffnessFactor=0.7933), + dbc_dict('toyota_nodsu_pt_generated', 'toyota_adas'), + flags=ToyotaFlags.NO_DSU, + ) + TOYOTA_CAMRY_TSS2 = ToyotaTSS2PlatformConfig( # TSS 2.5 + [ + ToyotaCarDocs("Toyota Camry 2021-24", footnotes=[Footnote.CAMRY]), + ToyotaCarDocs("Toyota Camry Hybrid 2021-24"), + ], + TOYOTA_CAMRY.specs, + ) + TOYOTA_CHR = PlatformConfig( + [ + ToyotaCarDocs("Toyota C-HR 2017-20"), + ToyotaCarDocs("Toyota C-HR Hybrid 2017-20"), + ], + CarSpecs(mass=3300. * CV.LB_TO_KG, wheelbase=2.63906, steerRatio=13.6, tireStiffnessFactor=0.7933), + dbc_dict('toyota_nodsu_pt_generated', 'toyota_adas'), + flags=ToyotaFlags.NO_DSU, + ) + TOYOTA_CHR_TSS2 = ToyotaTSS2PlatformConfig( + [ + ToyotaCarDocs("Toyota C-HR 2021"), + ToyotaCarDocs("Toyota C-HR Hybrid 2021-22"), + ], + TOYOTA_CHR.specs, + flags=ToyotaFlags.RADAR_ACC, + ) + TOYOTA_COROLLA = PlatformConfig( + [ToyotaCarDocs("Toyota Corolla 2017-19")], + CarSpecs(mass=2860. * CV.LB_TO_KG, wheelbase=2.7, steerRatio=18.27, tireStiffnessFactor=0.444), + dbc_dict('toyota_new_mc_pt_generated', 'toyota_adas'), + ) + # LSS2 Lexus UX Hybrid is same as a TSS2 Corolla Hybrid + TOYOTA_COROLLA_TSS2 = ToyotaTSS2PlatformConfig( + [ + ToyotaCarDocs("Toyota Corolla 2020-22", video_link="https://www.youtube.com/watch?v=_66pXk0CBYA"), + ToyotaCarDocs("Toyota Corolla Cross (Non-US only) 2020-23", min_enable_speed=7.5), + ToyotaCarDocs("Toyota Corolla Hatchback 2019-22", video_link="https://www.youtube.com/watch?v=_66pXk0CBYA"), + # Hybrid platforms + ToyotaCarDocs("Toyota Corolla Hybrid 2020-22"), + ToyotaCarDocs("Toyota Corolla Hybrid (Non-US only) 2020-23", min_enable_speed=7.5), + ToyotaCarDocs("Toyota Corolla Cross Hybrid (Non-US only) 2020-22", min_enable_speed=7.5), + ToyotaCarDocs("Lexus UX Hybrid 2019-23"), + ], + CarSpecs(mass=3060. * CV.LB_TO_KG, wheelbase=2.67, steerRatio=13.9, tireStiffnessFactor=0.444), + ) + TOYOTA_HIGHLANDER = PlatformConfig( + [ + ToyotaCarDocs("Toyota Highlander 2017-19", video_link="https://www.youtube.com/watch?v=0wS0wXSLzoo"), + ToyotaCarDocs("Toyota Highlander Hybrid 2017-19"), + ], + CarSpecs(mass=4516. * CV.LB_TO_KG, wheelbase=2.8194, steerRatio=16.0, tireStiffnessFactor=0.8), + dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), + flags=ToyotaFlags.NO_STOP_TIMER | ToyotaFlags.SNG_WITHOUT_DSU, + ) + TOYOTA_HIGHLANDER_TSS2 = ToyotaTSS2PlatformConfig( + [ + ToyotaCarDocs("Toyota Highlander 2020-23"), + ToyotaCarDocs("Toyota Highlander Hybrid 2020-23"), + ], + TOYOTA_HIGHLANDER.specs, + ) + TOYOTA_PRIUS = PlatformConfig( + [ + ToyotaCarDocs("Toyota Prius 2016", "Toyota Safety Sense P", video_link="https://www.youtube.com/watch?v=8zopPJI8XQ0"), + ToyotaCarDocs("Toyota Prius 2017-20", video_link="https://www.youtube.com/watch?v=8zopPJI8XQ0"), + ToyotaCarDocs("Toyota Prius Prime 2017-20", video_link="https://www.youtube.com/watch?v=8zopPJI8XQ0"), + ], + CarSpecs(mass=3045. * CV.LB_TO_KG, wheelbase=2.7, steerRatio=15.74, tireStiffnessFactor=0.6371), + dbc_dict('toyota_nodsu_pt_generated', 'toyota_adas'), + ) + TOYOTA_PRIUS_V = PlatformConfig( + [ToyotaCarDocs("Toyota Prius v 2017", "Toyota Safety Sense P", min_enable_speed=MIN_ACC_SPEED)], + CarSpecs(mass=3340. * CV.LB_TO_KG, wheelbase=2.78, steerRatio=17.4, tireStiffnessFactor=0.5533), + dbc_dict('toyota_new_mc_pt_generated', 'toyota_adas'), + flags=ToyotaFlags.NO_STOP_TIMER | ToyotaFlags.SNG_WITHOUT_DSU, + ) + TOYOTA_PRIUS_TSS2 = ToyotaTSS2PlatformConfig( + [ + ToyotaCarDocs("Toyota Prius 2021-22", video_link="https://www.youtube.com/watch?v=J58TvCpUd4U"), + ToyotaCarDocs("Toyota Prius Prime 2021-22", video_link="https://www.youtube.com/watch?v=J58TvCpUd4U"), + ], + CarSpecs(mass=3115. * CV.LB_TO_KG, wheelbase=2.70002, steerRatio=13.4, tireStiffnessFactor=0.6371), + ) + TOYOTA_RAV4 = PlatformConfig( + [ + ToyotaCarDocs("Toyota RAV4 2016", "Toyota Safety Sense P"), + ToyotaCarDocs("Toyota RAV4 2017-18") + ], + CarSpecs(mass=3650. * CV.LB_TO_KG, wheelbase=2.65, steerRatio=16.88, tireStiffnessFactor=0.5533), + dbc_dict('toyota_new_mc_pt_generated', 'toyota_adas'), + ) + TOYOTA_RAV4H = PlatformConfig( + [ + ToyotaCarDocs("Toyota RAV4 Hybrid 2016", "Toyota Safety Sense P", video_link="https://youtu.be/LhT5VzJVfNI?t=26"), + ToyotaCarDocs("Toyota RAV4 Hybrid 2017-18", video_link="https://youtu.be/LhT5VzJVfNI?t=26") + ], + TOYOTA_RAV4.specs, + dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), + # Note that the ICE RAV4 does not respect positive acceleration commands under 19 mph + flags=ToyotaFlags.NO_STOP_TIMER | ToyotaFlags.SNG_WITHOUT_DSU, + ) + TOYOTA_RAV4_TSS2 = ToyotaTSS2PlatformConfig( + [ + ToyotaCarDocs("Toyota RAV4 2019-21", video_link="https://www.youtube.com/watch?v=wJxjDd42gGA"), + ToyotaCarDocs("Toyota RAV4 Hybrid 2019-21"), + ], + CarSpecs(mass=3585. * CV.LB_TO_KG, wheelbase=2.68986, steerRatio=14.3, tireStiffnessFactor=0.7933), + ) + TOYOTA_RAV4_TSS2_2022 = ToyotaTSS2PlatformConfig( + [ + ToyotaCarDocs("Toyota RAV4 2022"), + ToyotaCarDocs("Toyota RAV4 Hybrid 2022", video_link="https://youtu.be/U0nH9cnrFB0"), + ], + TOYOTA_RAV4_TSS2.specs, + flags=ToyotaFlags.RADAR_ACC, + ) + TOYOTA_RAV4_TSS2_2023 = ToyotaTSS2PlatformConfig( + [ + ToyotaCarDocs("Toyota RAV4 2023-24"), + ToyotaCarDocs("Toyota RAV4 Hybrid 2023-24"), + ], + TOYOTA_RAV4_TSS2.specs, + flags=ToyotaFlags.RADAR_ACC | ToyotaFlags.ANGLE_CONTROL, + ) + TOYOTA_MIRAI = ToyotaTSS2PlatformConfig( # TSS 2.5 + [ToyotaCarDocs("Toyota Mirai 2021")], + CarSpecs(mass=4300. * CV.LB_TO_KG, wheelbase=2.91, steerRatio=14.8, tireStiffnessFactor=0.8), + ) + TOYOTA_SIENNA = PlatformConfig( + [ToyotaCarDocs("Toyota Sienna 2018-20", video_link="https://www.youtube.com/watch?v=q1UPOo4Sh68", min_enable_speed=MIN_ACC_SPEED)], + CarSpecs(mass=4590. * CV.LB_TO_KG, wheelbase=3.03, steerRatio=15.5, tireStiffnessFactor=0.444), + dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), + flags=ToyotaFlags.NO_STOP_TIMER, + ) + + # Lexus + LEXUS_CTH = PlatformConfig( + [ToyotaCarDocs("Lexus CT Hybrid 2017-18", "Lexus Safety System+")], + CarSpecs(mass=3108. * CV.LB_TO_KG, wheelbase=2.6, steerRatio=18.6, tireStiffnessFactor=0.517), + dbc_dict('toyota_new_mc_pt_generated', 'toyota_adas'), + ) + LEXUS_ES = PlatformConfig( + [ + ToyotaCarDocs("Lexus ES 2017-18"), + ToyotaCarDocs("Lexus ES Hybrid 2017-18"), + ], + CarSpecs(mass=3677. * CV.LB_TO_KG, wheelbase=2.8702, steerRatio=16.0, tireStiffnessFactor=0.444), + dbc_dict('toyota_new_mc_pt_generated', 'toyota_adas'), + ) + LEXUS_ES_TSS2 = ToyotaTSS2PlatformConfig( + [ + ToyotaCarDocs("Lexus ES 2019-24"), + ToyotaCarDocs("Lexus ES Hybrid 2019-24", video_link="https://youtu.be/BZ29osRVJeg?t=12"), + ], + LEXUS_ES.specs, + ) + LEXUS_IS = PlatformConfig( + [ToyotaCarDocs("Lexus IS 2017-19")], + CarSpecs(mass=3736.8 * CV.LB_TO_KG, wheelbase=2.79908, steerRatio=13.3, tireStiffnessFactor=0.444), + dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), + flags=ToyotaFlags.UNSUPPORTED_DSU, + ) + LEXUS_IS_TSS2 = ToyotaTSS2PlatformConfig( + [ToyotaCarDocs("Lexus IS 2022-23")], + LEXUS_IS.specs, + ) + LEXUS_NX = PlatformConfig( + [ + ToyotaCarDocs("Lexus NX 2018-19"), + ToyotaCarDocs("Lexus NX Hybrid 2018-19"), + ], + CarSpecs(mass=4070. * CV.LB_TO_KG, wheelbase=2.66, steerRatio=14.7, tireStiffnessFactor=0.444), + dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), + ) + LEXUS_NX_TSS2 = ToyotaTSS2PlatformConfig( + [ + ToyotaCarDocs("Lexus NX 2020-21"), + ToyotaCarDocs("Lexus NX Hybrid 2020-21"), + ], + LEXUS_NX.specs, + ) + LEXUS_LC_TSS2 = ToyotaTSS2PlatformConfig( + [ToyotaCarDocs("Lexus LC 2024")], + CarSpecs(mass=4500. * CV.LB_TO_KG, wheelbase=2.87, steerRatio=13.0, tireStiffnessFactor=0.444), + ) + LEXUS_RC = PlatformConfig( + [ToyotaCarDocs("Lexus RC 2018-20")], + LEXUS_IS.specs, + dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), + flags=ToyotaFlags.UNSUPPORTED_DSU, + ) + LEXUS_RX = PlatformConfig( + [ + ToyotaCarDocs("Lexus RX 2016", "Lexus Safety System+"), + ToyotaCarDocs("Lexus RX 2017-19"), + # Hybrid platforms + ToyotaCarDocs("Lexus RX Hybrid 2016", "Lexus Safety System+"), + ToyotaCarDocs("Lexus RX Hybrid 2017-19"), + ], + CarSpecs(mass=4481. * CV.LB_TO_KG, wheelbase=2.79, steerRatio=16., tireStiffnessFactor=0.5533), + dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), + ) + LEXUS_RX_TSS2 = ToyotaTSS2PlatformConfig( + [ + ToyotaCarDocs("Lexus RX 2020-22"), + ToyotaCarDocs("Lexus RX Hybrid 2020-22"), + ], + LEXUS_RX.specs, + ) + LEXUS_GS_F = PlatformConfig( + [ToyotaCarDocs("Lexus GS F 2016")], + CarSpecs(mass=4034. * CV.LB_TO_KG, wheelbase=2.84988, steerRatio=13.3, tireStiffnessFactor=0.444), + dbc_dict('toyota_new_mc_pt_generated', 'toyota_adas'), + flags=ToyotaFlags.UNSUPPORTED_DSU, + ) + + +# (addr, cars, bus, 1/freq*100, vl) +STATIC_DSU_MSGS = [ + (0x128, (CAR.TOYOTA_PRIUS, CAR.TOYOTA_RAV4H, CAR.LEXUS_RX, CAR.LEXUS_NX, CAR.TOYOTA_RAV4, CAR.TOYOTA_COROLLA, CAR.TOYOTA_AVALON), \ + 1, 3, b'\xf4\x01\x90\x83\x00\x37'), + (0x128, (CAR.TOYOTA_HIGHLANDER, CAR.TOYOTA_SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES), 1, 3, b'\x03\x00\x20\x00\x00\x52'), + (0x141, (CAR.TOYOTA_PRIUS, CAR.TOYOTA_RAV4H, CAR.LEXUS_RX, CAR.LEXUS_NX, CAR.TOYOTA_RAV4, CAR.TOYOTA_COROLLA, CAR.TOYOTA_HIGHLANDER, CAR.TOYOTA_AVALON, + CAR.TOYOTA_SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES, CAR.TOYOTA_PRIUS_V), 1, 2, b'\x00\x00\x00\x46'), + (0x160, (CAR.TOYOTA_PRIUS, CAR.TOYOTA_RAV4H, CAR.LEXUS_RX, CAR.LEXUS_NX, CAR.TOYOTA_RAV4, CAR.TOYOTA_COROLLA, CAR.TOYOTA_HIGHLANDER, CAR.TOYOTA_AVALON, + CAR.TOYOTA_SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES, CAR.TOYOTA_PRIUS_V), 1, 7, b'\x00\x00\x08\x12\x01\x31\x9c\x51'), + (0x161, (CAR.TOYOTA_PRIUS, CAR.TOYOTA_RAV4H, CAR.LEXUS_RX, CAR.LEXUS_NX, CAR.TOYOTA_RAV4, CAR.TOYOTA_COROLLA, CAR.TOYOTA_AVALON, CAR.TOYOTA_PRIUS_V), + 1, 7, b'\x00\x1e\x00\x00\x00\x80\x07'), + (0X161, (CAR.TOYOTA_HIGHLANDER, CAR.TOYOTA_SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES), 1, 7, b'\x00\x1e\x00\xd4\x00\x00\x5b'), + (0x283, (CAR.TOYOTA_PRIUS, CAR.TOYOTA_RAV4H, CAR.LEXUS_RX, CAR.LEXUS_NX, CAR.TOYOTA_RAV4, CAR.TOYOTA_COROLLA, CAR.TOYOTA_HIGHLANDER, CAR.TOYOTA_AVALON, + CAR.TOYOTA_SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES, CAR.TOYOTA_PRIUS_V), 0, 3, b'\x00\x00\x00\x00\x00\x00\x8c'), + (0x2E6, (CAR.TOYOTA_PRIUS, CAR.TOYOTA_RAV4H, CAR.LEXUS_RX), 0, 3, b'\xff\xf8\x00\x08\x7f\xe0\x00\x4e'), + (0x2E7, (CAR.TOYOTA_PRIUS, CAR.TOYOTA_RAV4H, CAR.LEXUS_RX), 0, 3, b'\xa8\x9c\x31\x9c\x00\x00\x00\x02'), + (0x33E, (CAR.TOYOTA_PRIUS, CAR.TOYOTA_RAV4H, CAR.LEXUS_RX), 0, 20, b'\x0f\xff\x26\x40\x00\x1f\x00'), + (0x344, (CAR.TOYOTA_PRIUS, CAR.TOYOTA_RAV4H, CAR.LEXUS_RX, CAR.LEXUS_NX, CAR.TOYOTA_RAV4, CAR.TOYOTA_COROLLA, CAR.TOYOTA_HIGHLANDER, CAR.TOYOTA_AVALON, + CAR.TOYOTA_SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES, CAR.TOYOTA_PRIUS_V), 0, 5, b'\x00\x00\x01\x00\x00\x00\x00\x50'), + (0x365, (CAR.TOYOTA_PRIUS, CAR.LEXUS_NX, CAR.TOYOTA_HIGHLANDER), 0, 20, b'\x00\x00\x00\x80\x03\x00\x08'), + (0x365, (CAR.TOYOTA_RAV4, CAR.TOYOTA_RAV4H, CAR.TOYOTA_COROLLA, CAR.TOYOTA_AVALON, CAR.TOYOTA_SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES, CAR.LEXUS_RX, + CAR.TOYOTA_PRIUS_V), 0, 20, b'\x00\x00\x00\x80\xfc\x00\x08'), + (0x366, (CAR.TOYOTA_PRIUS, CAR.TOYOTA_RAV4H, CAR.LEXUS_RX, CAR.LEXUS_NX, CAR.TOYOTA_HIGHLANDER), 0, 20, b'\x00\x00\x4d\x82\x40\x02\x00'), + (0x366, (CAR.TOYOTA_RAV4, CAR.TOYOTA_COROLLA, CAR.TOYOTA_AVALON, CAR.TOYOTA_SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES, CAR.TOYOTA_PRIUS_V), + 0, 20, b'\x00\x72\x07\xff\x09\xfe\x00'), + (0x470, (CAR.TOYOTA_PRIUS, CAR.LEXUS_RX), 1, 100, b'\x00\x00\x02\x7a'), + (0x470, (CAR.TOYOTA_HIGHLANDER, CAR.TOYOTA_RAV4H, CAR.TOYOTA_SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES, CAR.TOYOTA_PRIUS_V), 1, 100, b'\x00\x00\x01\x79'), + (0x4CB, (CAR.TOYOTA_PRIUS, CAR.TOYOTA_RAV4H, CAR.LEXUS_RX, CAR.LEXUS_NX, CAR.TOYOTA_RAV4, CAR.TOYOTA_COROLLA, CAR.TOYOTA_HIGHLANDER, CAR.TOYOTA_AVALON, + CAR.TOYOTA_SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES, CAR.TOYOTA_PRIUS_V), 0, 100, b'\x0c\x00\x00\x00\x00\x00\x00\x00'), +] + + +def get_platform_codes(fw_versions: list[bytes]) -> dict[bytes, set[bytes]]: + # Returns sub versions in a dict so comparisons can be made within part-platform-major_version combos + codes = defaultdict(set) # Optional[part]-platform-major_version: set of sub_version + for fw in fw_versions: + # FW versions returned from UDS queries can return multiple fields/chunks of data (different ECU calibrations, different data?) + # and are prefixed with a byte that describes how many chunks of data there are. + # But FW returned from KWP requires querying of each sub-data id and does not have a length prefix. + + length_code = 1 + length_code_match = FW_LEN_CODE.search(fw) + if length_code_match is not None: + length_code = length_code_match.group()[0] + fw = fw[1:] + + # fw length should be multiple of 16 bytes (per chunk, even if no length code), skip parsing if unexpected length + if length_code * FW_CHUNK_LEN != len(fw): + continue + + chunks = [fw[FW_CHUNK_LEN * i:FW_CHUNK_LEN * i + FW_CHUNK_LEN].strip(b'\x00 ') for i in range(length_code)] + + # only first is considered for now since second is commonly shared (TODO: understand that) + first_chunk = chunks[0] + if len(first_chunk) == 8: + # TODO: no part number, but some short chunks have it in subsequent chunks + fw_match = SHORT_FW_PATTERN.search(first_chunk) + if fw_match is not None: + platform, major_version, sub_version = fw_match.groups() + codes[b'-'.join((platform, major_version))].add(sub_version) + + elif len(first_chunk) == 10: + fw_match = MEDIUM_FW_PATTERN.search(first_chunk) + if fw_match is not None: + part, platform, major_version, sub_version = fw_match.groups() + codes[b'-'.join((part, platform, major_version))].add(sub_version) + + elif len(first_chunk) == 12: + fw_match = LONG_FW_PATTERN.search(first_chunk) + if fw_match is not None: + part, platform, major_version, sub_version = fw_match.groups() + codes[b'-'.join((part, platform, major_version))].add(sub_version) + + return dict(codes) + + +def match_fw_to_car_fuzzy(live_fw_versions, vin, offline_fw_versions) -> set[str]: + candidates = set() + + for candidate, fws in offline_fw_versions.items(): + # Keep track of ECUs which pass all checks (platform codes, within sub-version range) + valid_found_ecus = set() + valid_expected_ecus = {ecu[1:] for ecu in fws if ecu[0] in PLATFORM_CODE_ECUS} + for ecu, expected_versions in fws.items(): + addr = ecu[1:] + # Only check ECUs expected to have platform codes + if ecu[0] not in PLATFORM_CODE_ECUS: + continue + + # Expected platform codes & versions + expected_platform_codes = get_platform_codes(expected_versions) + + # Found platform codes & versions + found_platform_codes = get_platform_codes(live_fw_versions.get(addr, set())) + + # Check part number + platform code + major version matches for any found versions + # Platform codes and major versions change for different physical parts, generation, API, etc. + # Sub-versions are incremented for minor recalls, do not need to be checked. + if not any(found_platform_code in expected_platform_codes for found_platform_code in found_platform_codes): + break + + valid_found_ecus.add(addr) + + # If all live ECUs pass all checks for candidate, add it as a match + if valid_expected_ecus.issubset(valid_found_ecus): + candidates.add(candidate) + + return {str(c) for c in (candidates - FUZZY_EXCLUDED_PLATFORMS)} + + +# Regex patterns for parsing more general platform-specific identifiers from FW versions. +# - Part number: Toyota part number (usually last character needs to be ignored to find a match). +# Each ECU address has just one part number. +# - Platform: usually multiple codes per an openpilot platform, however this is the least variable and +# is usually shared across ECUs and model years signifying this describes something about the specific platform. +# This describes more generational changes (TSS-P vs TSS2), or manufacture region. +# - Major version: second least variable part of the FW version. Seen splitting cars by model year/API such as +# RAV4 2022/2023 and Avalon. Used to differentiate cars where API has changed slightly, but is not a generational change. +# It is important to note that these aren't always consecutive, for example: +# Avalon 2016-18's fwdCamera has these major versions: 01, 03 while 2019 has: 02 +# - Sub version: exclusive to major version, but shared with other cars. Should only be used for further filtering. +# Seen bumped in TSB FW updates, and describes other minor differences. +SHORT_FW_PATTERN = re.compile(b'[A-Z0-9](?P[A-Z0-9]{2})(?P[A-Z0-9]{2})(?P[A-Z0-9]{3})') +MEDIUM_FW_PATTERN = re.compile(b'(?P[A-Z0-9]{5})(?P[A-Z0-9]{2})(?P[A-Z0-9]{1})(?P[A-Z0-9]{2})') +LONG_FW_PATTERN = re.compile(b'(?P[A-Z0-9]{5})(?P[A-Z0-9]{2})(?P[A-Z0-9]{2})(?P[A-Z0-9]{3})') +FW_LEN_CODE = re.compile(b'^[\x01-\x03]') # highest seen is 3 chunks, 16 bytes each +FW_CHUNK_LEN = 16 + +# List of ECUs that are most unique across openpilot platforms +# - fwdCamera: describes actual features related to ADAS. For example, on the Avalon it describes +# when TSS-P became standard, whether the car supports stop and go, and whether it's TSS2. +# On the RAV4, it describes the move to the radar doing ACC, and the use of LTA for lane keeping. +# Note that the platform codes & major versions do not describe features in plain text, only with +# matching against other seen FW versions in the database they can describe features. +# - fwdRadar: sanity check against fwdCamera, commonly shares a platform code. +# For example the RAV4 2022's new radar architecture is shown for both with platform code. +# - abs: differentiates hybrid/ICE on most cars (Corolla TSS2 is an exception, not used due to hybrid platform combination) +# - eps: describes lateral API changes for the EPS, such as using LTA for lane keeping and rejecting LKA messages +PLATFORM_CODE_ECUS = (Ecu.fwdCamera, Ecu.fwdRadar, Ecu.eps) + +# These platforms have at least one platform code for all ECUs shared with another platform. +FUZZY_EXCLUDED_PLATFORMS: set[CAR] = set() + +# Some ECUs that use KWP2000 have their FW versions on non-standard data identifiers. +# Toyota diagnostic software first gets the supported data ids, then queries them one by one. +# For example, sends: 0x1a8800, receives: 0x1a8800010203, queries: 0x1a8801, 0x1a8802, 0x1a8803 +TOYOTA_VERSION_REQUEST_KWP = b'\x1a\x88\x01' +TOYOTA_VERSION_RESPONSE_KWP = b'\x5a\x88\x01' + +FW_QUERY_CONFIG = FwQueryConfig( + # TODO: look at data to whitelist new ECUs effectively + requests=[ + Request( + [StdQueries.SHORT_TESTER_PRESENT_REQUEST, TOYOTA_VERSION_REQUEST_KWP], + [StdQueries.SHORT_TESTER_PRESENT_RESPONSE, TOYOTA_VERSION_RESPONSE_KWP], + whitelist_ecus=[Ecu.fwdCamera, Ecu.fwdRadar, Ecu.dsu, Ecu.abs, Ecu.eps, Ecu.srs, Ecu.transmission, Ecu.hvac], + bus=0, + ), + Request( + [StdQueries.SHORT_TESTER_PRESENT_REQUEST, StdQueries.OBD_VERSION_REQUEST], + [StdQueries.SHORT_TESTER_PRESENT_RESPONSE, StdQueries.OBD_VERSION_RESPONSE], + whitelist_ecus=[Ecu.engine, Ecu.hybrid, Ecu.srs, Ecu.transmission, Ecu.hvac], + bus=0, + ), + Request( + [StdQueries.TESTER_PRESENT_REQUEST, StdQueries.DEFAULT_DIAGNOSTIC_REQUEST, StdQueries.EXTENDED_DIAGNOSTIC_REQUEST, StdQueries.UDS_VERSION_REQUEST], + [StdQueries.TESTER_PRESENT_RESPONSE, StdQueries.DEFAULT_DIAGNOSTIC_RESPONSE, StdQueries.EXTENDED_DIAGNOSTIC_RESPONSE, StdQueries.UDS_VERSION_RESPONSE], + whitelist_ecus=[Ecu.engine, Ecu.fwdRadar, Ecu.fwdCamera, Ecu.abs, Ecu.eps, + Ecu.hybrid, Ecu.srs, Ecu.transmission, Ecu.hvac], + bus=0, + ), + ], + non_essential_ecus={ + # FIXME: On some models, abs can sometimes be missing + Ecu.abs: [CAR.TOYOTA_RAV4, CAR.TOYOTA_COROLLA, CAR.TOYOTA_HIGHLANDER, CAR.TOYOTA_SIENNA, CAR.LEXUS_IS, CAR.TOYOTA_ALPHARD_TSS2], + # On some models, the engine can show on two different addresses + Ecu.engine: [CAR.TOYOTA_HIGHLANDER, CAR.TOYOTA_CAMRY, CAR.TOYOTA_COROLLA_TSS2, CAR.TOYOTA_CHR, CAR.TOYOTA_CHR_TSS2, CAR.LEXUS_IS, + CAR.LEXUS_IS_TSS2, CAR.LEXUS_RC, CAR.LEXUS_NX, CAR.LEXUS_NX_TSS2, CAR.LEXUS_RX, CAR.LEXUS_RX_TSS2], + }, + extra_ecus=[ + # All known ECUs on a late-model Toyota vehicle not queried here: + # Responds to UDS: + # - Combination Meter (0x7c0) + # - HV Battery (0x713, 0x747) + # - Motor Generator (0x716, 0x724) + # - 2nd ABS "Brake/EPB" (0x730) + # - Electronic Parking Brake ((0x750, 0x2c)) + # - Telematics ((0x750, 0xc7)) + # Responds to KWP (0x1a8801): + # - Steering Angle Sensor (0x7b3) + # - EPS/EMPS (0x7a0, 0x7a1) + # - 2nd SRS Airbag (0x784) + # - Central Gateway ((0x750, 0x5f)) + # - Telematics ((0x750, 0xc7)) + # Responds to KWP (0x1a8881): + # - Body Control Module ((0x750, 0x40)) + # - Telematics ((0x750, 0xc7)) + + # Hybrid control computer can be on 0x7e2 (KWP) or 0x7d2 (UDS) depending on platform + (Ecu.hybrid, 0x7e2, None), # Hybrid Control Assembly & Computer + (Ecu.srs, 0x780, None), # SRS Airbag + # Transmission is combined with engine on some platforms, such as TSS-P RAV4 + (Ecu.transmission, 0x701, None), + # A few platforms have a tester present response on this address, add to log + (Ecu.transmission, 0x7e1, None), + (Ecu.hvac, 0x7c4, None), + ], + match_fw_to_car_fuzzy=match_fw_to_car_fuzzy, +) + + +STEER_THRESHOLD = 100 + +# These cars have non-standard EPS torque scale factors. All others are 73 +EPS_SCALE = defaultdict(lambda: 73, + {CAR.TOYOTA_PRIUS: 66, CAR.TOYOTA_COROLLA: 88, CAR.LEXUS_IS: 77, CAR.LEXUS_RC: 77, CAR.LEXUS_CTH: 100, CAR.TOYOTA_PRIUS_V: 100}) + +# Toyota/Lexus Safety Sense 2.0 and 2.5 +TSS2_CAR = CAR.with_flags(ToyotaFlags.TSS2) + +NO_DSU_CAR = CAR.with_flags(ToyotaFlags.NO_DSU) + +# the DSU uses the AEB message for longitudinal on these cars +UNSUPPORTED_DSU_CAR = CAR.with_flags(ToyotaFlags.UNSUPPORTED_DSU) + +# these cars have a radar which sends ACC messages instead of the camera +RADAR_ACC_CAR = CAR.with_flags(ToyotaFlags.RADAR_ACC) + +ANGLE_CONTROL_CAR = CAR.with_flags(ToyotaFlags.ANGLE_CONTROL) + +# no resume button press required +NO_STOP_TIMER_CAR = CAR.with_flags(ToyotaFlags.NO_STOP_TIMER) + +DBC = CAR.create_dbc_map() diff --git a/car/volkswagen/__init__.py b/car/volkswagen/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/car/volkswagen/carcontroller.py b/car/volkswagen/carcontroller.py new file mode 100644 index 0000000000..a4e0c8946a --- /dev/null +++ b/car/volkswagen/carcontroller.py @@ -0,0 +1,121 @@ +from cereal import car +from opendbc.can.packer import CANPacker +from openpilot.common.numpy_fast import clip +from openpilot.common.conversions import Conversions as CV +from openpilot.common.realtime import DT_CTRL +from openpilot.selfdrive.car import apply_driver_steer_torque_limits +from openpilot.selfdrive.car.interfaces import CarControllerBase +from openpilot.selfdrive.car.volkswagen import mqbcan, pqcan +from openpilot.selfdrive.car.volkswagen.values import CANBUS, CarControllerParams, VolkswagenFlags + +VisualAlert = car.CarControl.HUDControl.VisualAlert +LongCtrlState = car.CarControl.Actuators.LongControlState + + +class CarController(CarControllerBase): + def __init__(self, dbc_name, CP, VM): + self.CP = CP + self.CCP = CarControllerParams(CP) + self.CCS = pqcan if CP.flags & VolkswagenFlags.PQ else mqbcan + self.packer_pt = CANPacker(dbc_name) + self.ext_bus = CANBUS.pt if CP.networkLocation == car.CarParams.NetworkLocation.fwdCamera else CANBUS.cam + + self.apply_steer_last = 0 + self.gra_acc_counter_last = None + self.frame = 0 + self.eps_timer_soft_disable_alert = False + self.hca_frame_timer_running = 0 + self.hca_frame_same_torque = 0 + + def update(self, CC, CS, now_nanos): + actuators = CC.actuators + hud_control = CC.hudControl + can_sends = [] + + # **** Steering Controls ************************************************ # + + if self.frame % self.CCP.STEER_STEP == 0: + # Logic to avoid HCA state 4 "refused": + # * Don't steer unless HCA is in state 3 "ready" or 5 "active" + # * Don't steer at standstill + # * Don't send > 3.00 Newton-meters torque + # * Don't send the same torque for > 6 seconds + # * Don't send uninterrupted steering for > 360 seconds + # MQB racks reset the uninterrupted steering timer after a single frame + # of HCA disabled; this is done whenever output happens to be zero. + + if CC.latActive: + new_steer = int(round(actuators.steer * self.CCP.STEER_MAX)) + apply_steer = apply_driver_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.CCP) + self.hca_frame_timer_running += self.CCP.STEER_STEP + if self.apply_steer_last == apply_steer: + self.hca_frame_same_torque += self.CCP.STEER_STEP + if self.hca_frame_same_torque > self.CCP.STEER_TIME_STUCK_TORQUE / DT_CTRL: + apply_steer -= (1, -1)[apply_steer < 0] + self.hca_frame_same_torque = 0 + else: + self.hca_frame_same_torque = 0 + hca_enabled = abs(apply_steer) > 0 + else: + hca_enabled = False + apply_steer = 0 + + if not hca_enabled: + self.hca_frame_timer_running = 0 + + self.eps_timer_soft_disable_alert = self.hca_frame_timer_running > self.CCP.STEER_TIME_ALERT / DT_CTRL + self.apply_steer_last = apply_steer + can_sends.append(self.CCS.create_steering_control(self.packer_pt, CANBUS.pt, apply_steer, hca_enabled)) + + if self.CP.flags & VolkswagenFlags.STOCK_HCA_PRESENT: + # Pacify VW Emergency Assist driver inactivity detection by changing its view of driver steering input torque + # to the greatest of actual driver input or 2x openpilot's output (1x openpilot output is not enough to + # consistently reset inactivity detection on straight level roads). See commaai/openpilot#23274 for background. + ea_simulated_torque = clip(apply_steer * 2, -self.CCP.STEER_MAX, self.CCP.STEER_MAX) + if abs(CS.out.steeringTorque) > abs(ea_simulated_torque): + ea_simulated_torque = CS.out.steeringTorque + can_sends.append(self.CCS.create_eps_update(self.packer_pt, CANBUS.cam, CS.eps_stock_values, ea_simulated_torque)) + + # **** Acceleration Controls ******************************************** # + + if self.frame % self.CCP.ACC_CONTROL_STEP == 0 and self.CP.openpilotLongitudinalControl: + acc_control = self.CCS.acc_control_value(CS.out.cruiseState.available, CS.out.accFaulted, CC.longActive) + accel = clip(actuators.accel, self.CCP.ACCEL_MIN, self.CCP.ACCEL_MAX) if CC.longActive else 0 + stopping = actuators.longControlState == LongCtrlState.stopping + starting = actuators.longControlState == LongCtrlState.pid and (CS.esp_hold_confirmation or CS.out.vEgo < self.CP.vEgoStopping) + can_sends.extend(self.CCS.create_acc_accel_control(self.packer_pt, CANBUS.pt, CS.acc_type, CC.longActive, accel, + acc_control, stopping, starting, CS.esp_hold_confirmation)) + + # **** HUD Controls ***************************************************** # + + if self.frame % self.CCP.LDW_STEP == 0: + hud_alert = 0 + if hud_control.visualAlert in (VisualAlert.steerRequired, VisualAlert.ldw): + hud_alert = self.CCP.LDW_MESSAGES["laneAssistTakeOver"] + can_sends.append(self.CCS.create_lka_hud_control(self.packer_pt, CANBUS.pt, CS.ldw_stock_values, CC.latActive, + CS.out.steeringPressed, hud_alert, hud_control)) + + if self.frame % self.CCP.ACC_HUD_STEP == 0 and self.CP.openpilotLongitudinalControl: + lead_distance = 0 + if hud_control.leadVisible and self.frame * DT_CTRL > 1.0: # Don't display lead until we know the scaling factor + lead_distance = 512 if CS.upscale_lead_car_signal else 8 + acc_hud_status = self.CCS.acc_hud_status_value(CS.out.cruiseState.available, CS.out.accFaulted, CC.longActive) + # FIXME: follow the recent displayed-speed updates, also use mph_kmh toggle to fix display rounding problem? + set_speed = hud_control.setSpeed * CV.MS_TO_KPH + can_sends.append(self.CCS.create_acc_hud_control(self.packer_pt, CANBUS.pt, acc_hud_status, set_speed, + lead_distance, hud_control.leadDistanceBars)) + + # **** Stock ACC Button Controls **************************************** # + + gra_send_ready = self.CP.pcmCruise and CS.gra_stock_values["COUNTER"] != self.gra_acc_counter_last + if gra_send_ready and (CC.cruiseControl.cancel or CC.cruiseControl.resume): + can_sends.append(self.CCS.create_acc_buttons_control(self.packer_pt, self.ext_bus, CS.gra_stock_values, + cancel=CC.cruiseControl.cancel, resume=CC.cruiseControl.resume)) + + new_actuators = actuators.as_builder() + new_actuators.steer = self.apply_steer_last / self.CCP.STEER_MAX + new_actuators.steerOutputCan = self.apply_steer_last + + self.gra_acc_counter_last = CS.gra_stock_values["COUNTER"] + self.frame += 1 + return new_actuators, can_sends diff --git a/car/volkswagen/carstate.py b/car/volkswagen/carstate.py new file mode 100644 index 0000000000..ec6403496f --- /dev/null +++ b/car/volkswagen/carstate.py @@ -0,0 +1,398 @@ +import numpy as np +from cereal import car +from openpilot.common.conversions import Conversions as CV +from openpilot.selfdrive.car.interfaces import CarStateBase +from opendbc.can.parser import CANParser +from openpilot.selfdrive.car.volkswagen.values import DBC, CANBUS, NetworkLocation, TransmissionType, GearShifter, \ + CarControllerParams, VolkswagenFlags + + +class CarState(CarStateBase): + def __init__(self, CP): + super().__init__(CP) + self.frame = 0 + self.eps_init_complete = False + self.CCP = CarControllerParams(CP) + self.button_states = {button.event_type: False for button in self.CCP.BUTTONS} + self.esp_hold_confirmation = False + self.upscale_lead_car_signal = False + self.eps_stock_values = False + + def create_button_events(self, pt_cp, buttons): + button_events = [] + + for button in buttons: + state = pt_cp.vl[button.can_addr][button.can_msg] in button.values + if self.button_states[button.event_type] != state: + event = car.CarState.ButtonEvent.new_message() + event.type = button.event_type + event.pressed = state + button_events.append(event) + self.button_states[button.event_type] = state + + return button_events + + def update(self, pt_cp, cam_cp, ext_cp, trans_type): + if self.CP.flags & VolkswagenFlags.PQ: + return self.update_pq(pt_cp, cam_cp, ext_cp, trans_type) + + ret = car.CarState.new_message() + # Update vehicle speed and acceleration from ABS wheel speeds. + ret.wheelSpeeds = self.get_wheel_speeds( + pt_cp.vl["ESP_19"]["ESP_VL_Radgeschw_02"], + pt_cp.vl["ESP_19"]["ESP_VR_Radgeschw_02"], + pt_cp.vl["ESP_19"]["ESP_HL_Radgeschw_02"], + pt_cp.vl["ESP_19"]["ESP_HR_Radgeschw_02"], + ) + + ret.vEgoRaw = float(np.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 + + # Update EPS position and state info. For signed values, VW sends the sign in a separate signal. + ret.steeringAngleDeg = pt_cp.vl["LWI_01"]["LWI_Lenkradwinkel"] * (1, -1)[int(pt_cp.vl["LWI_01"]["LWI_VZ_Lenkradwinkel"])] + ret.steeringRateDeg = pt_cp.vl["LWI_01"]["LWI_Lenkradw_Geschw"] * (1, -1)[int(pt_cp.vl["LWI_01"]["LWI_VZ_Lenkradw_Geschw"])] + ret.steeringTorque = pt_cp.vl["LH_EPS_03"]["EPS_Lenkmoment"] * (1, -1)[int(pt_cp.vl["LH_EPS_03"]["EPS_VZ_Lenkmoment"])] + ret.steeringPressed = abs(ret.steeringTorque) > self.CCP.STEER_DRIVER_ALLOWANCE + ret.yawRate = pt_cp.vl["ESP_02"]["ESP_Gierrate"] * (1, -1)[int(pt_cp.vl["ESP_02"]["ESP_VZ_Gierrate"])] * CV.DEG_TO_RAD + hca_status = self.CCP.hca_status_values.get(pt_cp.vl["LH_EPS_03"]["EPS_HCA_Status"]) + ret.steerFaultTemporary, ret.steerFaultPermanent = self.update_hca_state(hca_status) + + # VW Emergency Assist status tracking and mitigation + self.eps_stock_values = pt_cp.vl["LH_EPS_03"] + if self.CP.flags & VolkswagenFlags.STOCK_HCA_PRESENT: + ret.carFaultedNonCritical = bool(cam_cp.vl["HCA_01"]["EA_Ruckfreigabe"]) or cam_cp.vl["HCA_01"]["EA_ACC_Sollstatus"] > 0 + + # Update gas, brakes, and gearshift. + ret.gas = pt_cp.vl["Motor_20"]["MO_Fahrpedalrohwert_01"] / 100.0 + ret.gasPressed = ret.gas > 0 + ret.brake = pt_cp.vl["ESP_05"]["ESP_Bremsdruck"] / 250.0 # FIXME: this is pressure in Bar, not sure what OP expects + brake_pedal_pressed = bool(pt_cp.vl["Motor_14"]["MO_Fahrer_bremst"]) + brake_pressure_detected = bool(pt_cp.vl["ESP_05"]["ESP_Fahrer_bremst"]) + ret.brakePressed = brake_pedal_pressed or brake_pressure_detected + ret.parkingBrake = bool(pt_cp.vl["Kombi_01"]["KBI_Handbremse"]) # FIXME: need to include an EPB check as well + + # Update gear and/or clutch position data. + if trans_type == TransmissionType.automatic: + ret.gearShifter = self.parse_gear_shifter(self.CCP.shifter_values.get(pt_cp.vl["Getriebe_11"]["GE_Fahrstufe"], None)) + elif trans_type == TransmissionType.direct: + ret.gearShifter = self.parse_gear_shifter(self.CCP.shifter_values.get(pt_cp.vl["EV_Gearshift"]["GearPosition"], None)) + elif trans_type == TransmissionType.manual: + ret.clutchPressed = not pt_cp.vl["Motor_14"]["MO_Kuppl_schalter"] + if bool(pt_cp.vl["Gateway_72"]["BCM1_Rueckfahrlicht_Schalter"]): + ret.gearShifter = GearShifter.reverse + else: + ret.gearShifter = GearShifter.drive + + # Update door and trunk/hatch lid open status. + ret.doorOpen = any([pt_cp.vl["Gateway_72"]["ZV_FT_offen"], + pt_cp.vl["Gateway_72"]["ZV_BT_offen"], + pt_cp.vl["Gateway_72"]["ZV_HFS_offen"], + pt_cp.vl["Gateway_72"]["ZV_HBFS_offen"], + pt_cp.vl["Gateway_72"]["ZV_HD_offen"]]) + + # Update seatbelt fastened status. + ret.seatbeltUnlatched = pt_cp.vl["Airbag_02"]["AB_Gurtschloss_FA"] != 3 + + # Consume blind-spot monitoring info/warning LED states, if available. + # Infostufe: BSM LED on, Warnung: BSM LED flashing + if self.CP.enableBsm: + ret.leftBlindspot = bool(ext_cp.vl["SWA_01"]["SWA_Infostufe_SWA_li"]) or bool(ext_cp.vl["SWA_01"]["SWA_Warnung_SWA_li"]) + ret.rightBlindspot = bool(ext_cp.vl["SWA_01"]["SWA_Infostufe_SWA_re"]) or bool(ext_cp.vl["SWA_01"]["SWA_Warnung_SWA_re"]) + + # Consume factory LDW data relevant for factory SWA (Lane Change Assist) + # and capture it for forwarding to the blind spot radar controller + self.ldw_stock_values = cam_cp.vl["LDW_02"] if self.CP.networkLocation == NetworkLocation.fwdCamera else {} + + # Stock FCW is considered active if the release bit for brake-jerk warning + # is set. Stock AEB considered active if the partial braking or target + # braking release bits are set. + # Refer to VW Self Study Program 890253: Volkswagen Driver Assistance + # Systems, chapter on Front Assist with Braking: Golf Family for all MQB + ret.stockFcw = bool(ext_cp.vl["ACC_10"]["AWV2_Freigabe"]) + ret.stockAeb = bool(ext_cp.vl["ACC_10"]["ANB_Teilbremsung_Freigabe"]) or bool(ext_cp.vl["ACC_10"]["ANB_Zielbremsung_Freigabe"]) + + # Update ACC radar status. + self.acc_type = ext_cp.vl["ACC_06"]["ACC_Typ"] + + # ACC okay but disabled (1), ACC ready (2), a radar visibility or other fault/disruption (6 or 7) + # currently regulating speed (3), driver accel override (4), brake only (5) + ret.cruiseState.available = pt_cp.vl["TSK_06"]["TSK_Status"] in (2, 3, 4, 5) + ret.cruiseState.enabled = pt_cp.vl["TSK_06"]["TSK_Status"] in (3, 4, 5) + + if self.CP.pcmCruise: + # Cruise Control mode; check for distance UI setting from the radar. + # ECM does not manage this, so do not need to check for openpilot longitudinal + ret.cruiseState.nonAdaptive = ext_cp.vl["ACC_02"]["ACC_Gesetzte_Zeitluecke"] == 0 + else: + # Speed limiter mode; ECM faults if we command ACC while not pcmCruise + ret.cruiseState.nonAdaptive = bool(pt_cp.vl["TSK_06"]["TSK_Limiter_ausgewaehlt"]) + + ret.accFaulted = pt_cp.vl["TSK_06"]["TSK_Status"] in (6, 7) + + self.esp_hold_confirmation = bool(pt_cp.vl["ESP_21"]["ESP_Haltebestaetigung"]) + ret.cruiseState.standstill = self.CP.pcmCruise and self.esp_hold_confirmation + + # Update ACC setpoint. When the setpoint is zero or there's an error, the + # radar sends a set-speed of ~90.69 m/s / 203mph. + if self.CP.pcmCruise: + ret.cruiseState.speed = ext_cp.vl["ACC_02"]["ACC_Wunschgeschw_02"] * CV.KPH_TO_MS + if ret.cruiseState.speed > 90: + ret.cruiseState.speed = 0 + + # Update button states for turn signals and ACC controls, capture all ACC button state/config for passthrough + ret.leftBlinker = bool(pt_cp.vl["Blinkmodi_02"]["Comfort_Signal_Left"]) + ret.rightBlinker = bool(pt_cp.vl["Blinkmodi_02"]["Comfort_Signal_Right"]) + ret.buttonEvents = self.create_button_events(pt_cp, self.CCP.BUTTONS) + self.gra_stock_values = pt_cp.vl["GRA_ACC_01"] + + # Additional safety checks performed in CarInterface. + ret.espDisabled = pt_cp.vl["ESP_21"]["ESP_Tastung_passiv"] != 0 + + # Digital instrument clusters expect the ACC HUD lead car distance to be scaled differently + self.upscale_lead_car_signal = bool(pt_cp.vl["Kombi_03"]["KBI_Variante"]) + + self.frame += 1 + return ret + + def update_pq(self, pt_cp, cam_cp, ext_cp, trans_type): + ret = car.CarState.new_message() + # Update vehicle speed and acceleration from ABS wheel speeds. + ret.wheelSpeeds = self.get_wheel_speeds( + pt_cp.vl["Bremse_3"]["Radgeschw__VL_4_1"], + pt_cp.vl["Bremse_3"]["Radgeschw__VR_4_1"], + pt_cp.vl["Bremse_3"]["Radgeschw__HL_4_1"], + pt_cp.vl["Bremse_3"]["Radgeschw__HR_4_1"], + ) + + # vEgo obtained from Bremse_1 vehicle speed rather than Bremse_3 wheel speeds because Bremse_3 isn't present on NSF + ret.vEgoRaw = pt_cp.vl["Bremse_1"]["Geschwindigkeit_neu__Bremse_1_"] * CV.KPH_TO_MS + ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) + ret.standstill = ret.vEgoRaw == 0 + + # Update EPS position and state info. For signed values, VW sends the sign in a separate signal. + ret.steeringAngleDeg = pt_cp.vl["Lenkhilfe_3"]["LH3_BLW"] * (1, -1)[int(pt_cp.vl["Lenkhilfe_3"]["LH3_BLWSign"])] + ret.steeringRateDeg = pt_cp.vl["Lenkwinkel_1"]["Lenkradwinkel_Geschwindigkeit"] * (1, -1)[int(pt_cp.vl["Lenkwinkel_1"]["Lenkradwinkel_Geschwindigkeit_S"])] + ret.steeringTorque = pt_cp.vl["Lenkhilfe_3"]["LH3_LM"] * (1, -1)[int(pt_cp.vl["Lenkhilfe_3"]["LH3_LMSign"])] + ret.steeringPressed = abs(ret.steeringTorque) > self.CCP.STEER_DRIVER_ALLOWANCE + ret.yawRate = pt_cp.vl["Bremse_5"]["Giergeschwindigkeit"] * (1, -1)[int(pt_cp.vl["Bremse_5"]["Vorzeichen_der_Giergeschwindigk"])] * CV.DEG_TO_RAD + hca_status = self.CCP.hca_status_values.get(pt_cp.vl["Lenkhilfe_2"]["LH2_Sta_HCA"]) + ret.steerFaultTemporary, ret.steerFaultPermanent = self.update_hca_state(hca_status) + + # Update gas, brakes, and gearshift. + ret.gas = pt_cp.vl["Motor_3"]["Fahrpedal_Rohsignal"] / 100.0 + ret.gasPressed = ret.gas > 0 + ret.brake = pt_cp.vl["Bremse_5"]["Bremsdruck"] / 250.0 # FIXME: this is pressure in Bar, not sure what OP expects + ret.brakePressed = bool(pt_cp.vl["Motor_2"]["Bremslichtschalter"]) + ret.parkingBrake = bool(pt_cp.vl["Kombi_1"]["Bremsinfo"]) + + # Update gear and/or clutch position data. + if trans_type == TransmissionType.automatic: + ret.gearShifter = self.parse_gear_shifter(self.CCP.shifter_values.get(pt_cp.vl["Getriebe_1"]["Waehlhebelposition__Getriebe_1_"], None)) + elif trans_type == TransmissionType.manual: + ret.clutchPressed = not pt_cp.vl["Motor_1"]["Kupplungsschalter"] + reverse_light = bool(pt_cp.vl["Gate_Komf_1"]["GK1_Rueckfahr"]) + if reverse_light: + ret.gearShifter = GearShifter.reverse + else: + ret.gearShifter = GearShifter.drive + + # Update door and trunk/hatch lid open status. + ret.doorOpen = any([pt_cp.vl["Gate_Komf_1"]["GK1_Fa_Tuerkont"], + pt_cp.vl["Gate_Komf_1"]["BSK_BT_geoeffnet"], + pt_cp.vl["Gate_Komf_1"]["BSK_HL_geoeffnet"], + pt_cp.vl["Gate_Komf_1"]["BSK_HR_geoeffnet"], + pt_cp.vl["Gate_Komf_1"]["BSK_HD_Hauptraste"]]) + + # Update seatbelt fastened status. + ret.seatbeltUnlatched = not bool(pt_cp.vl["Airbag_1"]["Gurtschalter_Fahrer"]) + + # Consume blind-spot monitoring info/warning LED states, if available. + # Infostufe: BSM LED on, Warnung: BSM LED flashing + if self.CP.enableBsm: + ret.leftBlindspot = bool(ext_cp.vl["SWA_1"]["SWA_Infostufe_SWA_li"]) or bool(ext_cp.vl["SWA_1"]["SWA_Warnung_SWA_li"]) + ret.rightBlindspot = bool(ext_cp.vl["SWA_1"]["SWA_Infostufe_SWA_re"]) or bool(ext_cp.vl["SWA_1"]["SWA_Warnung_SWA_re"]) + + # Consume factory LDW data relevant for factory SWA (Lane Change Assist) + # and capture it for forwarding to the blind spot radar controller + self.ldw_stock_values = cam_cp.vl["LDW_Status"] if self.CP.networkLocation == NetworkLocation.fwdCamera else {} + + # Stock FCW is considered active if the release bit for brake-jerk warning + # is set. Stock AEB considered active if the partial braking or target + # braking release bits are set. + # Refer to VW Self Study Program 890253: Volkswagen Driver Assistance + # Systems, chapters on Front Assist with Braking and City Emergency + # Braking for the 2016 Passat NMS + # TODO: deferred until we can collect data on pre-MY2016 behavior, AWV message may be shorter with fewer signals + ret.stockFcw = False + ret.stockAeb = False + + # Update ACC radar status. + self.acc_type = ext_cp.vl["ACC_System"]["ACS_Typ_ACC"] + ret.cruiseState.available = bool(pt_cp.vl["Motor_5"]["GRA_Hauptschalter"]) + ret.cruiseState.enabled = pt_cp.vl["Motor_2"]["GRA_Status"] in (1, 2) + if self.CP.pcmCruise: + ret.accFaulted = ext_cp.vl["ACC_GRA_Anzeige"]["ACA_StaACC"] in (6, 7) + else: + ret.accFaulted = pt_cp.vl["Motor_2"]["GRA_Status"] == 3 + + # Update ACC setpoint. When the setpoint reads as 255, the driver has not + # yet established an ACC setpoint, so treat it as zero. + ret.cruiseState.speed = ext_cp.vl["ACC_GRA_Anzeige"]["ACA_V_Wunsch"] * CV.KPH_TO_MS + if ret.cruiseState.speed > 70: # 255 kph in m/s == no current setpoint + ret.cruiseState.speed = 0 + + # Update button states for turn signals and ACC controls, capture all ACC button state/config for passthrough + ret.leftBlinker, ret.rightBlinker = self.update_blinker_from_stalk(300, pt_cp.vl["Gate_Komf_1"]["GK1_Blinker_li"], + pt_cp.vl["Gate_Komf_1"]["GK1_Blinker_re"]) + ret.buttonEvents = self.create_button_events(pt_cp, self.CCP.BUTTONS) + self.gra_stock_values = pt_cp.vl["GRA_Neu"] + + # Additional safety checks performed in CarInterface. + ret.espDisabled = bool(pt_cp.vl["Bremse_1"]["ESP_Passiv_getastet"]) + + self.frame += 1 + return ret + + def update_hca_state(self, hca_status): + # Treat INITIALIZING and FAULT as temporary for worst likely EPS recovery time, for cars without factory Lane Assist + # DISABLED means the EPS hasn't been configured to support Lane Assist + self.eps_init_complete = self.eps_init_complete or (hca_status in ("DISABLED", "READY", "ACTIVE") or self.frame > 600) + perm_fault = hca_status == "DISABLED" or (self.eps_init_complete and hca_status in ("INITIALIZING", "FAULT")) + temp_fault = hca_status in ("REJECTED", "PREEMPTED") or not self.eps_init_complete + return temp_fault, perm_fault + + @staticmethod + def get_can_parser(CP): + if CP.flags & VolkswagenFlags.PQ: + return CarState.get_can_parser_pq(CP) + + messages = [ + # sig_address, frequency + ("LWI_01", 100), # From J500 Steering Assist with integrated sensors + ("LH_EPS_03", 100), # From J500 Steering Assist with integrated sensors + ("ESP_19", 100), # From J104 ABS/ESP controller + ("ESP_05", 50), # From J104 ABS/ESP controller + ("ESP_21", 50), # From J104 ABS/ESP controller + ("Motor_20", 50), # From J623 Engine control module + ("TSK_06", 50), # From J623 Engine control module + ("ESP_02", 50), # From J104 ABS/ESP controller + ("GRA_ACC_01", 33), # From J533 CAN gateway (via LIN from steering wheel controls) + ("Gateway_72", 10), # From J533 CAN gateway (aggregated data) + ("Motor_14", 10), # From J623 Engine control module + ("Airbag_02", 5), # From J234 Airbag control module + ("Kombi_01", 2), # From J285 Instrument cluster + ("Blinkmodi_02", 1), # From J519 BCM (sent at 1Hz when no lights active, 50Hz when active) + ("Kombi_03", 0), # From J285 instrument cluster (not present on older cars, 1Hz when present) + ] + + if CP.transmissionType == TransmissionType.automatic: + messages.append(("Getriebe_11", 20)) # From J743 Auto transmission control module + elif CP.transmissionType == TransmissionType.direct: + messages.append(("EV_Gearshift", 10)) # From J??? unknown EV control module + + if CP.networkLocation == NetworkLocation.fwdCamera: + # Radars are here on CANBUS.pt + messages += MqbExtraSignals.fwd_radar_messages + if CP.enableBsm: + messages += MqbExtraSignals.bsm_radar_messages + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, CANBUS.pt) + + @staticmethod + def get_cam_can_parser(CP): + if CP.flags & VolkswagenFlags.PQ: + return CarState.get_cam_can_parser_pq(CP) + + messages = [] + + if CP.flags & VolkswagenFlags.STOCK_HCA_PRESENT: + messages += [ + ("HCA_01", 1), # From R242 Driver assistance camera, 50Hz if steering/1Hz if not + ] + + if CP.networkLocation == NetworkLocation.fwdCamera: + messages += [ + # sig_address, frequency + ("LDW_02", 10) # From R242 Driver assistance camera + ] + else: + # Radars are here on CANBUS.cam + messages += MqbExtraSignals.fwd_radar_messages + if CP.enableBsm: + messages += MqbExtraSignals.bsm_radar_messages + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, CANBUS.cam) + + @staticmethod + def get_can_parser_pq(CP): + messages = [ + # sig_address, frequency + ("Bremse_1", 100), # From J104 ABS/ESP controller + ("Bremse_3", 100), # From J104 ABS/ESP controller + ("Lenkhilfe_3", 100), # From J500 Steering Assist with integrated sensors + ("Lenkwinkel_1", 100), # From J500 Steering Assist with integrated sensors + ("Motor_3", 100), # From J623 Engine control module + ("Airbag_1", 50), # From J234 Airbag control module + ("Bremse_5", 50), # From J104 ABS/ESP controller + ("GRA_Neu", 50), # From J??? steering wheel control buttons + ("Kombi_1", 50), # From J285 Instrument cluster + ("Motor_2", 50), # From J623 Engine control module + ("Motor_5", 50), # From J623 Engine control module + ("Lenkhilfe_2", 20), # From J500 Steering Assist with integrated sensors + ("Gate_Komf_1", 10), # From J533 CAN gateway + ] + + if CP.transmissionType == TransmissionType.automatic: + messages += [("Getriebe_1", 100)] # From J743 Auto transmission control module + elif CP.transmissionType == TransmissionType.manual: + messages += [("Motor_1", 100)] # From J623 Engine control module + + if CP.networkLocation == NetworkLocation.fwdCamera: + # Extended CAN devices other than the camera are here on CANBUS.pt + messages += PqExtraSignals.fwd_radar_messages + if CP.enableBsm: + messages += PqExtraSignals.bsm_radar_messages + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, CANBUS.pt) + + @staticmethod + def get_cam_can_parser_pq(CP): + + messages = [] + + if CP.networkLocation == NetworkLocation.fwdCamera: + messages += [ + # sig_address, frequency + ("LDW_Status", 10) # From R242 Driver assistance camera + ] + + if CP.networkLocation == NetworkLocation.gateway: + # Radars are here on CANBUS.cam + messages += PqExtraSignals.fwd_radar_messages + if CP.enableBsm: + messages += PqExtraSignals.bsm_radar_messages + + return CANParser(DBC[CP.carFingerprint]["pt"], messages, CANBUS.cam) + + +class MqbExtraSignals: + # Additional signal and message lists for optional or bus-portable controllers + fwd_radar_messages = [ + ("ACC_06", 50), # From J428 ACC radar control module + ("ACC_10", 50), # From J428 ACC radar control module + ("ACC_02", 17), # From J428 ACC radar control module + ] + bsm_radar_messages = [ + ("SWA_01", 20), # From J1086 Lane Change Assist + ] + +class PqExtraSignals: + # Additional signal and message lists for optional or bus-portable controllers + fwd_radar_messages = [ + ("ACC_System", 50), # From J428 ACC radar control module + ("ACC_GRA_Anzeige", 25), # From J428 ACC radar control module + ] + bsm_radar_messages = [ + ("SWA_1", 20), # From J1086 Lane Change Assist + ] diff --git a/car/volkswagen/fingerprints.py b/car/volkswagen/fingerprints.py new file mode 100644 index 0000000000..fdc375fc8d --- /dev/null +++ b/car/volkswagen/fingerprints.py @@ -0,0 +1,1201 @@ +from cereal import car +from openpilot.selfdrive.car.volkswagen.values import CAR + +Ecu = car.CarParams.Ecu + +# TODO: Sharan Mk2 EPS and DQ250 auto trans both require KWP2000 support for fingerprinting + + +FW_VERSIONS = { + CAR.VOLKSWAGEN_ARTEON_MK1: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x873G0906259AH\xf1\x890001', + b'\xf1\x873G0906259F \xf1\x890004', + b'\xf1\x873G0906259G \xf1\x890004', + b'\xf1\x873G0906259G \xf1\x890005', + b'\xf1\x873G0906259M \xf1\x890003', + b'\xf1\x873G0906259N \xf1\x890004', + b'\xf1\x873G0906259P \xf1\x890001', + b'\xf1\x875NA907115H \xf1\x890002', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x8709G927158L \xf1\x893611', + b'\xf1\x870DL300014C \xf1\x893704', + b'\xf1\x870GC300011L \xf1\x891401', + b'\xf1\x870GC300014M \xf1\x892802', + b'\xf1\x870GC300019G \xf1\x892804', + b'\xf1\x870GC300040P \xf1\x891401', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x873Q0959655BK\xf1\x890703\xf1\x82\x0e1616001613121157161111572900', + b'\xf1\x873Q0959655BK\xf1\x890703\xf1\x82\x0e1616001613121177161113772900', + b'\xf1\x873Q0959655CK\xf1\x890711\xf1\x82\x0e1712141712141105121122052900', + b'\xf1\x873Q0959655DA\xf1\x890720\xf1\x82\x0e1712141712141105121122052900', + b'\xf1\x873Q0959655DL\xf1\x890732\xf1\x82\x0e1812141812171105141123052J00', + b'\xf1\x875QF959655AP\xf1\x890755\xf1\x82\x1311110011111311111100110200--1611125F49', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571B41815A1', + b'\xf1\x873Q0909144L \xf1\x895081\xf1\x82\x0571B00817A1', + b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567B0020800', + b'\xf1\x875WA907145M \xf1\x891051\xf1\x82\x002MB4092M7N', + b'\xf1\x875WA907145M \xf1\x891051\xf1\x82\x002NB4202N7N', + b'\xf1\x875WA907145Q \xf1\x891063\xf1\x82\x002KB4092KOM', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572AA\xf1\x890396', + b'\xf1\x872Q0907572T \xf1\x890383', + b'\xf1\x875Q0907572J \xf1\x890654', + b'\xf1\x875Q0907572R \xf1\x890771', + ], + }, + CAR.VOLKSWAGEN_ATLAS_MK1: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8703H906026AA\xf1\x899970', + b'\xf1\x8703H906026AG\xf1\x899973', + b'\xf1\x8703H906026AJ\xf1\x890638', + b'\xf1\x8703H906026AJ\xf1\x891017', + b'\xf1\x8703H906026AT\xf1\x891922', + b'\xf1\x8703H906026BC\xf1\x892664', + b'\xf1\x8703H906026F \xf1\x896696', + b'\xf1\x8703H906026F \xf1\x899970', + b'\xf1\x8703H906026J \xf1\x896026', + b'\xf1\x8703H906026J \xf1\x899970', + b'\xf1\x8703H906026J \xf1\x899971', + b'\xf1\x8703H906026S \xf1\x896693', + b'\xf1\x8703H906026S \xf1\x899970', + b'\xf1\x873CN906259 \xf1\x890005', + b'\xf1\x873CN906259F \xf1\x890002', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x8709G927158A \xf1\x893387', + b'\xf1\x8709G927158DR\xf1\x893536', + b'\xf1\x8709G927158DR\xf1\x893742', + b'\xf1\x8709G927158EN\xf1\x893691', + b'\xf1\x8709G927158F \xf1\x893489', + b'\xf1\x8709G927158FT\xf1\x893835', + b'\xf1\x8709G927158GL\xf1\x893939', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x873Q0959655BC\xf1\x890503\xf1\x82\x0e1914151912001103111122031200', + b'\xf1\x873Q0959655BN\xf1\x890713\xf1\x82\x0e2214152212001105141122052900', + b'\xf1\x873Q0959655DB\xf1\x890720\xf1\x82\x0e1114151112001105111122052900', + b'\xf1\x873Q0959655DB\xf1\x890720\xf1\x82\x0e2214152212001105141122052900', + b'\xf1\x873Q0959655DM\xf1\x890732\xf1\x82\x0e1114151112001105111122052J00', + b'\xf1\x873Q0959655DM\xf1\x890732\xf1\x82\x0e1114151112001105161122052J00', + b'\xf1\x873Q0959655DM\xf1\x890732\xf1\x82\x0e1115151112001105171122052J00', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x873QF909144B \xf1\x891582\xf1\x82\x0571B60924A1', + b'\xf1\x873QF909144B \xf1\x891582\xf1\x82\x0571B6G920A1', + b'\xf1\x873QF909144B \xf1\x891582\xf1\x82\x0571B6M921A1', + b'\xf1\x873QF909144B \xf1\x891582\xf1\x82\x0571B6N920A1', + b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820528B6080105', + b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820528B6090105', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572AA\xf1\x890396', + b'\xf1\x872Q0907572R \xf1\x890372', + b'\xf1\x872Q0907572T \xf1\x890383', + b'\xf1\x875Q0907572H \xf1\x890620', + b'\xf1\x875Q0907572J \xf1\x890654', + b'\xf1\x875Q0907572P \xf1\x890682', + b'\xf1\x875Q0907572S \xf1\x890780', + ], + }, + CAR.VOLKSWAGEN_CADDY_MK3: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704E906027T \xf1\x892363', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x872K5959655E \xf1\x890018\xf1\x82\x05000P037605', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x877N0907572C \xf1\x890211\xf1\x82\x0155', + ], + }, + CAR.VOLKSWAGEN_CRAFTER_MK2: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704L906056BP\xf1\x894729', + b'\xf1\x8704L906056EK\xf1\x896391', + b'\xf1\x8705L906023BC\xf1\x892688', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x873Q0959655AL\xf1\x890505\xf1\x82\x0e1411001413001203151311031100', + b'\xf1\x873Q0959655BG\xf1\x890703\xf1\x82\x0e16120016130012051G1313052900', + b'\xf1\x875QF959655AS\xf1\x890755\xf1\x82\x1315140015150011111100050200--1311120749', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x872N0909143D\x00\xf1\x897010\xf1\x82\x05183AZ306A2', + b'\xf1\x872N0909143E \xf1\x897021\xf1\x82\x05163AZ306A2', + b'\xf1\x872N0909144K \xf1\x897045\xf1\x82\x05233AZ810A2', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572AA\xf1\x890396', + b'\xf1\x872Q0907572J \xf1\x890156', + b'\xf1\x872Q0907572M \xf1\x890233', + ], + }, + CAR.VOLKSWAGEN_GOLF_MK7: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704E906016A \xf1\x897697', + b'\xf1\x8704E906016AD\xf1\x895758', + b'\xf1\x8704E906016CE\xf1\x899096', + b'\xf1\x8704E906016CH\xf1\x899226', + b'\xf1\x8704E906016N \xf1\x899105', + b'\xf1\x8704E906023AG\xf1\x891726', + b'\xf1\x8704E906023BN\xf1\x894518', + b'\xf1\x8704E906024K \xf1\x896811', + b'\xf1\x8704E906024K \xf1\x899970', + b'\xf1\x8704E906027GR\xf1\x892394', + b'\xf1\x8704E906027HD\xf1\x892603', + b'\xf1\x8704E906027HD\xf1\x893742', + b'\xf1\x8704E906027MA\xf1\x894958', + b'\xf1\x8704L906021DT\xf1\x895520', + b'\xf1\x8704L906021DT\xf1\x898127', + b'\xf1\x8704L906021N \xf1\x895518', + b'\xf1\x8704L906021N \xf1\x898138', + b'\xf1\x8704L906026BN\xf1\x891197', + b'\xf1\x8704L906026BP\xf1\x897608', + b'\xf1\x8704L906026NF\xf1\x899528', + b'\xf1\x8704L906056CL\xf1\x893823', + b'\xf1\x8704L906056CR\xf1\x895813', + b'\xf1\x8704L906056HE\xf1\x893758', + b'\xf1\x8704L906056HN\xf1\x896590', + b'\xf1\x8704L906056HT\xf1\x896591', + b'\xf1\x8704L997022N \xf1\x899459', + b'\xf1\x870EA906016A \xf1\x898343', + b'\xf1\x870EA906016E \xf1\x894219', + b'\xf1\x870EA906016F \xf1\x894238', + b'\xf1\x870EA906016F \xf1\x895002', + b'\xf1\x870EA906016Q \xf1\x895993', + b'\xf1\x870EA906016S \xf1\x897207', + b'\xf1\x875G0906259 \xf1\x890007', + b'\xf1\x875G0906259D \xf1\x890002', + b'\xf1\x875G0906259J \xf1\x890002', + b'\xf1\x875G0906259L \xf1\x890002', + b'\xf1\x875G0906259N \xf1\x890003', + b'\xf1\x875G0906259Q \xf1\x890002', + b'\xf1\x875G0906259Q \xf1\x892313', + b'\xf1\x875G0906259T \xf1\x890003', + b'\xf1\x878V0906259H \xf1\x890002', + b'\xf1\x878V0906259J \xf1\x890003', + b'\xf1\x878V0906259J \xf1\x890103', + b'\xf1\x878V0906259K \xf1\x890001', + b'\xf1\x878V0906259K \xf1\x890003', + b'\xf1\x878V0906259P \xf1\x890001', + b'\xf1\x878V0906259Q \xf1\x890002', + b'\xf1\x878V0906259R \xf1\x890002', + b'\xf1\x878V0906264F \xf1\x890003', + b'\xf1\x878V0906264L \xf1\x890002', + b'\xf1\x878V0906264M \xf1\x890001', + b'\xf1\x878V09C0BB01 \xf1\x890001', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x8709G927749AP\xf1\x892943', + b'\xf1\x8709S927158A \xf1\x893585', + b'\xf1\x870CW300040H \xf1\x890606', + b'\xf1\x870CW300041D \xf1\x891004', + b'\xf1\x870CW300041H \xf1\x891010', + b'\xf1\x870CW300042F \xf1\x891604', + b'\xf1\x870CW300043B \xf1\x891601', + b'\xf1\x870CW300043E \xf1\x891603', + b'\xf1\x870CW300044S \xf1\x894530', + b'\xf1\x870CW300044T \xf1\x895245', + b'\xf1\x870CW300045 \xf1\x894531', + b'\xf1\x870CW300047D \xf1\x895261', + b'\xf1\x870CW300047E \xf1\x895261', + b'\xf1\x870CW300048J \xf1\x890611', + b'\xf1\x870CW300049H \xf1\x890905', + b'\xf1\x870CW300050G \xf1\x891905', + b'\xf1\x870D9300012 \xf1\x894904', + b'\xf1\x870D9300012 \xf1\x894913', + b'\xf1\x870D9300012 \xf1\x894937', + b'\xf1\x870D9300012 \xf1\x895045', + b'\xf1\x870D9300012 \xf1\x895046', + b'\xf1\x870D9300014M \xf1\x895004', + b'\xf1\x870D9300014Q \xf1\x895006', + b'\xf1\x870D9300018 \xf1\x895201', + b'\xf1\x870D9300020J \xf1\x894902', + b'\xf1\x870D9300020Q \xf1\x895201', + b'\xf1\x870D9300020S \xf1\x895201', + b'\xf1\x870D9300040A \xf1\x893613', + b'\xf1\x870D9300040S \xf1\x894311', + b'\xf1\x870D9300041H \xf1\x895220', + b'\xf1\x870D9300041N \xf1\x894512', + b'\xf1\x870D9300041P \xf1\x894507', + b'\xf1\x870DD300045K \xf1\x891120', + b'\xf1\x870DD300046F \xf1\x891601', + b'\xf1\x870GC300012A \xf1\x891401', + b'\xf1\x870GC300012A \xf1\x891403', + b'\xf1\x870GC300012A \xf1\x891422', + b'\xf1\x870GC300012M \xf1\x892301', + b'\xf1\x870GC300014B \xf1\x892401', + b'\xf1\x870GC300014B \xf1\x892403', + b'\xf1\x870GC300014B \xf1\x892405', + b'\xf1\x870GC300020G \xf1\x892401', + b'\xf1\x870GC300020G \xf1\x892403', + b'\xf1\x870GC300020G \xf1\x892404', + b'\xf1\x870GC300020N \xf1\x892804', + b'\xf1\x870GC300043T \xf1\x899999', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x875Q0959655AA\xf1\x890386\xf1\x82\x111413001113120043114317121C111C9113', + b'\xf1\x875Q0959655AA\xf1\x890386\xf1\x82\x111413001113120053114317121C111C9113', + b'\xf1\x875Q0959655AA\xf1\x890388\xf1\x82\x111413001113120043114317121C111C9113', + b'\xf1\x875Q0959655AA\xf1\x890388\xf1\x82\x111413001113120043114417121411149113', + b'\xf1\x875Q0959655AA\xf1\x890388\xf1\x82\x111413001113120053114317121C111C9113', + b'\xf1\x875Q0959655AR\xf1\x890317\xf1\x82\x13141500111233003142114A2131219333313100', + b'\xf1\x875Q0959655BH\xf1\x890336\xf1\x82\x1314160011123300314211012230229333423100', + b'\xf1\x875Q0959655BH\xf1\x890336\xf1\x82\x1314160011123300314211012230229333463100', + b'\xf1\x875Q0959655BJ\xf1\x890339\xf1\x82\x13141600111233003142115A2232229333463100', + b'\xf1\x875Q0959655BS\xf1\x890403\xf1\x82\x1314160011123300314240012250229333463100', + b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x13141600111233003142404A2251229333463100', + b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x13141600111233003142404A2252229333463100', + b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x13141600111233003142405A2251229333463100', + b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x13141600111233003142405A2252229333463100', + b'\xf1\x875Q0959655C \xf1\x890361\xf1\x82\x111413001112120004110415121610169112', + b'\xf1\x875Q0959655CA\xf1\x890403\xf1\x82\x1314160011123300314240012250229333463100', + b'\xf1\x875Q0959655D \xf1\x890388\xf1\x82\x111413001113120006110417121A101A9113', + b'\xf1\x875Q0959655J \xf1\x890825\xf1\x82\x13271112111312--071104171825102591131211', + b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13271112111312--071104171825102591131211', + b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13271212111312--071104171838103891131211', + b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13272512111312--07110417182C102C91131211', + b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13341512112212--071104172328102891131211', + b'\xf1\x875Q0959655M \xf1\x890361\xf1\x82\x111413001112120041114115121611169112', + b'\xf1\x875Q0959655S \xf1\x890870\xf1\x82\x1315120011211200061104171717101791132111', + b'\xf1\x875Q0959655S \xf1\x890870\xf1\x82\x1315120011211200621143171717111791132111', + b'\xf1\x875Q0959655S \xf1\x890870\xf1\x82\x1324230011211200061104171724102491132111', + b'\xf1\x875Q0959655S \xf1\x890870\xf1\x82\x1324230011211200621143171724112491132111', + b'\xf1\x875Q0959655S \xf1\x890870\xf1\x82\x1324230011211200631143171724122491132111', + b'\xf1\x875Q0959655T \xf1\x890825\xf1\x82\x13271200111312--071104171837103791132111', + b'\xf1\x875Q0959655T \xf1\x890830\xf1\x82\x13271100111312--071104171826102691131211', + b'\xf1\x875QD959655 \xf1\x890388\xf1\x82\x111413001113120006110417121D101D9112', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x873Q0909144F \xf1\x895043\xf1\x82\x0561A01612A0', + b'\xf1\x873Q0909144H \xf1\x895061\xf1\x82\x0566A0J612A1', + b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566A00514A1', + b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566A01613A1', + b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566A0J712A1', + b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571A0J714A1', + b'\xf1\x873Q0909144L \xf1\x895081\xf1\x82\x0571A0JA15A1', + b'\xf1\x873Q0909144M \xf1\x895082\xf1\x82\x0571A01A18A1', + b'\xf1\x873Q0909144M \xf1\x895082\xf1\x82\x0571A02A16A1', + b'\xf1\x873Q0909144M \xf1\x895082\xf1\x82\x0571A0JA16A1', + b'\xf1\x873QM909144 \xf1\x895072\xf1\x82\x0571A01714A1', + b'\xf1\x875Q0909143K \xf1\x892033\xf1\x820519A9040203', + b'\xf1\x875Q0909144AA\xf1\x891081\xf1\x82\x0521A00441A1', + b'\xf1\x875Q0909144AA\xf1\x891081\xf1\x82\x0521A00608A1', + b'\xf1\x875Q0909144AA\xf1\x891081\xf1\x82\x0521A00641A1', + b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521A00442A1', + b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521A00642A1', + b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521A07B05A1', + b'\xf1\x875Q0909144L \xf1\x891021\xf1\x82\x0521A00502A0', + b'\xf1\x875Q0909144L \xf1\x891021\xf1\x82\x0521A00602A0', + b'\xf1\x875Q0909144L \xf1\x891021\xf1\x82\x0522A00402A0', + b'\xf1\x875Q0909144P \xf1\x891043\xf1\x82\x0511A00403A0', + b'\xf1\x875Q0909144R \xf1\x891061\xf1\x82\x0516A00604A1', + b'\xf1\x875Q0909144S \xf1\x891063\xf1\x82\x0516A00404A1', + b'\xf1\x875Q0909144S \xf1\x891063\xf1\x82\x0516A00504A1', + b'\xf1\x875Q0909144S \xf1\x891063\xf1\x82\x0516A00604A1', + b'\xf1\x875Q0909144S \xf1\x891063\xf1\x82\x0516A07A02A1', + b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521A00407A1', + b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521A00507A1', + b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521A07B04A1', + b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521A20B03A1', + b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567A2000400', + b'\xf1\x875QD909144B \xf1\x891072\xf1\x82\x0521A00507A1', + b'\xf1\x875QM909144A \xf1\x891072\xf1\x82\x0521A20B03A1', + b'\xf1\x875QM909144B \xf1\x891081\xf1\x82\x0521A00442A1', + b'\xf1\x875QM909144B \xf1\x891081\xf1\x82\x0521A00642A1', + b'\xf1\x875QN909144A \xf1\x895081\xf1\x82\x0571A01A16A1', + b'\xf1\x875QN909144A \xf1\x895081\xf1\x82\x0571A01A17A1', + b'\xf1\x875QN909144A \xf1\x895081\xf1\x82\x0571A01A18A1', + b'\xf1\x875QN909144B \xf1\x895082\xf1\x82\x0571A01A18A1', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x875Q0907567G \xf1\x890390\xf1\x82\x0101', + b'\xf1\x875Q0907567J \xf1\x890396\xf1\x82\x0101', + b'\xf1\x875Q0907567L \xf1\x890098\xf1\x82\x0101', + b'\xf1\x875Q0907572A \xf1\x890141\xf1\x82\x0101', + b'\xf1\x875Q0907572B \xf1\x890200\xf1\x82\x0101', + b'\xf1\x875Q0907572C \xf1\x890210\xf1\x82\x0101', + b'\xf1\x875Q0907572D \xf1\x890304\xf1\x82\x0101', + b'\xf1\x875Q0907572E \xf1\x89X310\xf1\x82\x0101', + b'\xf1\x875Q0907572F \xf1\x890400\xf1\x82\x0101', + b'\xf1\x875Q0907572G \xf1\x890571', + b'\xf1\x875Q0907572H \xf1\x890620', + b'\xf1\x875Q0907572J \xf1\x890653', + b'\xf1\x875Q0907572J \xf1\x890654', + b'\xf1\x875Q0907572P \xf1\x890682', + b'\xf1\x875Q0907572R \xf1\x890771', + b'\xf1\x875Q0907572S \xf1\x890780', + ], + }, + CAR.VOLKSWAGEN_JETTA_MK7: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704E906024AK\xf1\x899937', + b'\xf1\x8704E906024AS\xf1\x899912', + b'\xf1\x8704E906024B \xf1\x895594', + b'\xf1\x8704E906024BC\xf1\x899971', + b'\xf1\x8704E906024BG\xf1\x891057', + b'\xf1\x8704E906024C \xf1\x899970', + b'\xf1\x8704E906024C \xf1\x899971', + b'\xf1\x8704E906024L \xf1\x895595', + b'\xf1\x8704E906024L \xf1\x899970', + b'\xf1\x8704E906027MS\xf1\x896223', + b'\xf1\x8705E906013DB\xf1\x893361', + b'\xf1\x875G0906259T \xf1\x890003', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x8709G927158BQ\xf1\x893545', + b'\xf1\x8709S927158BS\xf1\x893642', + b'\xf1\x8709S927158BS\xf1\x893694', + b'\xf1\x8709S927158CK\xf1\x893770', + b'\xf1\x8709S927158JC\xf1\x894113', + b'\xf1\x8709S927158R \xf1\x893552', + b'\xf1\x8709S927158R \xf1\x893587', + b'\xf1\x870GC300020N \xf1\x892803', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x875Q0959655AG\xf1\x890336\xf1\x82\x1314171231313500314611011630169333463100', + b'\xf1\x875Q0959655AG\xf1\x890338\xf1\x82\x1314171231313500314611011630169333463100', + b'\xf1\x875Q0959655BM\xf1\x890403\xf1\x82\x1314171231313500314642011650169333463100', + b'\xf1\x875Q0959655BM\xf1\x890403\xf1\x82\x1314171231313500314643011650169333463100', + b'\xf1\x875Q0959655BR\xf1\x890403\xf1\x82\x1311170031313300314240011150119333433100', + b'\xf1\x875Q0959655BR\xf1\x890403\xf1\x82\x1319170031313300314240011550159333463100', + b'\xf1\x875Q0959655CB\xf1\x890421\xf1\x82\x1314171231313500314642021650169333613100', + b'\xf1\x875Q0959655CB\xf1\x890421\xf1\x82\x1314171231313500314643021650169333613100', + b'\xf1\x875Q0959655CB\xf1\x890421\xf1\x82\x1317171231313500314642023050309333613100', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x873Q0909144M \xf1\x895082\xf1\x82\x0571A10A11A1', + b'\xf1\x875QM907144D \xf1\x891063\xf1\x82\x000_A1080_OM', + b'\xf1\x875QM909144B \xf1\x891081\xf1\x82\x0521A10A01A1', + b'\xf1\x875QM909144B \xf1\x891081\xf1\x82\x0521B00404A1', + b'\xf1\x875QM909144C \xf1\x891082\xf1\x82\x0521A00642A1', + b'\xf1\x875QM909144C \xf1\x891082\xf1\x82\x0521A10A01A1', + b'\xf1\x875QN909144B \xf1\x895082\xf1\x82\x0571A10A11A1', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572AA\xf1\x890396', + b'\xf1\x875Q0907572N \xf1\x890681', + b'\xf1\x875Q0907572P \xf1\x890682', + b'\xf1\x875Q0907572R \xf1\x890771', + ], + }, + CAR.VOLKSWAGEN_PASSAT_MK8: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8703N906026E \xf1\x892114', + b'\xf1\x8704E906023AH\xf1\x893379', + b'\xf1\x8704E906023BM\xf1\x894522', + b'\xf1\x8704L906026DP\xf1\x891538', + b'\xf1\x8704L906026ET\xf1\x891990', + b'\xf1\x8704L906026FP\xf1\x892012', + b'\xf1\x8704L906026GA\xf1\x892013', + b'\xf1\x8704L906026GK\xf1\x899971', + b'\xf1\x8704L906026KD\xf1\x894798', + b'\xf1\x8705L906022A \xf1\x890827', + b'\xf1\x873G0906259 \xf1\x890004', + b'\xf1\x873G0906259B \xf1\x890002', + b'\xf1\x873G0906264 \xf1\x890004', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870CW300041E \xf1\x891006', + b'\xf1\x870CW300042H \xf1\x891601', + b'\xf1\x870CW300042H \xf1\x891607', + b'\xf1\x870CW300043H \xf1\x891601', + b'\xf1\x870CW300048R \xf1\x890610', + b'\xf1\x870D9300013A \xf1\x894905', + b'\xf1\x870D9300014L \xf1\x895002', + b'\xf1\x870D9300018C \xf1\x895297', + b'\xf1\x870D9300041A \xf1\x894801', + b'\xf1\x870D9300042H \xf1\x894901', + b'\xf1\x870DD300045T \xf1\x891601', + b'\xf1\x870DD300046H \xf1\x891601', + b'\xf1\x870DL300011H \xf1\x895201', + b'\xf1\x870GC300042H \xf1\x891404', + b'\xf1\x870GC300043 \xf1\x892301', + b'\xf1\x870GC300046P \xf1\x892805', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x873Q0959655AE\xf1\x890195\xf1\x82\r56140056130012416612124111', + b'\xf1\x873Q0959655AF\xf1\x890195\xf1\x82\r56140056130012026612120211', + b'\xf1\x873Q0959655AN\xf1\x890305\xf1\x82\r58160058140013036914110311', + b'\xf1\x873Q0959655AN\xf1\x890306\xf1\x82\r58160058140013036914110311', + b'\xf1\x873Q0959655BA\xf1\x890195\xf1\x82\r56140056130012416612124111', + b'\xf1\x873Q0959655BA\xf1\x890195\xf1\x82\r56140056130012516612125111', + b'\xf1\x873Q0959655BB\xf1\x890195\xf1\x82\r56140056130012026612120211', + b'\xf1\x873Q0959655BG\xf1\x890712\xf1\x82\x0e5915005914001305701311052900', + b'\xf1\x873Q0959655BJ\xf1\x890703\xf1\x82\x0e5915005914001305701311052900', + b'\xf1\x873Q0959655BK\xf1\x890703\xf1\x82\x0e5915005914001344701311442900', + b'\xf1\x873Q0959655BK\xf1\x890703\xf1\x82\x0e5915005914001354701311542900', + b'\xf1\x873Q0959655CN\xf1\x890720\xf1\x82\x0e5915005914001305701311052900', + b'\xf1\x875Q0959655S \xf1\x890870\xf1\x82\x1315120011111200631145171716121691132111', + b'\xf1\x875QF959655S \xf1\x890639\xf1\x82\x13131100131300111111000120----2211114A48', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566B00611A1', + b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566B00711A1', + b'\xf1\x875Q0909143K \xf1\x892033\xf1\x820514B0060703', + b'\xf1\x875Q0909143M \xf1\x892041\xf1\x820522B0060803', + b'\xf1\x875Q0909143M \xf1\x892041\xf1\x820522B0080803', + b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820526B0060905', + b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820531B0062105', + b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521B00606A1', + b'\xf1\x875Q0909144S \xf1\x891063\xf1\x82\x0516B00501A1', + b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521B00603A1', + b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521B00703A1', + b'\xf1\x875Q0910143B \xf1\x892201\xf1\x82\x0563B0000600', + b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567B0020600', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x873Q0907572A \xf1\x890126', + b'\xf1\x873Q0907572A \xf1\x890130', + b'\xf1\x873Q0907572B \xf1\x890192', + b'\xf1\x873Q0907572B \xf1\x890194', + b'\xf1\x873Q0907572C \xf1\x890195', + b'\xf1\x873Q0907572C \xf1\x890196', + b'\xf1\x875Q0907572P \xf1\x890682', + b'\xf1\x875Q0907572R \xf1\x890771', + b'\xf1\x875Q0907572S \xf1\x890780', + ], + }, + CAR.VOLKSWAGEN_PASSAT_NMS: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8706K906016C \xf1\x899609', + b'\xf1\x8706K906016E \xf1\x899830', + b'\xf1\x8706K906016G \xf1\x891124', + b'\xf1\x8706K906071BJ\xf1\x894891', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x8709G927158AB\xf1\x893318', + b'\xf1\x8709G927158BD\xf1\x893121', + b'\xf1\x8709G927158DK\xf1\x893594', + b'\xf1\x8709G927158FQ\xf1\x893745', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x87561959655 \xf1\x890210\xf1\x82\x1212121111113000102011--121012--101312', + b'\xf1\x87561959655C \xf1\x890508\xf1\x82\x1215141111121100314919--153015--304831', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x87561907567A \xf1\x890132', + b'\xf1\x877N0907572C \xf1\x890211\xf1\x82\x0152', + ], + }, + CAR.VOLKSWAGEN_POLO_MK6: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704C906025H \xf1\x895177', + b'\xf1\x8705C906032J \xf1\x891702', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870CW300042D \xf1\x891612', + b'\xf1\x870CW300050D \xf1\x891908', + b'\xf1\x870CW300051G \xf1\x891909', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x872Q0959655AG\xf1\x890248\xf1\x82\x1218130411110411--04040404231811152H14', + b'\xf1\x872Q0959655AJ\xf1\x890250\xf1\x82\x1248130411110416--04040404784811152H14', + b'\xf1\x872Q0959655AS\xf1\x890411\xf1\x82\x1384830511110516041405820599841215391471', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x872Q1909144M \xf1\x896041', + b'\xf1\x872Q2909144AB\xf1\x896050', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572AA\xf1\x890396', + b'\xf1\x872Q0907572R \xf1\x890372', + ], + }, + CAR.VOLKSWAGEN_SHARAN_MK2: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704L906016HE\xf1\x894635', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x877N0959655D \xf1\x890016\xf1\x82\x0801100705----10--', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x877N0907572C \xf1\x890211\xf1\x82\x0153', + ], + }, + CAR.VOLKSWAGEN_TAOS_MK1: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704E906025CK\xf1\x892228', + b'\xf1\x8704E906027NJ\xf1\x891445', + b'\xf1\x8704E906027NP\xf1\x891286', + b'\xf1\x8705E906013BD\xf1\x892496', + b'\xf1\x8705E906013E \xf1\x891624', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x8709G927158EM\xf1\x893812', + b'\xf1\x8709S927158BL\xf1\x893791', + b'\xf1\x8709S927158CR\xf1\x893924', + b'\xf1\x8709S927158DN\xf1\x893946', + b'\xf1\x8709S927158FF\xf1\x893876', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x875Q0959655CB\xf1\x890421\xf1\x82\x1311111111333500314646021450149333613100', + b'\xf1\x875Q0959655CB\xf1\x890421\xf1\x82\x1312111111333500314646021550159333613100', + b'\xf1\x875Q0959655CE\xf1\x890421\xf1\x82\x1311110011333300314240021350139333613100', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x875QM907144D \xf1\x891063\xf1\x82\x001O06081OOM', + b'\xf1\x875QM909144C \xf1\x891082\xf1\x82\x0521060405A1', + b'\xf1\x875QM909144C \xf1\x891082\xf1\x82\x0521060605A1', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572AA\xf1\x890396', + b'\xf1\x872Q0907572T \xf1\x890383', + ], + }, + CAR.VOLKSWAGEN_TCROSS_MK1: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704C906025AK\xf1\x897053', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870CW300050E \xf1\x891903', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x872Q0959655AJ\xf1\x890250\xf1\x82\x1212130411110411--04041104141311152H14', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x872Q1909144M \xf1\x896041', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572T \xf1\x890383', + ], + }, + CAR.VOLKSWAGEN_TIGUAN_MK2: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8703N906026D \xf1\x893680', + b'\xf1\x8704E906024AP\xf1\x891461', + b'\xf1\x8704E906027NB\xf1\x899504', + b'\xf1\x8704L906026EJ\xf1\x893661', + b'\xf1\x8704L906027G \xf1\x899893', + b'\xf1\x8705E906018BS\xf1\x890914', + b'\xf1\x875N0906259 \xf1\x890002', + b'\xf1\x875NA906259H \xf1\x890002', + b'\xf1\x875NA907115E \xf1\x890003', + b'\xf1\x875NA907115E \xf1\x890005', + b'\xf1\x875NA907115J \xf1\x890002', + b'\xf1\x875NA907115K \xf1\x890004', + b'\xf1\x8783A907115 \xf1\x890007', + b'\xf1\x8783A907115B \xf1\x890005', + b'\xf1\x8783A907115F \xf1\x890002', + b'\xf1\x8783A907115G \xf1\x890001', + b'\xf1\x8783A907115K \xf1\x890001', + b'\xf1\x8783A907115K \xf1\x890002', + b'\xf1\x8783A907115Q \xf1\x890001', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x8709G927158DT\xf1\x893698', + b'\xf1\x8709G927158FM\xf1\x893757', + b'\xf1\x8709G927158GC\xf1\x893821', + b'\xf1\x8709G927158GD\xf1\x893820', + b'\xf1\x8709G927158GM\xf1\x893936', + b'\xf1\x8709G927158GN\xf1\x893938', + b'\xf1\x8709G927158HB\xf1\x894069', + b'\xf1\x8709G927158HC\xf1\x894070', + b'\xf1\x870D9300043 \xf1\x895202', + b'\xf1\x870DD300046K \xf1\x892302', + b'\xf1\x870DL300011N \xf1\x892001', + b'\xf1\x870DL300011N \xf1\x892012', + b'\xf1\x870DL300012M \xf1\x892107', + b'\xf1\x870DL300012P \xf1\x892103', + b'\xf1\x870DL300013A \xf1\x893005', + b'\xf1\x870DL300013G \xf1\x892119', + b'\xf1\x870DL300013G \xf1\x892120', + b'\xf1\x870DL300014C \xf1\x893703', + b'\xf1\x870GC300013P \xf1\x892401', + b'\xf1\x870GC300046Q \xf1\x892802', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x875Q0959655AG\xf1\x890336\xf1\x82\x1316143231313500314617011730179333423100', + b'\xf1\x875Q0959655AG\xf1\x890338\xf1\x82\x1316143231313500314617011730179333423100', + b'\xf1\x875Q0959655AR\xf1\x890317\xf1\x82\x1331310031333334313132573732379333313100', + b'\xf1\x875Q0959655BJ\xf1\x890336\xf1\x82\x1312110031333300314232583732379333423100', + b'\xf1\x875Q0959655BJ\xf1\x890339\xf1\x82\x1331310031333334313132013730379333423100', + b'\xf1\x875Q0959655BM\xf1\x890403\xf1\x82\x1316143231313500314641011750179333423100', + b'\xf1\x875Q0959655BS\xf1\x890403\xf1\x82\x1312110031333300314240013750379333423100', + b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x1312110031333300314240583752379333423100', + b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x1331310031333334313140013750379333423100', + b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x1331310031333334313140573752379333423100', + b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x1331310031333336313140013950399333423100', + b'\xf1\x875Q0959655CB\xf1\x890421\xf1\x82\x1316143231313500314647021750179333613100', + b'\xf1\x875Q0959655CD\xf1\x890421\xf1\x82\x13123112313333003145406F6154619333613100', + b'\xf1\x875Q0959655CG\xf1\x890421\xf1\x82\x1331310031333300314240024050409333613100', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x875Q0909143M \xf1\x892041\xf1\x820529A6060603', + b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820527A6050705', + b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820527A6070705', + b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521A60604A1', + b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567A6000600', + b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567A6017A00', + b'\xf1\x875QF909144A \xf1\x895581\xf1\x82\x0571A60834A1', + b'\xf1\x875QF909144B \xf1\x895582\xf1\x82\x0571A60634A1', + b'\xf1\x875QF909144B \xf1\x895582\xf1\x82\x0571A62A32A1', + b'\xf1\x875QM907144D \xf1\x891063\xf1\x82\x002RA60A2ROM', + b'\xf1\x875QM907144D \xf1\x891063\xf1\x82\x002SA6092SOM', + b'\xf1\x875QM909144B \xf1\x891081\xf1\x82\x0521A60604A1', + b'\xf1\x875QM909144B \xf1\x891081\xf1\x82\x0521A60804A1', + b'\xf1\x875QM909144C \xf1\x891082\xf1\x82\x0521A60604A1', + b'\xf1\x875QM909144C \xf1\x891082\xf1\x82\x0521A60804A1', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572AA\xf1\x890396', + b'\xf1\x872Q0907572AB\xf1\x890397', + b'\xf1\x872Q0907572J \xf1\x890156', + b'\xf1\x872Q0907572M \xf1\x890233', + b'\xf1\x872Q0907572Q \xf1\x890342', + b'\xf1\x872Q0907572R \xf1\x890372', + b'\xf1\x872Q0907572T \xf1\x890383', + ], + }, + CAR.VOLKSWAGEN_TOURAN_MK2: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704E906025BE\xf1\x890720', + b'\xf1\x8704E906027HQ\xf1\x893746', + b'\xf1\x8704L906026HM\xf1\x893017', + b'\xf1\x8705E906018CQ\xf1\x890808', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870CW300020A \xf1\x891936', + b'\xf1\x870CW300041E \xf1\x891005', + b'\xf1\x870CW300041Q \xf1\x891606', + b'\xf1\x870CW300051M \xf1\x891926', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x875Q0959655AS\xf1\x890318\xf1\x82\x1336350021353335314132014730479333313100', + b'\xf1\x875Q0959655AS\xf1\x890318\xf1\x82\x13363500213533353141324C4732479333313100', + b'\xf1\x875Q0959655CH\xf1\x890421\xf1\x82\x1336350021353336314740025250529333613100', + b'\xf1\x875QD959655AJ\xf1\x890421\xf1\x82\x1336350021313300314240023330339333663100', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820531B0062105', + b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567A8090400', + b'\xf1\x875QD909144F \xf1\x891082\xf1\x82\x0521A00642A1', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572AA\xf1\x890396', + b'\xf1\x873Q0907572C \xf1\x890195', + b'\xf1\x875Q0907572R \xf1\x890771', + ], + }, + CAR.VOLKSWAGEN_TRANSPORTER_T61: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704L906056AG\xf1\x899970', + b'\xf1\x8704L906056AL\xf1\x899970', + b'\xf1\x8704L906057AP\xf1\x891186', + b'\xf1\x8704L906057N \xf1\x890413', + b'\xf1\x8705L906023E \xf1\x891352', + b'\xf1\x8705L906023MR\xf1\x892582', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870BT300012E \xf1\x893105', + b'\xf1\x870BT300012G \xf1\x893102', + b'\xf1\x870BT300046R \xf1\x893102', + b'\xf1\x870DV300012B \xf1\x893701', + b'\xf1\x870DV300012B \xf1\x893702', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x872Q0959655AE\xf1\x890506\xf1\x82\x1316170411110411--04041704161611152S1411', + b'\xf1\x872Q0959655AE\xf1\x890506\xf1\x82\x1316170411110411--04041704171711152S1411', + b'\xf1\x872Q0959655AF\xf1\x890506\xf1\x82\x1316171111110411--04041711121211152S1413', + b'\xf1\x872Q0959655AQ\xf1\x890511\xf1\x82\x1316170411110411--0404170426261215391421', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x877LA909144F \xf1\x897150\xf1\x82\x0532380518A2', + b'\xf1\x877LA909144F \xf1\x897150\xf1\x82\x05323A5519A2', + b'\xf1\x877LA909144G \xf1\x897160\xf1\x82\x05333A5519A2', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572AA\xf1\x890396', + b'\xf1\x872Q0907572R \xf1\x890372', + ], + }, + CAR.VOLKSWAGEN_TROC_MK1: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8705E906018AT\xf1\x899640', + b'\xf1\x8705E906018CK\xf1\x890863', + b'\xf1\x8705E906018P \xf1\x896020', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870CW300041S \xf1\x891615', + b'\xf1\x870CW300050J \xf1\x891911', + b'\xf1\x870CW300051M \xf1\x891925', + b'\xf1\x870CW300051M \xf1\x891928', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x873Q0959655BH\xf1\x890712\xf1\x82\x0e1111001111001105111111052900', + b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x1311110012333300314240681152119333463100', + b'\xf1\x875Q0959655CF\xf1\x890421\xf1\x82\x1311110012333300314240021150119333613100', + b'\xf1\x875Q0959655CG\xf1\x890421\xf1\x82\x13111100123333003142404M1152119333613100', + b'\xf1\x875Q0959655CG\xf1\x890421\xf1\x82\x13111100123333003142404M1154119333613100', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x875Q0909144AA\xf1\x891081\xf1\x82\x0521060403A1', + b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521060405A1', + b'\xf1\x875WA907144M \xf1\x891051\xf1\x82\x001T06081T7N', + b'\xf1\x875WA907144Q \xf1\x891063\xf1\x82\x001O06081OOM', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572AA\xf1\x890396', + b'\xf1\x872Q0907572M \xf1\x890233', + b'\xf1\x872Q0907572T \xf1\x890383', + ], + }, + CAR.AUDI_A3_MK3: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704E906023AN\xf1\x893695', + b'\xf1\x8704E906023AR\xf1\x893440', + b'\xf1\x8704E906023BL\xf1\x895190', + b'\xf1\x8704E906027CJ\xf1\x897798', + b'\xf1\x8704L997022N \xf1\x899459', + b'\xf1\x875G0906259A \xf1\x890004', + b'\xf1\x875G0906259D \xf1\x890002', + b'\xf1\x875G0906259L \xf1\x890002', + b'\xf1\x875G0906259Q \xf1\x890002', + b'\xf1\x878V0906259E \xf1\x890001', + b'\xf1\x878V0906259F \xf1\x890002', + b'\xf1\x878V0906259H \xf1\x890002', + b'\xf1\x878V0906259J \xf1\x890002', + b'\xf1\x878V0906259K \xf1\x890001', + b'\xf1\x878V0906264B \xf1\x890003', + b'\xf1\x878V0907115B \xf1\x890007', + b'\xf1\x878V0907404A \xf1\x890005', + b'\xf1\x878V0907404G \xf1\x890005', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870CW300044T \xf1\x895245', + b'\xf1\x870CW300048 \xf1\x895201', + b'\xf1\x870D9300012 \xf1\x894912', + b'\xf1\x870D9300012 \xf1\x894931', + b'\xf1\x870D9300012K \xf1\x894513', + b'\xf1\x870D9300012L \xf1\x894521', + b'\xf1\x870D9300013B \xf1\x894902', + b'\xf1\x870D9300013B \xf1\x894931', + b'\xf1\x870D9300041N \xf1\x894512', + b'\xf1\x870D9300043T \xf1\x899699', + b'\xf1\x870DD300046 \xf1\x891604', + b'\xf1\x870DD300046A \xf1\x891602', + b'\xf1\x870DD300046F \xf1\x891602', + b'\xf1\x870DD300046G \xf1\x891601', + b'\xf1\x870DL300012E \xf1\x892012', + b'\xf1\x870DL300012H \xf1\x892112', + b'\xf1\x870GC300011 \xf1\x890403', + b'\xf1\x870GC300013M \xf1\x892402', + b'\xf1\x870GC300042J \xf1\x891402', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x875Q0959655AB\xf1\x890388\xf1\x82\x111111001111111206110412111321139114', + b'\xf1\x875Q0959655AM\xf1\x890315\xf1\x82\x1311111111111111311411011231129321212100', + b'\xf1\x875Q0959655AM\xf1\x890318\xf1\x82\x1311111111111112311411011531159321212100', + b'\xf1\x875Q0959655AR\xf1\x890315\xf1\x82\x1311110011131115311211012331239321212100', + b'\xf1\x875Q0959655BJ\xf1\x890339\xf1\x82\x1311110011131100311111011731179321342100', + b'\xf1\x875Q0959655J \xf1\x890825\xf1\x82\x13111112111111--171115141112221291163221', + b'\xf1\x875Q0959655J \xf1\x890825\xf1\x82\x13111112111111--241115141112221291163221', + b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13111112111111--241115141112221291163221', + b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13121111111111--341117141212231291163221', + b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13121111111211--261117141112231291163221', + b'\xf1\x875Q0959655N \xf1\x890361\xf1\x82\x111212001112110004110411111421149114', + b'\xf1\x875Q0959655N \xf1\x890361\xf1\x82\x111212001112111104110411111521159114', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x873Q0909144F \xf1\x895043\xf1\x82\x0561G01A13A0', + b'\xf1\x873Q0909144H \xf1\x895061\xf1\x82\x0566G0HA14A1', + b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566G0HA14A1', + b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571G01A16A1', + b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571G0HA16A1', + b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571G0JA13A1', + b'\xf1\x873Q0909144L \xf1\x895081\xf1\x82\x0571G0JA14A1', + b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521G0G809A1', + b'\xf1\x875Q0909144P \xf1\x891043\xf1\x82\x0503G00303A0', + b'\xf1\x875Q0909144P \xf1\x891043\xf1\x82\x0503G00803A0', + b'\xf1\x875Q0909144P \xf1\x891043\xf1\x82\x0503G0G803A0', + b'\xf1\x875Q0909144R \xf1\x891061\xf1\x82\x0516G00804A1', + b'\xf1\x875Q0909144S \xf1\x891063\xf1\x82\x0516G00804A1', + b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521G00807A1', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x875Q0907567M \xf1\x890398\xf1\x82\x0101', + b'\xf1\x875Q0907567N \xf1\x890400\xf1\x82\x0101', + b'\xf1\x875Q0907572D \xf1\x890304\xf1\x82\x0101', + b'\xf1\x875Q0907572F \xf1\x890400\xf1\x82\x0101', + b'\xf1\x875Q0907572G \xf1\x890571', + b'\xf1\x875Q0907572H \xf1\x890620', + b'\xf1\x875Q0907572P \xf1\x890682', + ], + }, + CAR.AUDI_Q2_MK1: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704E906027JT\xf1\x894145', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870CW300041F \xf1\x891006', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x875Q0959655BD\xf1\x890336\xf1\x82\x1311111111111100311211011231129321312111', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571F60511A1', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572M \xf1\x890233', + ], + }, + CAR.AUDI_Q3_MK2: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8705E906018N \xf1\x899970', + b'\xf1\x8705L906022M \xf1\x890901', + b'\xf1\x8783A906259 \xf1\x890001', + b'\xf1\x8783A906259 \xf1\x890005', + b'\xf1\x8783A906259C \xf1\x890002', + b'\xf1\x8783A906259D \xf1\x890001', + b'\xf1\x8783A906259F \xf1\x890001', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x8709G927158CN\xf1\x893608', + b'\xf1\x8709G927158FL\xf1\x893758', + b'\xf1\x8709G927158GG\xf1\x893825', + b'\xf1\x8709G927158GP\xf1\x893937', + b'\xf1\x870GC300045D \xf1\x892802', + b'\xf1\x870GC300046F \xf1\x892701', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x875Q0959655BF\xf1\x890403\xf1\x82\x1321211111211200311121232152219321422111', + b'\xf1\x875Q0959655BQ\xf1\x890421\xf1\x82\x132121111121120031112124218A219321532111', + b'\xf1\x875Q0959655BQ\xf1\x890421\xf1\x82\x132121111121120031112124218C219321532111', + b'\xf1\x875Q0959655CC\xf1\x890421\xf1\x82\x131111111111120031111224118A119321532111', + b'\xf1\x875Q0959655CC\xf1\x890421\xf1\x82\x131111111111120031111237116A119321532111', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567G6000300', + b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567G6000800', + b'\xf1\x875QF909144B \xf1\x895582\xf1\x82\x0571G60533A1', + b'\xf1\x875QF909144B \xf1\x895582\xf1\x82\x0571G60733A1', + b'\xf1\x875TA907145D \xf1\x891051\xf1\x82\x001PG60A1P7N', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572AA\xf1\x890396', + b'\xf1\x872Q0907572R \xf1\x890372', + b'\xf1\x872Q0907572T \xf1\x890383', + ], + }, + CAR.SEAT_ATECA_MK1: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704E906027KA\xf1\x893749', + b'\xf1\x8704L906021EL\xf1\x897542', + b'\xf1\x8704L906026BP\xf1\x891198', + b'\xf1\x8704L906026BP\xf1\x897608', + b'\xf1\x8704L906056CR\xf1\x892181', + b'\xf1\x8704L906056CR\xf1\x892797', + b'\xf1\x8705E906018AS\xf1\x899596', + b'\xf1\x8781A906259B \xf1\x890003', + b'\xf1\x878V0906264H \xf1\x890005', + b'\xf1\x878V0907115E \xf1\x890002', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870CW300041D \xf1\x891004', + b'\xf1\x870CW300041G \xf1\x891003', + b'\xf1\x870CW300050J \xf1\x891908', + b'\xf1\x870D9300014S \xf1\x895202', + b'\xf1\x870D9300042M \xf1\x895016', + b'\xf1\x870GC300014P \xf1\x892801', + b'\xf1\x870GC300043A \xf1\x892304', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x873Q0959655AC\xf1\x890189\xf1\x82\r11110011110011021511110200', + b'\xf1\x873Q0959655AS\xf1\x890200\xf1\x82\r11110011110011021511110200', + b'\xf1\x873Q0959655AS\xf1\x890200\xf1\x82\r12110012120012021612110200', + b'\xf1\x873Q0959655BH\xf1\x890703\xf1\x82\x0e1212001211001305121211052900', + b'\xf1\x873Q0959655BH\xf1\x890703\xf1\x82\x0e1312001313001305171311052900', + b'\xf1\x873Q0959655BH\xf1\x890712\xf1\x82\x0e1312001313001305171311052900', + b'\xf1\x873Q0959655CM\xf1\x890720\xf1\x82\x0e1312001313001305171311052900', + b'\xf1\x875QF959655AT\xf1\x890755\xf1\x82\x1311110011110011111100110200--1113121149', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x873Q0909144L \xf1\x895081\xf1\x82\x0571N60511A1', + b'\xf1\x875Q0909144AA\xf1\x891081\xf1\x82\x0521N01842A1', + b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521N01342A1', + b'\xf1\x875Q0909144P \xf1\x891043\xf1\x82\x0511N01805A0', + b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521N01309A1', + b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521N05808A1', + b'\xf1\x875WA907145M \xf1\x891051\xf1\x82\x0013N619137N', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572AA\xf1\x890396', + b'\xf1\x872Q0907572M \xf1\x890233', + b'\xf1\x875Q0907572B \xf1\x890200\xf1\x82\x0101', + b'\xf1\x875Q0907572H \xf1\x890620', + b'\xf1\x875Q0907572K \xf1\x890402\xf1\x82\x0101', + b'\xf1\x875Q0907572P \xf1\x890682', + b'\xf1\x875Q0907572R \xf1\x890771', + ], + }, + CAR.SKODA_FABIA_MK4: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8705E906018CF\xf1\x891905', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870CW300051M \xf1\x891936', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x875QF959655AT\xf1\x890755\xf1\x82\x1311110011110011111100110200--1111120749', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x872Q1909144S \xf1\x896042', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572AA\xf1\x890396', + ], + }, + CAR.SKODA_KAMIQ_MK1: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704C906025AK\xf1\x897053', + b'\xf1\x8705C906032M \xf1\x891333', + b'\xf1\x8705C906032M \xf1\x892365', + b'\xf1\x8705E906013CK\xf1\x892540', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870CW300020 \xf1\x891906', + b'\xf1\x870CW300020 \xf1\x891907', + b'\xf1\x870CW300020T \xf1\x892204', + b'\xf1\x870CW300050 \xf1\x891709', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x872Q0959655AJ\xf1\x890250\xf1\x82\x1211110411110411--04040404131111112H14', + b'\xf1\x872Q0959655AM\xf1\x890351\xf1\x82\x12111104111104112104040404111111112H14', + b'\xf1\x872Q0959655AM\xf1\x890351\xf1\x82\x122221042111042121040404042E2711152H14', + b'\xf1\x872Q0959655AS\xf1\x890411\xf1\x82\x1311150411110411210404040417151215391413', + b'\xf1\x872Q0959655BJ\xf1\x890412\xf1\x82\x132223042111042121040404042B251215391423', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x872Q1909144AB\xf1\x896050', + b'\xf1\x872Q1909144M \xf1\x896041', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572AA\xf1\x890396', + b'\xf1\x872Q0907572R \xf1\x890372', + b'\xf1\x872Q0907572T \xf1\x890383', + ], + }, + CAR.SKODA_KAROQ_MK1: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8705E906013CL\xf1\x892541', + b'\xf1\x8705E906013H \xf1\x892407', + b'\xf1\x8705E906018P \xf1\x895472', + b'\xf1\x8705E906018P \xf1\x896020', + b'\xf1\x8705L906022BS\xf1\x890913', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870CW300020T \xf1\x892202', + b'\xf1\x870CW300041S \xf1\x891615', + b'\xf1\x870GC300014L \xf1\x892802', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x873Q0959655BH\xf1\x890703\xf1\x82\x0e1213001211001101131112012100', + b'\xf1\x873Q0959655BH\xf1\x890712\xf1\x82\x0e1213001211001101131122012100', + b'\xf1\x873Q0959655DE\xf1\x890731\xf1\x82\x0e1213001211001101131121012J00', + b'\xf1\x875QF959655AT\xf1\x890755\xf1\x82\x1312110012120011111100010200--2521210749', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x875Q0910143B \xf1\x892201\xf1\x82\x0563T6090500', + b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567T6100500', + b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567T6100600', + b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567T6100700', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572AA\xf1\x890396', + b'\xf1\x872Q0907572AB\xf1\x890397', + b'\xf1\x872Q0907572M \xf1\x890233', + b'\xf1\x872Q0907572T \xf1\x890383', + ], + }, + CAR.SKODA_KODIAQ_MK1: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704E906027DD\xf1\x893123', + b'\xf1\x8704E906027LD\xf1\x893433', + b'\xf1\x8704E906027NB\xf1\x896517', + b'\xf1\x8704E906027NB\xf1\x899504', + b'\xf1\x8704L906026DE\xf1\x895418', + b'\xf1\x8704L906026EJ\xf1\x893661', + b'\xf1\x8704L906026HT\xf1\x893617', + b'\xf1\x8705E906018DJ\xf1\x890915', + b'\xf1\x8705E906018DJ\xf1\x891903', + b'\xf1\x8705L906022GM\xf1\x893411', + b'\xf1\x875NA906259E \xf1\x890003', + b'\xf1\x875NA907115D \xf1\x890003', + b'\xf1\x875NA907115E \xf1\x890003', + b'\xf1\x875NA907115E \xf1\x890005', + b'\xf1\x8783A907115E \xf1\x890001', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870D9300014S \xf1\x895201', + b'\xf1\x870D9300043 \xf1\x895202', + b'\xf1\x870DL300011N \xf1\x892014', + b'\xf1\x870DL300012G \xf1\x892006', + b'\xf1\x870DL300012M \xf1\x892107', + b'\xf1\x870DL300012N \xf1\x892110', + b'\xf1\x870DL300013G \xf1\x892119', + b'\xf1\x870GC300014N \xf1\x892801', + b'\xf1\x870GC300018S \xf1\x892803', + b'\xf1\x870GC300019H \xf1\x892806', + b'\xf1\x870GC300046Q \xf1\x892802', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x873Q0959655AN\xf1\x890306\xf1\x82\r11110011110011031111310311', + b'\xf1\x873Q0959655AP\xf1\x890306\xf1\x82\r11110011110011421111314211', + b'\xf1\x873Q0959655BH\xf1\x890703\xf1\x82\x0e1213001211001205212111052100', + b'\xf1\x873Q0959655BJ\xf1\x890703\xf1\x82\x0e1213001211001205212111052100', + b'\xf1\x873Q0959655BK\xf1\x890703\xf1\x82\x0e1213001211001244212111442100', + b'\xf1\x873Q0959655CN\xf1\x890720\xf1\x82\x0e1213001211001205212112052100', + b'\xf1\x873Q0959655CQ\xf1\x890720\xf1\x82\x0e1213111211001205212112052111', + b'\xf1\x873Q0959655DJ\xf1\x890731\xf1\x82\x0e1513001511001205232113052J00', + b'\xf1\x875QF959655AT\xf1\x890755\xf1\x82\x1311110011110011111100010200--1121240749', + b'\xf1\x875QF959655AT\xf1\x890755\xf1\x82\x1311110011110011111100010200--1121246149', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820527T6050405', + b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820527T6060405', + b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820527T6070405', + b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567T600G500', + b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567T600G600', + b'\xf1\x875TA907145F \xf1\x891063\xf1\x82\x0025T6BA25OM', + b'\xf1\x875TA907145F \xf1\x891063\xf1\x82\x002LT61A2LOM', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572AA\xf1\x890396', + b'\xf1\x872Q0907572AB\xf1\x890397', + b'\xf1\x872Q0907572M \xf1\x890233', + b'\xf1\x872Q0907572Q \xf1\x890342', + b'\xf1\x872Q0907572R \xf1\x890372', + b'\xf1\x872Q0907572T \xf1\x890383', + ], + }, + CAR.SKODA_OCTAVIA_MK3: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704C906025L \xf1\x896198', + b'\xf1\x8704E906016ER\xf1\x895823', + b'\xf1\x8704E906027HD\xf1\x893742', + b'\xf1\x8704E906027MH\xf1\x894786', + b'\xf1\x8704L906021DT\xf1\x898127', + b'\xf1\x8704L906021ER\xf1\x898361', + b'\xf1\x8704L906026BP\xf1\x897608', + b'\xf1\x8704L906026BS\xf1\x891541', + b'\xf1\x8704L906026BT\xf1\x897612', + b'\xf1\x875G0906259C \xf1\x890002', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870CW300041L \xf1\x891601', + b'\xf1\x870CW300041N \xf1\x891605', + b'\xf1\x870CW300043B \xf1\x891601', + b'\xf1\x870CW300043P \xf1\x891605', + b'\xf1\x870D9300012H \xf1\x894518', + b'\xf1\x870D9300014T \xf1\x895221', + b'\xf1\x870D9300041C \xf1\x894936', + b'\xf1\x870D9300041H \xf1\x895220', + b'\xf1\x870D9300041J \xf1\x894902', + b'\xf1\x870D9300041P \xf1\x894507', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x873Q0959655AC\xf1\x890200\xf1\x82\r11120011100010022212110200', + b'\xf1\x873Q0959655AK\xf1\x890306\xf1\x82\r31210031210021033733310331', + b'\xf1\x873Q0959655AP\xf1\x890305\xf1\x82\r11110011110011213331312131', + b'\xf1\x873Q0959655AQ\xf1\x890200\xf1\x82\r11120011100010312212113100', + b'\xf1\x873Q0959655AS\xf1\x890200\xf1\x82\r11120011100010022212110200', + b'\xf1\x873Q0959655BH\xf1\x890703\xf1\x82\x0e3221003221002105755331052100', + b'\xf1\x873Q0959655CM\xf1\x890720\xf1\x82\x0e3221003221002105755331052100', + b'\xf1\x873Q0959655CN\xf1\x890720\xf1\x82\x0e3221003221002105755331052100', + b'\xf1\x875QD959655 \xf1\x890388\xf1\x82\x111101000011110006110411111111119111', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566A01513A1', + b'\xf1\x875Q0909144AA\xf1\x891081\xf1\x82\x0521T00403A1', + b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521T00403A1', + b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521T00603A1', + b'\xf1\x875Q0909144R \xf1\x891061\xf1\x82\x0516A00604A1', + b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521T00601A1', + b'\xf1\x875QD909144E \xf1\x891081\xf1\x82\x0521T00503A1', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x875Q0907567P \xf1\x890100\xf1\x82\x0101', + b'\xf1\x875Q0907572D \xf1\x890304\xf1\x82\x0101', + b'\xf1\x875Q0907572F \xf1\x890400\xf1\x82\x0101', + b'\xf1\x875Q0907572H \xf1\x890620', + b'\xf1\x875Q0907572J \xf1\x890654', + b'\xf1\x875Q0907572K \xf1\x890402\xf1\x82\x0101', + b'\xf1\x875Q0907572P \xf1\x890682', + b'\xf1\x875Q0907572R \xf1\x890771', + ], + }, + CAR.SKODA_SUPERB_MK3: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704E906027BS\xf1\x892887', + b'\xf1\x8704E906027BT\xf1\x899042', + b'\xf1\x8704L906026ET\xf1\x891343', + b'\xf1\x8704L906026ET\xf1\x891990', + b'\xf1\x8704L906026FP\xf1\x891196', + b'\xf1\x8704L906026KA\xf1\x896014', + b'\xf1\x8704L906026KB\xf1\x894071', + b'\xf1\x8704L906026KD\xf1\x894798', + b'\xf1\x8704L906026MT\xf1\x893076', + b'\xf1\x8705L906022BK\xf1\x899971', + b'\xf1\x873G0906259 \xf1\x890004', + b'\xf1\x873G0906259B \xf1\x890002', + b'\xf1\x873G0906259L \xf1\x890003', + b'\xf1\x873G0906264A \xf1\x890002', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x870CW300042H \xf1\x891601', + b'\xf1\x870CW300043B \xf1\x891603', + b'\xf1\x870CW300049Q \xf1\x890906', + b'\xf1\x870D9300011T \xf1\x894801', + b'\xf1\x870D9300012 \xf1\x894940', + b'\xf1\x870D9300013A \xf1\x894905', + b'\xf1\x870D9300014K \xf1\x895006', + b'\xf1\x870D9300041H \xf1\x894905', + b'\xf1\x870D9300042M \xf1\x895013', + b'\xf1\x870D9300043F \xf1\x895202', + b'\xf1\x870GC300013K \xf1\x892403', + b'\xf1\x870GC300014M \xf1\x892801', + b'\xf1\x870GC300019G \xf1\x892803', + b'\xf1\x870GC300043 \xf1\x892301', + b'\xf1\x870GC300046D \xf1\x892402', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x875Q0959655AE\xf1\x890130\xf1\x82\x12111200111121001121110012211292221111', + b'\xf1\x875Q0959655AE\xf1\x890130\xf1\x82\x12111200111121001121118112231292221111', + b'\xf1\x875Q0959655AK\xf1\x890130\xf1\x82\x12111200111121001121110012211292221111', + b'\xf1\x875Q0959655AS\xf1\x890317\xf1\x82\x1331310031313100313131823133319331313100', + b'\xf1\x875Q0959655AT\xf1\x890317\xf1\x82\x1331310031313100313131013131319331313100', + b'\xf1\x875Q0959655BH\xf1\x890336\xf1\x82\x1331310031313100313131013141319331413100', + b'\xf1\x875Q0959655BK\xf1\x890336\xf1\x82\x1331310031313100313131013141319331413100', + b'\xf1\x875Q0959655BS\xf1\x890403\xf1\x82\x1333310031313100313152015351539331423100', + b'\xf1\x875Q0959655CA\xf1\x890403\xf1\x82\x1331310031313100313151013141319331423100', + b'\xf1\x875Q0959655CA\xf1\x890403\xf1\x82\x1331310031313100313151823143319331423100', + b'\xf1\x875Q0959655CH\xf1\x890421\xf1\x82\x1333310031313100313152025350539331463100', + b'\xf1\x875Q0959655CH\xf1\x890421\xf1\x82\x1333310031313100313152855372539331463100', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x875Q0909143K \xf1\x892033\xf1\x820514UZ070203', + b'\xf1\x875Q0909143M \xf1\x892041\xf1\x820522UZ050303', + b'\xf1\x875Q0909143M \xf1\x892041\xf1\x820522UZ070303', + b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820526UZ060505', + b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820526UZ070505', + b'\xf1\x875Q0910143B \xf1\x892201\xf1\x82\x0563UZ060600', + b'\xf1\x875Q0910143B \xf1\x892201\xf1\x82\x0563UZ060700', + b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567UZ070500', + b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567UZ070600', + b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567UZ070700', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x873Q0907572B \xf1\x890192', + b'\xf1\x873Q0907572B \xf1\x890194', + b'\xf1\x873Q0907572C \xf1\x890195', + b'\xf1\x875Q0907572R \xf1\x890771', + b'\xf1\x875Q0907572S \xf1\x890780', + ], + }, +} diff --git a/car/volkswagen/interface.py b/car/volkswagen/interface.py new file mode 100644 index 0000000000..91cd300e92 --- /dev/null +++ b/car/volkswagen/interface.py @@ -0,0 +1,133 @@ +from cereal import car +from panda import Panda +from openpilot.selfdrive.car import get_safety_config +from openpilot.selfdrive.car.interfaces import CarInterfaceBase +from openpilot.selfdrive.car.volkswagen.values import CAR, CANBUS, CarControllerParams, NetworkLocation, TransmissionType, GearShifter, VolkswagenFlags + +ButtonType = car.CarState.ButtonEvent.Type +EventName = car.CarEvent.EventName + + +class CarInterface(CarInterfaceBase): + def __init__(self, CP, CarController, CarState): + super().__init__(CP, CarController, CarState) + + if CP.networkLocation == NetworkLocation.fwdCamera: + self.ext_bus = CANBUS.pt + self.cp_ext = self.cp + else: + self.ext_bus = CANBUS.cam + self.cp_ext = self.cp_cam + + @staticmethod + def _get_params(ret, candidate: CAR, fingerprint, car_fw, experimental_long, docs): + ret.carName = "volkswagen" + ret.radarUnavailable = True + + if ret.flags & VolkswagenFlags.PQ: + # Set global PQ35/PQ46/NMS parameters + ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.volkswagenPq)] + ret.enableBsm = 0x3BA in fingerprint[0] # SWA_1 + + if 0x440 in fingerprint[0] or docs: # Getriebe_1 + ret.transmissionType = TransmissionType.automatic + else: + ret.transmissionType = TransmissionType.manual + + if any(msg in fingerprint[1] for msg in (0x1A0, 0xC2)): # Bremse_1, Lenkwinkel_1 + ret.networkLocation = NetworkLocation.gateway + else: + ret.networkLocation = NetworkLocation.fwdCamera + + # The PQ port is in dashcam-only mode due to a fixed six-minute maximum timer on HCA steering. An unsupported + # EPS flash update to work around this timer, and enable steering down to zero, is available from: + # https://github.com/pd0wm/pq-flasher + # It is documented in a four-part blog series: + # https://blog.willemmelching.nl/carhacking/2022/01/02/vw-part1/ + # Panda ALLOW_DEBUG firmware required. + ret.dashcamOnly = True + + else: + # Set global MQB parameters + ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.volkswagen)] + ret.enableBsm = 0x30F in fingerprint[0] # SWA_01 + + if 0xAD in fingerprint[0] or docs: # Getriebe_11 + ret.transmissionType = TransmissionType.automatic + elif 0x187 in fingerprint[0]: # EV_Gearshift + ret.transmissionType = TransmissionType.direct + else: + ret.transmissionType = TransmissionType.manual + + if any(msg in fingerprint[1] for msg in (0x40, 0x86, 0xB2, 0xFD)): # Airbag_01, LWI_01, ESP_19, ESP_21 + ret.networkLocation = NetworkLocation.gateway + else: + ret.networkLocation = NetworkLocation.fwdCamera + + if 0x126 in fingerprint[2]: # HCA_01 + ret.flags |= VolkswagenFlags.STOCK_HCA_PRESENT.value + + # Global lateral tuning defaults, can be overridden per-vehicle + + ret.steerLimitTimer = 0.4 + if ret.flags & VolkswagenFlags.PQ: + ret.steerActuatorDelay = 0.2 + CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) + else: + ret.steerActuatorDelay = 0.1 + ret.lateralTuning.pid.kpBP = [0.] + ret.lateralTuning.pid.kiBP = [0.] + ret.lateralTuning.pid.kf = 0.00006 + ret.lateralTuning.pid.kpV = [0.6] + ret.lateralTuning.pid.kiV = [0.2] + + # Global longitudinal tuning defaults, can be overridden per-vehicle + + ret.experimentalLongitudinalAvailable = ret.networkLocation == NetworkLocation.gateway or docs + if experimental_long: + # Proof-of-concept, prep for E2E only. No radar points available. Panda ALLOW_DEBUG firmware required. + ret.openpilotLongitudinalControl = True + ret.safetyConfigs[0].safetyParam |= Panda.FLAG_VOLKSWAGEN_LONG_CONTROL + if ret.transmissionType == TransmissionType.manual: + ret.minEnableSpeed = 4.5 + + ret.pcmCruise = not ret.openpilotLongitudinalControl + ret.stoppingControl = True + ret.stopAccel = -0.55 + ret.vEgoStarting = 0.1 + ret.vEgoStopping = 0.5 + ret.longitudinalTuning.kpV = [0.1] + ret.longitudinalTuning.kiV = [0.0] + ret.autoResumeSng = ret.minEnableSpeed == -1 + + return ret + + # returns a car.CarState + def _update(self, c): + ret = self.CS.update(self.cp, self.cp_cam, self.cp_ext, self.CP.transmissionType) + + events = self.create_common_events(ret, extra_gears=[GearShifter.eco, GearShifter.sport, GearShifter.manumatic], + pcm_enable=not self.CS.CP.openpilotLongitudinalControl, + enable_buttons=(ButtonType.setCruise, ButtonType.resumeCruise)) + + # Low speed steer alert hysteresis logic + if (self.CP.minSteerSpeed - 1e-3) > CarControllerParams.DEFAULT_MIN_STEER_SPEED and ret.vEgo < (self.CP.minSteerSpeed + 1.): + self.low_speed_alert = True + elif ret.vEgo > (self.CP.minSteerSpeed + 2.): + self.low_speed_alert = False + if self.low_speed_alert: + events.add(EventName.belowSteerSpeed) + + if self.CS.CP.openpilotLongitudinalControl: + if ret.vEgo < self.CP.minEnableSpeed + 0.5: + events.add(EventName.belowEngageSpeed) + if c.enabled and ret.vEgo < self.CP.minEnableSpeed: + events.add(EventName.speedTooLow) + + if self.CC.eps_timer_soft_disable_alert: + events.add(EventName.steerTimeLimit) + + ret.events = events.to_msg() + + return ret + diff --git a/car/volkswagen/mqbcan.py b/car/volkswagen/mqbcan.py new file mode 100644 index 0000000000..763908b6b2 --- /dev/null +++ b/car/volkswagen/mqbcan.py @@ -0,0 +1,137 @@ +def create_steering_control(packer, bus, apply_steer, lkas_enabled): + values = { + "HCA_01_Status_HCA": 5 if lkas_enabled else 3, + "HCA_01_LM_Offset": abs(apply_steer), + "HCA_01_LM_OffSign": 1 if apply_steer < 0 else 0, + "HCA_01_Vib_Freq": 18, + "HCA_01_Sendestatus": 1 if lkas_enabled else 0, + "EA_ACC_Wunschgeschwindigkeit": 327.36, + } + return packer.make_can_msg("HCA_01", bus, values) + + +def create_eps_update(packer, bus, eps_stock_values, ea_simulated_torque): + values = {s: eps_stock_values[s] for s in [ + "COUNTER", # Sync counter value to EPS output + "EPS_Lenkungstyp", # EPS rack type + "EPS_Berechneter_LW", # Absolute raw steering angle + "EPS_VZ_BLW", # Raw steering angle sign + "EPS_HCA_Status", # EPS HCA control status + ]} + + values.update({ + # Absolute driver torque input and sign, with EA inactivity mitigation + "EPS_Lenkmoment": abs(ea_simulated_torque), + "EPS_VZ_Lenkmoment": 1 if ea_simulated_torque < 0 else 0, + }) + + return packer.make_can_msg("LH_EPS_03", bus, values) + + +def create_lka_hud_control(packer, bus, ldw_stock_values, lat_active, steering_pressed, hud_alert, hud_control): + values = {} + if len(ldw_stock_values): + values = {s: ldw_stock_values[s] for s in [ + "LDW_SW_Warnung_links", # Blind spot in warning mode on left side due to lane departure + "LDW_SW_Warnung_rechts", # Blind spot in warning mode on right side due to lane departure + "LDW_Seite_DLCTLC", # Direction of most likely lane departure (left or right) + "LDW_DLC", # Lane departure, distance to line crossing + "LDW_TLC", # Lane departure, time to line crossing + ]} + + values.update({ + "LDW_Status_LED_gelb": 1 if lat_active and steering_pressed else 0, + "LDW_Status_LED_gruen": 1 if lat_active and not steering_pressed else 0, + "LDW_Lernmodus_links": 3 if hud_control.leftLaneDepart else 1 + hud_control.leftLaneVisible, + "LDW_Lernmodus_rechts": 3 if hud_control.rightLaneDepart else 1 + hud_control.rightLaneVisible, + "LDW_Texte": hud_alert, + }) + return packer.make_can_msg("LDW_02", bus, values) + + +def create_acc_buttons_control(packer, bus, gra_stock_values, cancel=False, resume=False): + values = {s: gra_stock_values[s] for s in [ + "GRA_Hauptschalter", # ACC button, on/off + "GRA_Typ_Hauptschalter", # ACC main button type + "GRA_Codierung", # ACC button configuration/coding + "GRA_Tip_Stufe_2", # unknown related to stalk type + "GRA_ButtonTypeInfo", # unknown related to stalk type + ]} + + values.update({ + "COUNTER": (gra_stock_values["COUNTER"] + 1) % 16, + "GRA_Abbrechen": cancel, + "GRA_Tip_Wiederaufnahme": resume, + }) + + return packer.make_can_msg("GRA_ACC_01", bus, values) + + +def acc_control_value(main_switch_on, acc_faulted, long_active): + if acc_faulted: + acc_control = 6 + elif long_active: + acc_control = 3 + elif main_switch_on: + acc_control = 2 + else: + acc_control = 0 + + return acc_control + + +def acc_hud_status_value(main_switch_on, acc_faulted, long_active): + # TODO: happens to resemble the ACC control value for now, but extend this for init/gas override later + return acc_control_value(main_switch_on, acc_faulted, long_active) + + +def create_acc_accel_control(packer, bus, acc_type, acc_enabled, accel, acc_control, stopping, starting, esp_hold): + commands = [] + + acc_06_values = { + "ACC_Typ": acc_type, + "ACC_Status_ACC": acc_control, + "ACC_StartStopp_Info": acc_enabled, + "ACC_Sollbeschleunigung_02": accel if acc_enabled else 3.01, + "ACC_zul_Regelabw_unten": 0.2, # TODO: dynamic adjustment of comfort-band + "ACC_zul_Regelabw_oben": 0.2, # TODO: dynamic adjustment of comfort-band + "ACC_neg_Sollbeschl_Grad_02": 4.0 if acc_enabled else 0, # TODO: dynamic adjustment of jerk limits + "ACC_pos_Sollbeschl_Grad_02": 4.0 if acc_enabled else 0, # TODO: dynamic adjustment of jerk limits + "ACC_Anfahren": starting, + "ACC_Anhalten": stopping, + } + commands.append(packer.make_can_msg("ACC_06", bus, acc_06_values)) + + if starting: + acc_hold_type = 4 # hold release / startup + elif esp_hold: + acc_hold_type = 3 # hold standby + elif stopping: + acc_hold_type = 1 # hold request + else: + acc_hold_type = 0 + + acc_07_values = { + "ACC_Anhalteweg": 0.3 if stopping else 20.46, # Distance to stop (stopping coordinator handles terminal roll-out) + "ACC_Freilauf_Info": 2 if acc_enabled else 0, + "ACC_Folgebeschl": 3.02, # Not using secondary controller accel unless and until we understand its impact + "ACC_Sollbeschleunigung_02": accel if acc_enabled else 3.01, + "ACC_Anforderung_HMS": acc_hold_type, + "ACC_Anfahren": starting, + "ACC_Anhalten": stopping, + } + commands.append(packer.make_can_msg("ACC_07", bus, acc_07_values)) + + return commands + + +def create_acc_hud_control(packer, bus, acc_hud_status, set_speed, lead_distance, distance): + values = { + "ACC_Status_Anzeige": acc_hud_status, + "ACC_Wunschgeschw_02": set_speed if set_speed < 250 else 327.36, + "ACC_Gesetzte_Zeitluecke": distance + 2, + "ACC_Display_Prio": 3, + "ACC_Abstandsindex": lead_distance, + } + + return packer.make_can_msg("ACC_02", bus, values) diff --git a/car/volkswagen/pqcan.py b/car/volkswagen/pqcan.py new file mode 100644 index 0000000000..f8d161b970 --- /dev/null +++ b/car/volkswagen/pqcan.py @@ -0,0 +1,105 @@ +def create_steering_control(packer, bus, apply_steer, lkas_enabled): + values = { + "LM_Offset": abs(apply_steer), + "LM_OffSign": 1 if apply_steer < 0 else 0, + "HCA_Status": 5 if (lkas_enabled and apply_steer != 0) else 3, + "Vib_Freq": 16, + } + + return packer.make_can_msg("HCA_1", bus, values) + + +def create_lka_hud_control(packer, bus, ldw_stock_values, lat_active, steering_pressed, hud_alert, hud_control): + values = {} + if len(ldw_stock_values): + values = {s: ldw_stock_values[s] for s in [ + "LDW_SW_Warnung_links", # Blind spot in warning mode on left side due to lane departure + "LDW_SW_Warnung_rechts", # Blind spot in warning mode on right side due to lane departure + "LDW_Seite_DLCTLC", # Direction of most likely lane departure (left or right) + "LDW_DLC", # Lane departure, distance to line crossing + "LDW_TLC", # Lane departure, time to line crossing + ]} + + values.update({ + "LDW_Lampe_gelb": 1 if lat_active and steering_pressed else 0, + "LDW_Lampe_gruen": 1 if lat_active and not steering_pressed else 0, + "LDW_Lernmodus_links": 3 if hud_control.leftLaneDepart else 1 + hud_control.leftLaneVisible, + "LDW_Lernmodus_rechts": 3 if hud_control.rightLaneDepart else 1 + hud_control.rightLaneVisible, + "LDW_Textbits": hud_alert, + }) + + return packer.make_can_msg("LDW_Status", bus, values) + + +def create_acc_buttons_control(packer, bus, gra_stock_values, cancel=False, resume=False): + values = {s: gra_stock_values[s] for s in [ + "GRA_Hauptschalt", # ACC button, on/off + "GRA_Typ_Hauptschalt", # ACC button, momentary vs latching + "GRA_Kodierinfo", # ACC button, configuration + "GRA_Sender", # ACC button, CAN message originator + ]} + + values.update({ + "COUNTER": (gra_stock_values["COUNTER"] + 1) % 16, + "GRA_Abbrechen": cancel, + "GRA_Recall": resume, + }) + + return packer.make_can_msg("GRA_Neu", bus, values) + + +def acc_control_value(main_switch_on, acc_faulted, long_active): + if long_active: + acc_control = 1 + elif main_switch_on: + acc_control = 2 + else: + acc_control = 0 + + return acc_control + + +def acc_hud_status_value(main_switch_on, acc_faulted, long_active): + if acc_faulted: + hud_status = 6 + elif long_active: + hud_status = 3 + elif main_switch_on: + hud_status = 2 + else: + hud_status = 0 + + return hud_status + + +def create_acc_accel_control(packer, bus, acc_type, acc_enabled, accel, acc_control, stopping, starting, esp_hold): + commands = [] + + values = { + "ACS_Sta_ADR": acc_control, + "ACS_StSt_Info": acc_enabled, + "ACS_Typ_ACC": acc_type, + "ACS_Anhaltewunsch": acc_type == 1 and stopping, + "ACS_FreigSollB": acc_enabled, + "ACS_Sollbeschl": accel if acc_enabled else 3.01, + "ACS_zul_Regelabw": 0.2 if acc_enabled else 1.27, + "ACS_max_AendGrad": 3.0 if acc_enabled else 5.08, + } + + commands.append(packer.make_can_msg("ACC_System", bus, values)) + + return commands + + +def create_acc_hud_control(packer, bus, acc_hud_status, set_speed, lead_distance, distance): + values = { + "ACA_StaACC": acc_hud_status, + "ACA_Zeitluecke": distance + 2, + "ACA_V_Wunsch": set_speed, + "ACA_gemZeitl": lead_distance, + "ACA_PrioDisp": 3, + # TODO: restore dynamic pop-to-foreground/highlight behavior with ACA_PrioDisp and ACA_AnzDisplay + # TODO: ACA_kmh_mph handling probably needed to resolve rounding errors in displayed setpoint + } + + return packer.make_can_msg("ACC_GRA_Anzeige", bus, values) diff --git a/car/volkswagen/radar_interface.py b/car/volkswagen/radar_interface.py new file mode 100644 index 0000000000..e654bd61fd --- /dev/null +++ b/car/volkswagen/radar_interface.py @@ -0,0 +1,4 @@ +from openpilot.selfdrive.car.interfaces import RadarInterfaceBase + +class RadarInterface(RadarInterfaceBase): + pass diff --git a/car/volkswagen/tests/test_volkswagen.py b/car/volkswagen/tests/test_volkswagen.py new file mode 100644 index 0000000000..0002578105 --- /dev/null +++ b/car/volkswagen/tests/test_volkswagen.py @@ -0,0 +1,60 @@ +import random +import re + +from cereal import car +from openpilot.selfdrive.car.volkswagen.values import CAR, FW_QUERY_CONFIG, WMI +from openpilot.selfdrive.car.volkswagen.fingerprints import FW_VERSIONS + +Ecu = car.CarParams.Ecu + +CHASSIS_CODE_PATTERN = re.compile('[A-Z0-9]{2}') +# TODO: determine the unknown groups +SPARE_PART_FW_PATTERN = re.compile(b'\xf1\x87(?P[0-9][0-9A-Z]{2})(?P[0-9][0-9A-Z][0-9])(?P[0-9A-Z]{2}[0-9])([A-Z0-9]| )') + + +class TestVolkswagenPlatformConfigs: + def test_spare_part_fw_pattern(self, subtests): + # Relied on for determining if a FW is likely VW + for platform, ecus in FW_VERSIONS.items(): + with subtests.test(platform=platform.value): + for fws in ecus.values(): + for fw in fws: + assert SPARE_PART_FW_PATTERN.match(fw) is not None, f"Bad FW: {fw}" + + def test_chassis_codes(self, subtests): + for platform in CAR: + with subtests.test(platform=platform.value): + assert len(platform.config.wmis) > 0, "WMIs not set" + assert len(platform.config.chassis_codes) > 0, "Chassis codes not set" + assert all(CHASSIS_CODE_PATTERN.match(cc) for cc in \ + platform.config.chassis_codes), "Bad chassis codes" + + # No two platforms should share chassis codes + for comp in CAR: + if platform == comp: + continue + assert set() == platform.config.chassis_codes & comp.config.chassis_codes, \ + f"Shared chassis codes: {comp}" + + def test_custom_fuzzy_fingerprinting(self, subtests): + all_radar_fw = list({fw for ecus in FW_VERSIONS.values() for fw in ecus[Ecu.fwdRadar, 0x757, None]}) + + for platform in CAR: + with subtests.test(platform=platform.name): + for wmi in WMI: + for chassis_code in platform.config.chassis_codes | {"00"}: + vin = ["0"] * 17 + vin[0:3] = wmi + vin[6:8] = chassis_code + vin = "".join(vin) + + # Check a few FW cases - expected, unexpected + for radar_fw in random.sample(all_radar_fw, 5) + [b'\xf1\x875Q0907572G \xf1\x890571', b'\xf1\x877H9907572AA\xf1\x890396']: + should_match = ((wmi in platform.config.wmis and chassis_code in platform.config.chassis_codes) and + radar_fw in all_radar_fw) + + live_fws = {(0x757, None): [radar_fw]} + matches = FW_QUERY_CONFIG.match_fw_to_car_fuzzy(live_fws, vin, FW_VERSIONS) + + expected_matches = {platform} if should_match else set() + assert expected_matches == matches, "Bad match" diff --git a/car/volkswagen/values.py b/car/volkswagen/values.py new file mode 100644 index 0000000000..4d317176be --- /dev/null +++ b/car/volkswagen/values.py @@ -0,0 +1,516 @@ +from collections import defaultdict, namedtuple +from dataclasses import dataclass, field +from enum import Enum, IntFlag, StrEnum + +from cereal import car +from panda.python import uds +from opendbc.can.can_define import CANDefine +from openpilot.common.conversions import Conversions as CV +from openpilot.selfdrive.car import dbc_dict, CarSpecs, DbcDict, PlatformConfig, Platforms +from openpilot.selfdrive.car.docs_definitions import CarFootnote, CarHarness, CarDocs, CarParts, Column, \ + Device +from openpilot.selfdrive.car.fw_query_definitions import EcuAddrSubAddr, FwQueryConfig, Request, p16 + +Ecu = car.CarParams.Ecu +NetworkLocation = car.CarParams.NetworkLocation +TransmissionType = car.CarParams.TransmissionType +GearShifter = car.CarState.GearShifter +Button = namedtuple('Button', ['event_type', 'can_addr', 'can_msg', 'values']) + + +class CarControllerParams: + STEER_STEP = 2 # HCA_01/HCA_1 message frequency 50Hz + ACC_CONTROL_STEP = 2 # ACC_06/ACC_07/ACC_System frequency 50Hz + + # Documented lateral limits: 3.00 Nm max, rate of change 5.00 Nm/sec. + # MQB vs PQ maximums are shared, but rate-of-change limited differently + # based on safety requirements driven by lateral accel testing. + + STEER_MAX = 300 # Max heading control assist torque 3.00 Nm + STEER_DRIVER_MULTIPLIER = 3 # weight driver torque heavily + STEER_DRIVER_FACTOR = 1 # from dbc + + STEER_TIME_MAX = 360 # Max time that EPS allows uninterrupted HCA steering control + STEER_TIME_ALERT = STEER_TIME_MAX - 10 # If mitigation fails, time to soft disengage before EPS timer expires + STEER_TIME_STUCK_TORQUE = 1.9 # EPS limits same torque to 6 seconds, reset timer 3x within that period + + DEFAULT_MIN_STEER_SPEED = 0.4 # m/s, newer EPS racks fault below this speed, don't show a low speed alert + + ACCEL_MAX = 2.0 # 2.0 m/s max acceleration + ACCEL_MIN = -3.5 # 3.5 m/s max deceleration + + def __init__(self, CP): + can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) + + if CP.flags & VolkswagenFlags.PQ: + self.LDW_STEP = 5 # LDW_1 message frequency 20Hz + self.ACC_HUD_STEP = 4 # ACC_GRA_Anzeige frequency 25Hz + self.STEER_DRIVER_ALLOWANCE = 80 # Driver intervention threshold 0.8 Nm + self.STEER_DELTA_UP = 6 # Max HCA reached in 1.00s (STEER_MAX / (50Hz * 1.00)) + self.STEER_DELTA_DOWN = 10 # Min HCA reached in 0.60s (STEER_MAX / (50Hz * 0.60)) + + if CP.transmissionType == TransmissionType.automatic: + self.shifter_values = can_define.dv["Getriebe_1"]["Waehlhebelposition__Getriebe_1_"] + self.hca_status_values = can_define.dv["Lenkhilfe_2"]["LH2_Sta_HCA"] + + self.BUTTONS = [ + Button(car.CarState.ButtonEvent.Type.setCruise, "GRA_Neu", "GRA_Neu_Setzen", [1]), + Button(car.CarState.ButtonEvent.Type.resumeCruise, "GRA_Neu", "GRA_Recall", [1]), + Button(car.CarState.ButtonEvent.Type.accelCruise, "GRA_Neu", "GRA_Up_kurz", [1]), + Button(car.CarState.ButtonEvent.Type.decelCruise, "GRA_Neu", "GRA_Down_kurz", [1]), + Button(car.CarState.ButtonEvent.Type.cancel, "GRA_Neu", "GRA_Abbrechen", [1]), + Button(car.CarState.ButtonEvent.Type.gapAdjustCruise, "GRA_Neu", "GRA_Zeitluecke", [1]), + ] + + self.LDW_MESSAGES = { + "none": 0, # Nothing to display + "laneAssistUnavail": 1, # "Lane Assist currently not available." + "laneAssistUnavailSysError": 2, # "Lane Assist system error" + "laneAssistUnavailNoSensorView": 3, # "Lane Assist not available. No sensor view." + "laneAssistTakeOver": 4, # "Lane Assist: Please Take Over Steering" + "laneAssistDeactivTrailer": 5, # "Lane Assist: no function with trailer" + } + + else: + self.LDW_STEP = 10 # LDW_02 message frequency 10Hz + self.ACC_HUD_STEP = 6 # ACC_02 message frequency 16Hz + self.STEER_DRIVER_ALLOWANCE = 80 # Driver intervention threshold 0.8 Nm + self.STEER_DELTA_UP = 4 # Max HCA reached in 1.50s (STEER_MAX / (50Hz * 1.50)) + self.STEER_DELTA_DOWN = 10 # Min HCA reached in 0.60s (STEER_MAX / (50Hz * 0.60)) + + if CP.transmissionType == TransmissionType.automatic: + self.shifter_values = can_define.dv["Getriebe_11"]["GE_Fahrstufe"] + elif CP.transmissionType == TransmissionType.direct: + self.shifter_values = can_define.dv["EV_Gearshift"]["GearPosition"] + self.hca_status_values = can_define.dv["LH_EPS_03"]["EPS_HCA_Status"] + + self.BUTTONS = [ + Button(car.CarState.ButtonEvent.Type.setCruise, "GRA_ACC_01", "GRA_Tip_Setzen", [1]), + Button(car.CarState.ButtonEvent.Type.resumeCruise, "GRA_ACC_01", "GRA_Tip_Wiederaufnahme", [1]), + Button(car.CarState.ButtonEvent.Type.accelCruise, "GRA_ACC_01", "GRA_Tip_Hoch", [1]), + Button(car.CarState.ButtonEvent.Type.decelCruise, "GRA_ACC_01", "GRA_Tip_Runter", [1]), + Button(car.CarState.ButtonEvent.Type.cancel, "GRA_ACC_01", "GRA_Abbrechen", [1]), + Button(car.CarState.ButtonEvent.Type.gapAdjustCruise, "GRA_ACC_01", "GRA_Verstellung_Zeitluecke", [1]), + ] + + self.LDW_MESSAGES = { + "none": 0, # Nothing to display + "laneAssistUnavailChime": 1, # "Lane Assist currently not available." with chime + "laneAssistUnavailNoSensorChime": 3, # "Lane Assist not available. No sensor view." with chime + "laneAssistTakeOverUrgent": 4, # "Lane Assist: Please Take Over Steering" with urgent beep + "emergencyAssistUrgent": 6, # "Emergency Assist: Please Take Over Steering" with urgent beep + "laneAssistTakeOverChime": 7, # "Lane Assist: Please Take Over Steering" with chime + "laneAssistTakeOver": 8, # "Lane Assist: Please Take Over Steering" silent + "emergencyAssistChangingLanes": 9, # "Emergency Assist: Changing lanes..." with urgent beep + "laneAssistDeactivated": 10, # "Lane Assist deactivated." silent with persistent icon afterward + } + + +class CANBUS: + pt = 0 + cam = 2 + + +class WMI(StrEnum): + VOLKSWAGEN_USA_SUV = "1V2" + VOLKSWAGEN_USA_CAR = "1VW" + VOLKSWAGEN_MEXICO_SUV = "3VV" + VOLKSWAGEN_MEXICO_CAR = "3VW" + VOLKSWAGEN_ARGENTINA = "8AW" + VOLKSWAGEN_BRASIL = "9BW" + SAIC_VOLKSWAGEN = "LSV" + SKODA = "TMB" + SEAT = "VSS" + AUDI_EUROPE_MPV = "WA1" + AUDI_GERMANY_CAR = "WAU" + MAN = "WMA" + AUDI_SPORT = "WUA" + VOLKSWAGEN_COMMERCIAL = "WV1" + VOLKSWAGEN_COMMERCIAL_BUS_VAN = "WV2" + VOLKSWAGEN_EUROPE_SUV = "WVG" + VOLKSWAGEN_EUROPE_CAR = "WVW" + VOLKSWAGEN_GROUP_RUS = "XW8" + + +class VolkswagenFlags(IntFlag): + # Detected flags + STOCK_HCA_PRESENT = 1 + + # Static flags + PQ = 2 + + +@dataclass +class VolkswagenMQBPlatformConfig(PlatformConfig): + dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict('vw_mqb_2010', None)) + # Volkswagen uses the VIN WMI and chassis code to match in the absence of the comma power + # on camera-integrated cars, as we lose too many ECUs to reliably identify the vehicle + chassis_codes: set[str] = field(default_factory=set) + wmis: set[WMI] = field(default_factory=set) + + +@dataclass +class VolkswagenPQPlatformConfig(VolkswagenMQBPlatformConfig): + dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict('vw_golf_mk4', None)) + + def init(self): + self.flags |= VolkswagenFlags.PQ + + +@dataclass(frozen=True, kw_only=True) +class VolkswagenCarSpecs(CarSpecs): + centerToFrontRatio: float = 0.45 + steerRatio: float = 15.6 + minSteerSpeed: float = CarControllerParams.DEFAULT_MIN_STEER_SPEED + + +class Footnote(Enum): + KAMIQ = CarFootnote( + "Not including the China market Kamiq, which is based on the (currently) unsupported PQ34 platform.", + Column.MODEL) + PASSAT = CarFootnote( + "Refers only to the MQB-based European B8 Passat, not the NMS Passat in the USA/China/Mideast markets.", + Column.MODEL) + SKODA_HEATED_WINDSHIELD = CarFootnote( + "Some Škoda vehicles are equipped with heated windshields, which are known " + + "to block GPS signal needed for some comma 3X functionality.", + Column.MODEL) + VW_EXP_LONG = CarFootnote( + "Only available for vehicles using a gateway (J533) harness. At this time, vehicles using a camera harness " + + "are limited to using stock ACC.", + Column.LONGITUDINAL) + VW_MQB_A0 = CarFootnote( + "Model-years 2022 and beyond may have a combined CAN gateway and BCM, which is supported by openpilot " + + "in software, but doesn't yet have a harness available from the comma store.", + Column.HARDWARE) + + +@dataclass +class VWCarDocs(CarDocs): + package: str = "Adaptive Cruise Control (ACC) & Lane Assist" + car_parts: CarParts = field(default_factory=CarParts.common([CarHarness.j533])) + + def init_make(self, CP: car.CarParams): + self.footnotes.append(Footnote.VW_EXP_LONG) + if "SKODA" in CP.carFingerprint: + self.footnotes.append(Footnote.SKODA_HEATED_WINDSHIELD) + + if CP.carFingerprint in (CAR.VOLKSWAGEN_CRAFTER_MK2, CAR.VOLKSWAGEN_TRANSPORTER_T61): + self.car_parts = CarParts([Device.threex_angled_mount, CarHarness.j533]) + + if abs(CP.minSteerSpeed - CarControllerParams.DEFAULT_MIN_STEER_SPEED) < 1e-3: + self.min_steer_speed = 0 + + +# Check the 7th and 8th characters of the VIN before adding a new CAR. If the +# chassis code is already listed below, don't add a new CAR, just add to the +# FW_VERSIONS for that existing CAR. + +class CAR(Platforms): + config: VolkswagenMQBPlatformConfig | VolkswagenPQPlatformConfig + + VOLKSWAGEN_ARTEON_MK1 = VolkswagenMQBPlatformConfig( + [ + VWCarDocs("Volkswagen Arteon 2018-23", video_link="https://youtu.be/FAomFKPFlDA"), + VWCarDocs("Volkswagen Arteon R 2020-23", video_link="https://youtu.be/FAomFKPFlDA"), + VWCarDocs("Volkswagen Arteon eHybrid 2020-23", video_link="https://youtu.be/FAomFKPFlDA"), + VWCarDocs("Volkswagen Arteon Shooting Brake 2020-23", video_link="https://youtu.be/FAomFKPFlDA"), + VWCarDocs("Volkswagen CC 2018-22", video_link="https://youtu.be/FAomFKPFlDA"), + ], + VolkswagenCarSpecs(mass=1733, wheelbase=2.84), + chassis_codes={"AN", "3H"}, + wmis={WMI.VOLKSWAGEN_EUROPE_CAR}, + ) + VOLKSWAGEN_ATLAS_MK1 = VolkswagenMQBPlatformConfig( + [ + VWCarDocs("Volkswagen Atlas 2018-23"), + VWCarDocs("Volkswagen Atlas Cross Sport 2020-22"), + VWCarDocs("Volkswagen Teramont 2018-22"), + VWCarDocs("Volkswagen Teramont Cross Sport 2021-22"), + VWCarDocs("Volkswagen Teramont X 2021-22"), + ], + VolkswagenCarSpecs(mass=2011, wheelbase=2.98), + chassis_codes={"CA"}, + wmis={WMI.VOLKSWAGEN_USA_SUV, WMI.VOLKSWAGEN_EUROPE_SUV}, + ) + VOLKSWAGEN_CADDY_MK3 = VolkswagenPQPlatformConfig( + [ + VWCarDocs("Volkswagen Caddy 2019"), + VWCarDocs("Volkswagen Caddy Maxi 2019"), + ], + VolkswagenCarSpecs(mass=1613, wheelbase=2.6, minSteerSpeed=21 * CV.KPH_TO_MS), + chassis_codes={"2K"}, + wmis={WMI.VOLKSWAGEN_COMMERCIAL_BUS_VAN}, + ) + VOLKSWAGEN_CRAFTER_MK2 = VolkswagenMQBPlatformConfig( + [ + VWCarDocs("Volkswagen Crafter 2017-23", video_link="https://youtu.be/4100gLeabmo"), + VWCarDocs("Volkswagen e-Crafter 2018-23", video_link="https://youtu.be/4100gLeabmo"), + VWCarDocs("Volkswagen Grand California 2019-23", video_link="https://youtu.be/4100gLeabmo"), + VWCarDocs("MAN TGE 2017-23", video_link="https://youtu.be/4100gLeabmo"), + VWCarDocs("MAN eTGE 2020-23", video_link="https://youtu.be/4100gLeabmo"), + ], + VolkswagenCarSpecs(mass=2100, wheelbase=3.64, minSteerSpeed=50 * CV.KPH_TO_MS), + chassis_codes={"SY", "SZ"}, + wmis={WMI.VOLKSWAGEN_COMMERCIAL, WMI.MAN}, + ) + VOLKSWAGEN_GOLF_MK7 = VolkswagenMQBPlatformConfig( + [ + VWCarDocs("Volkswagen e-Golf 2014-20"), + VWCarDocs("Volkswagen Golf 2015-20", auto_resume=False), + VWCarDocs("Volkswagen Golf Alltrack 2015-19", auto_resume=False), + VWCarDocs("Volkswagen Golf GTD 2015-20"), + VWCarDocs("Volkswagen Golf GTE 2015-20"), + VWCarDocs("Volkswagen Golf GTI 2015-21", auto_resume=False), + VWCarDocs("Volkswagen Golf R 2015-19"), + VWCarDocs("Volkswagen Golf SportsVan 2015-20"), + ], + VolkswagenCarSpecs(mass=1397, wheelbase=2.62), + chassis_codes={"5G", "AU", "BA", "BE"}, + wmis={WMI.VOLKSWAGEN_MEXICO_CAR, WMI.VOLKSWAGEN_EUROPE_CAR}, + ) + VOLKSWAGEN_JETTA_MK7 = VolkswagenMQBPlatformConfig( + [ + VWCarDocs("Volkswagen Jetta 2018-24"), + VWCarDocs("Volkswagen Jetta GLI 2021-24"), + ], + VolkswagenCarSpecs(mass=1328, wheelbase=2.71), + chassis_codes={"BU"}, + wmis={WMI.VOLKSWAGEN_MEXICO_CAR, WMI.VOLKSWAGEN_EUROPE_CAR}, + ) + VOLKSWAGEN_PASSAT_MK8 = VolkswagenMQBPlatformConfig( + [ + VWCarDocs("Volkswagen Passat 2015-22", footnotes=[Footnote.PASSAT]), + VWCarDocs("Volkswagen Passat Alltrack 2015-22"), + VWCarDocs("Volkswagen Passat GTE 2015-22"), + ], + VolkswagenCarSpecs(mass=1551, wheelbase=2.79), + chassis_codes={"3C", "3G"}, + wmis={WMI.VOLKSWAGEN_EUROPE_CAR}, + ) + VOLKSWAGEN_PASSAT_NMS = VolkswagenPQPlatformConfig( + [VWCarDocs("Volkswagen Passat NMS 2017-22")], + VolkswagenCarSpecs(mass=1503, wheelbase=2.80, minSteerSpeed=50 * CV.KPH_TO_MS, minEnableSpeed=20 * CV.KPH_TO_MS), + chassis_codes={"A3"}, + wmis={WMI.VOLKSWAGEN_USA_CAR}, + ) + VOLKSWAGEN_POLO_MK6 = VolkswagenMQBPlatformConfig( + [ + VWCarDocs("Volkswagen Polo 2018-23", footnotes=[Footnote.VW_MQB_A0]), + VWCarDocs("Volkswagen Polo GTI 2018-23", footnotes=[Footnote.VW_MQB_A0]), + ], + VolkswagenCarSpecs(mass=1230, wheelbase=2.55), + chassis_codes={"AW"}, + wmis={WMI.VOLKSWAGEN_EUROPE_CAR}, + ) + VOLKSWAGEN_SHARAN_MK2 = VolkswagenPQPlatformConfig( + [ + VWCarDocs("Volkswagen Sharan 2018-22"), + VWCarDocs("SEAT Alhambra 2018-20"), + ], + VolkswagenCarSpecs(mass=1639, wheelbase=2.92, minSteerSpeed=50 * CV.KPH_TO_MS), + chassis_codes={"7N"}, + wmis={WMI.VOLKSWAGEN_EUROPE_CAR}, + ) + VOLKSWAGEN_TAOS_MK1 = VolkswagenMQBPlatformConfig( + [VWCarDocs("Volkswagen Taos 2022-23")], + VolkswagenCarSpecs(mass=1498, wheelbase=2.69), + chassis_codes={"B2"}, + wmis={WMI.VOLKSWAGEN_MEXICO_SUV, WMI.VOLKSWAGEN_ARGENTINA}, + ) + VOLKSWAGEN_TCROSS_MK1 = VolkswagenMQBPlatformConfig( + [VWCarDocs("Volkswagen T-Cross 2021", footnotes=[Footnote.VW_MQB_A0])], + VolkswagenCarSpecs(mass=1150, wheelbase=2.60), + chassis_codes={"C1"}, + wmis={WMI.VOLKSWAGEN_EUROPE_SUV}, + ) + VOLKSWAGEN_TIGUAN_MK2 = VolkswagenMQBPlatformConfig( + [ + VWCarDocs("Volkswagen Tiguan 2018-24"), + VWCarDocs("Volkswagen Tiguan eHybrid 2021-23"), + ], + VolkswagenCarSpecs(mass=1715, wheelbase=2.74), + chassis_codes={"5N", "AD", "AX", "BW"}, + wmis={WMI.VOLKSWAGEN_EUROPE_SUV, WMI.VOLKSWAGEN_MEXICO_SUV}, + ) + VOLKSWAGEN_TOURAN_MK2 = VolkswagenMQBPlatformConfig( + [VWCarDocs("Volkswagen Touran 2016-23")], + VolkswagenCarSpecs(mass=1516, wheelbase=2.79), + chassis_codes={"1T"}, + wmis={WMI.VOLKSWAGEN_EUROPE_SUV}, + ) + VOLKSWAGEN_TRANSPORTER_T61 = VolkswagenMQBPlatformConfig( + [ + VWCarDocs("Volkswagen Caravelle 2020"), + VWCarDocs("Volkswagen California 2021-23"), + ], + VolkswagenCarSpecs(mass=1926, wheelbase=3.00, minSteerSpeed=14.0), + chassis_codes={"7H", "7L"}, + wmis={WMI.VOLKSWAGEN_COMMERCIAL_BUS_VAN}, + ) + VOLKSWAGEN_TROC_MK1 = VolkswagenMQBPlatformConfig( + [VWCarDocs("Volkswagen T-Roc 2018-23")], + VolkswagenCarSpecs(mass=1413, wheelbase=2.63), + chassis_codes={"A1"}, + wmis={WMI.VOLKSWAGEN_EUROPE_SUV}, + ) + AUDI_A3_MK3 = VolkswagenMQBPlatformConfig( + [ + VWCarDocs("Audi A3 2014-19"), + VWCarDocs("Audi A3 Sportback e-tron 2017-18"), + VWCarDocs("Audi RS3 2018"), + VWCarDocs("Audi S3 2015-17"), + ], + VolkswagenCarSpecs(mass=1335, wheelbase=2.61), + chassis_codes={"8V", "FF"}, + wmis={WMI.AUDI_GERMANY_CAR, WMI.AUDI_SPORT}, + ) + AUDI_Q2_MK1 = VolkswagenMQBPlatformConfig( + [VWCarDocs("Audi Q2 2018")], + VolkswagenCarSpecs(mass=1205, wheelbase=2.61), + chassis_codes={"GA"}, + wmis={WMI.AUDI_GERMANY_CAR}, + ) + AUDI_Q3_MK2 = VolkswagenMQBPlatformConfig( + [VWCarDocs("Audi Q3 2019-23")], + VolkswagenCarSpecs(mass=1623, wheelbase=2.68), + chassis_codes={"8U", "F3", "FS"}, + wmis={WMI.AUDI_EUROPE_MPV, WMI.AUDI_GERMANY_CAR}, + ) + SEAT_ATECA_MK1 = VolkswagenMQBPlatformConfig( + [ + VWCarDocs("CUPRA Ateca 2018-23"), + VWCarDocs("SEAT Ateca 2016-23"), + VWCarDocs("SEAT Leon 2014-20"), + ], + VolkswagenCarSpecs(mass=1300, wheelbase=2.64), + chassis_codes={"5F"}, + wmis={WMI.SEAT}, + ) + SKODA_FABIA_MK4 = VolkswagenMQBPlatformConfig( + [VWCarDocs("Škoda Fabia 2022-23", footnotes=[Footnote.VW_MQB_A0])], + VolkswagenCarSpecs(mass=1266, wheelbase=2.56), + chassis_codes={"PJ"}, + wmis={WMI.SKODA}, + ) + SKODA_KAMIQ_MK1 = VolkswagenMQBPlatformConfig( + [ + VWCarDocs("Škoda Kamiq 2021-23", footnotes=[Footnote.VW_MQB_A0, Footnote.KAMIQ]), + VWCarDocs("Škoda Scala 2020-23", footnotes=[Footnote.VW_MQB_A0]), + ], + VolkswagenCarSpecs(mass=1230, wheelbase=2.66), + chassis_codes={"NW"}, + wmis={WMI.SKODA}, + ) + SKODA_KAROQ_MK1 = VolkswagenMQBPlatformConfig( + [VWCarDocs("Škoda Karoq 2019-23")], + VolkswagenCarSpecs(mass=1278, wheelbase=2.66), + chassis_codes={"NU"}, + wmis={WMI.SKODA}, + ) + SKODA_KODIAQ_MK1 = VolkswagenMQBPlatformConfig( + [VWCarDocs("Škoda Kodiaq 2017-23")], + VolkswagenCarSpecs(mass=1569, wheelbase=2.79), + chassis_codes={"NS"}, + wmis={WMI.SKODA, WMI.VOLKSWAGEN_GROUP_RUS}, + ) + SKODA_OCTAVIA_MK3 = VolkswagenMQBPlatformConfig( + [ + VWCarDocs("Škoda Octavia 2015-19"), + VWCarDocs("Škoda Octavia RS 2016"), + VWCarDocs("Škoda Octavia Scout 2017-19"), + ], + VolkswagenCarSpecs(mass=1388, wheelbase=2.68), + chassis_codes={"NE"}, + wmis={WMI.SKODA}, + ) + SKODA_SUPERB_MK3 = VolkswagenMQBPlatformConfig( + [VWCarDocs("Škoda Superb 2015-22")], + VolkswagenCarSpecs(mass=1505, wheelbase=2.84), + chassis_codes={"3V", "NP"}, + wmis={WMI.SKODA}, + ) + + +def match_fw_to_car_fuzzy(live_fw_versions, vin, offline_fw_versions) -> set[str]: + candidates = set() + + # Compile all FW versions for each ECU + all_ecu_versions: dict[EcuAddrSubAddr, set[str]] = defaultdict(set) + for ecus in offline_fw_versions.values(): + for ecu, versions in ecus.items(): + all_ecu_versions[ecu] |= set(versions) + + # Check the WMI and chassis code to determine the platform + wmi = vin[:3] + chassis_code = vin[6:8] + + for platform in CAR: + valid_ecus = set() + for ecu in offline_fw_versions[platform]: + addr = ecu[1:] + if ecu[0] not in CHECK_FUZZY_ECUS: + continue + + # Sanity check that live FW is in the superset of all FW, Volkswagen ECU part numbers are commonly shared + found_versions = live_fw_versions.get(addr, []) + expected_versions = all_ecu_versions[ecu] + if not any(found_version in expected_versions for found_version in found_versions): + break + + valid_ecus.add(ecu[0]) + + if valid_ecus != CHECK_FUZZY_ECUS: + continue + + if wmi in platform.config.wmis and chassis_code in platform.config.chassis_codes: + candidates.add(platform) + + return {str(c) for c in candidates} + + +# These ECUs are required to match to gain a VIN match +# TODO: do we want to check camera when we add its FW? +CHECK_FUZZY_ECUS = {Ecu.fwdRadar} + +# All supported cars should return FW from the engine, srs, eps, and fwdRadar. Cars +# with a manual trans won't return transmission firmware, but all other cars will. +# +# The 0xF187 SW part number query should return in the form of N[NX][NX] NNN NNN [X[X]], +# where N=number, X=letter, and the trailing two letters are optional. Performance +# tuners sometimes tamper with that field (e.g. 8V0 9C0 BB0 1 from COBB/EQT). Tampered +# ECU SW part numbers are invalid for vehicle ID and compatibility checks. Try to have +# them repaired by the tuner before including them in openpilot. + +VOLKSWAGEN_VERSION_REQUEST_MULTI = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ + p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_SPARE_PART_NUMBER) + \ + p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_ECU_SOFTWARE_VERSION_NUMBER) + \ + p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_DATA_IDENTIFICATION) +VOLKSWAGEN_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + +VOLKSWAGEN_RX_OFFSET = 0x6a + +FW_QUERY_CONFIG = FwQueryConfig( + requests=[request for bus, obd_multiplexing in [(1, True), (1, False), (0, False)] for request in [ + Request( + [VOLKSWAGEN_VERSION_REQUEST_MULTI], + [VOLKSWAGEN_VERSION_RESPONSE], + whitelist_ecus=[Ecu.srs, Ecu.eps, Ecu.fwdRadar, Ecu.fwdCamera], + rx_offset=VOLKSWAGEN_RX_OFFSET, + bus=bus, + obd_multiplexing=obd_multiplexing, + ), + Request( + [VOLKSWAGEN_VERSION_REQUEST_MULTI], + [VOLKSWAGEN_VERSION_RESPONSE], + whitelist_ecus=[Ecu.engine, Ecu.transmission], + bus=bus, + obd_multiplexing=obd_multiplexing, + ), + ]], + non_essential_ecus={Ecu.eps: list(CAR)}, + extra_ecus=[(Ecu.fwdCamera, 0x74f, None)], + match_fw_to_car_fuzzy=match_fw_to_car_fuzzy, +) + +DBC = CAR.create_dbc_map() From caadb39d8de7606ce73d9d0123d529ea727c7bd8 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Fri, 7 Jun 2024 22:11:27 -0700 Subject: [PATCH 02/15] Revert "move car interfaces to opendbc" This reverts commit 0589ea0dbec5e3d25ed4498257eb162d656780bb. --- car/body/__init__.py | 0 car/body/bodycan.py | 7 - car/body/carcontroller.py | 84 - car/body/carstate.py | 40 - car/body/fingerprints.py | 28 - car/body/interface.py | 39 - car/body/radar_interface.py | 4 - car/body/values.py | 40 - car/chrysler/__init__.py | 0 car/chrysler/carcontroller.py | 85 -- car/chrysler/carstate.py | 156 -- car/chrysler/chryslercan.py | 71 - car/chrysler/fingerprints.py | 705 --------- car/chrysler/interface.py | 97 -- car/chrysler/radar_interface.py | 86 -- car/chrysler/values.py | 156 -- car/ford/__init__.py | 0 car/ford/carcontroller.py | 120 -- car/ford/carstate.py | 174 --- car/ford/fingerprints.py | 166 -- car/ford/fordcan.py | 340 ----- car/ford/interface.py | 85 -- car/ford/radar_interface.py | 143 -- car/ford/tests/__init__.py | 0 car/ford/tests/print_platform_codes.py | 30 - car/ford/tests/test_ford.py | 143 -- car/ford/values.py | 279 ---- car/gm/__init__.py | 0 car/gm/carcontroller.py | 165 -- car/gm/carstate.py | 180 --- car/gm/fingerprints.py | 63 - car/gm/gmcan.py | 173 --- car/gm/interface.py | 239 --- car/gm/radar_interface.py | 101 -- car/gm/tests/__init__.py | 0 car/gm/tests/test_gm.py | 20 - car/gm/values.py | 234 --- car/honda/__init__.py | 0 car/honda/carcontroller.py | 256 ---- car/honda/carstate.py | 297 ---- car/honda/fingerprints.py | 895 ----------- car/honda/hondacan.py | 211 --- car/honda/interface.py | 259 ---- car/honda/radar_interface.py | 84 - car/honda/tests/__init__.py | 0 car/honda/tests/test_honda.py | 14 - car/honda/values.py | 331 ---- car/hyundai/__init__.py | 0 car/hyundai/carcontroller.py | 208 --- car/hyundai/carstate.py | 368 ----- car/hyundai/fingerprints.py | 1160 -------------- car/hyundai/hyundaican.py | 213 --- car/hyundai/hyundaicanfd.py | 223 --- car/hyundai/interface.py | 180 --- car/hyundai/radar_interface.py | 79 - car/hyundai/tests/__init__.py | 0 car/hyundai/tests/print_platform_codes.py | 22 - car/hyundai/tests/test_hyundai.py | 218 --- car/hyundai/values.py | 751 --------- car/mazda/__init__.py | 0 car/mazda/carcontroller.py | 66 - car/mazda/carstate.py | 153 -- car/mazda/fingerprints.py | 265 ---- car/mazda/interface.py | 50 - car/mazda/mazdacan.py | 128 -- car/mazda/radar_interface.py | 5 - car/mazda/values.py | 104 -- car/mock/__init__.py | 0 car/mock/carcontroller.py | 5 - car/mock/carstate.py | 4 - car/mock/interface.py | 32 - car/mock/radar_interface.py | 4 - car/mock/values.py | 9 - car/nissan/__init__.py | 0 car/nissan/carcontroller.py | 82 - car/nissan/carstate.py | 197 --- car/nissan/fingerprints.py | 119 -- car/nissan/interface.py | 44 - car/nissan/nissancan.py | 154 -- car/nissan/radar_interface.py | 4 - car/nissan/values.py | 107 -- car/subaru/__init__.py | 0 car/subaru/carcontroller.py | 144 -- car/subaru/carstate.py | 229 --- car/subaru/fingerprints.py | 563 ------- car/subaru/interface.py | 116 -- car/subaru/radar_interface.py | 4 - car/subaru/subarucan.py | 321 ---- car/subaru/tests/test_subaru.py | 16 - car/subaru/values.py | 275 ---- car/tesla/__init__.py | 0 car/tesla/carcontroller.py | 67 - car/tesla/carstate.py | 139 -- car/tesla/fingerprints.py | 32 - car/tesla/interface.py | 52 - car/tesla/radar_interface.py | 91 -- car/tesla/teslacan.py | 94 -- car/tesla/values.py | 98 -- car/toyota/__init__.py | 0 car/toyota/carcontroller.py | 179 --- car/toyota/carstate.py | 247 --- car/toyota/fingerprints.py | 1681 --------------------- car/toyota/interface.py | 202 --- car/toyota/radar_interface.py | 94 -- car/toyota/tests/__init__.py | 0 car/toyota/tests/print_platform_codes.py | 35 - car/toyota/tests/test_toyota.py | 166 -- car/toyota/toyotacan.py | 118 -- car/toyota/values.py | 575 ------- car/volkswagen/__init__.py | 0 car/volkswagen/carcontroller.py | 121 -- car/volkswagen/carstate.py | 398 ----- car/volkswagen/fingerprints.py | 1201 --------------- car/volkswagen/interface.py | 133 -- car/volkswagen/mqbcan.py | 137 -- car/volkswagen/pqcan.py | 105 -- car/volkswagen/radar_interface.py | 4 - car/volkswagen/tests/test_volkswagen.py | 60 - car/volkswagen/values.py | 516 ------- 119 files changed, 19767 deletions(-) delete mode 100644 car/body/__init__.py delete mode 100644 car/body/bodycan.py delete mode 100644 car/body/carcontroller.py delete mode 100644 car/body/carstate.py delete mode 100644 car/body/fingerprints.py delete mode 100644 car/body/interface.py delete mode 100644 car/body/radar_interface.py delete mode 100644 car/body/values.py delete mode 100644 car/chrysler/__init__.py delete mode 100644 car/chrysler/carcontroller.py delete mode 100644 car/chrysler/carstate.py delete mode 100644 car/chrysler/chryslercan.py delete mode 100644 car/chrysler/fingerprints.py delete mode 100755 car/chrysler/interface.py delete mode 100755 car/chrysler/radar_interface.py delete mode 100644 car/chrysler/values.py delete mode 100644 car/ford/__init__.py delete mode 100644 car/ford/carcontroller.py delete mode 100644 car/ford/carstate.py delete mode 100644 car/ford/fingerprints.py delete mode 100644 car/ford/fordcan.py delete mode 100644 car/ford/interface.py delete mode 100644 car/ford/radar_interface.py delete mode 100644 car/ford/tests/__init__.py delete mode 100755 car/ford/tests/print_platform_codes.py delete mode 100644 car/ford/tests/test_ford.py delete mode 100644 car/ford/values.py delete mode 100644 car/gm/__init__.py delete mode 100644 car/gm/carcontroller.py delete mode 100644 car/gm/carstate.py delete mode 100644 car/gm/fingerprints.py delete mode 100644 car/gm/gmcan.py delete mode 100755 car/gm/interface.py delete mode 100755 car/gm/radar_interface.py delete mode 100644 car/gm/tests/__init__.py delete mode 100644 car/gm/tests/test_gm.py delete mode 100644 car/gm/values.py delete mode 100644 car/honda/__init__.py delete mode 100644 car/honda/carcontroller.py delete mode 100644 car/honda/carstate.py delete mode 100644 car/honda/fingerprints.py delete mode 100644 car/honda/hondacan.py delete mode 100755 car/honda/interface.py delete mode 100755 car/honda/radar_interface.py delete mode 100644 car/honda/tests/__init__.py delete mode 100644 car/honda/tests/test_honda.py delete mode 100644 car/honda/values.py delete mode 100644 car/hyundai/__init__.py delete mode 100644 car/hyundai/carcontroller.py delete mode 100644 car/hyundai/carstate.py delete mode 100644 car/hyundai/fingerprints.py delete mode 100644 car/hyundai/hyundaican.py delete mode 100644 car/hyundai/hyundaicanfd.py delete mode 100644 car/hyundai/interface.py delete mode 100644 car/hyundai/radar_interface.py delete mode 100644 car/hyundai/tests/__init__.py delete mode 100755 car/hyundai/tests/print_platform_codes.py delete mode 100644 car/hyundai/tests/test_hyundai.py delete mode 100644 car/hyundai/values.py delete mode 100644 car/mazda/__init__.py delete mode 100644 car/mazda/carcontroller.py delete mode 100644 car/mazda/carstate.py delete mode 100644 car/mazda/fingerprints.py delete mode 100755 car/mazda/interface.py delete mode 100644 car/mazda/mazdacan.py delete mode 100755 car/mazda/radar_interface.py delete mode 100644 car/mazda/values.py delete mode 100644 car/mock/__init__.py delete mode 100644 car/mock/carcontroller.py delete mode 100644 car/mock/carstate.py delete mode 100755 car/mock/interface.py delete mode 100644 car/mock/radar_interface.py delete mode 100644 car/mock/values.py delete mode 100644 car/nissan/__init__.py delete mode 100644 car/nissan/carcontroller.py delete mode 100644 car/nissan/carstate.py delete mode 100644 car/nissan/fingerprints.py delete mode 100644 car/nissan/interface.py delete mode 100644 car/nissan/nissancan.py delete mode 100644 car/nissan/radar_interface.py delete mode 100644 car/nissan/values.py delete mode 100644 car/subaru/__init__.py delete mode 100644 car/subaru/carcontroller.py delete mode 100644 car/subaru/carstate.py delete mode 100644 car/subaru/fingerprints.py delete mode 100644 car/subaru/interface.py delete mode 100644 car/subaru/radar_interface.py delete mode 100644 car/subaru/subarucan.py delete mode 100644 car/subaru/tests/test_subaru.py delete mode 100644 car/subaru/values.py delete mode 100644 car/tesla/__init__.py delete mode 100644 car/tesla/carcontroller.py delete mode 100644 car/tesla/carstate.py delete mode 100644 car/tesla/fingerprints.py delete mode 100755 car/tesla/interface.py delete mode 100755 car/tesla/radar_interface.py delete mode 100644 car/tesla/teslacan.py delete mode 100644 car/tesla/values.py delete mode 100644 car/toyota/__init__.py delete mode 100644 car/toyota/carcontroller.py delete mode 100644 car/toyota/carstate.py delete mode 100644 car/toyota/fingerprints.py delete mode 100644 car/toyota/interface.py delete mode 100755 car/toyota/radar_interface.py delete mode 100644 car/toyota/tests/__init__.py delete mode 100755 car/toyota/tests/print_platform_codes.py delete mode 100644 car/toyota/tests/test_toyota.py delete mode 100644 car/toyota/toyotacan.py delete mode 100644 car/toyota/values.py delete mode 100644 car/volkswagen/__init__.py delete mode 100644 car/volkswagen/carcontroller.py delete mode 100644 car/volkswagen/carstate.py delete mode 100644 car/volkswagen/fingerprints.py delete mode 100644 car/volkswagen/interface.py delete mode 100644 car/volkswagen/mqbcan.py delete mode 100644 car/volkswagen/pqcan.py delete mode 100644 car/volkswagen/radar_interface.py delete mode 100644 car/volkswagen/tests/test_volkswagen.py delete mode 100644 car/volkswagen/values.py diff --git a/car/body/__init__.py b/car/body/__init__.py deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/car/body/bodycan.py b/car/body/bodycan.py deleted file mode 100644 index 580e5025ad..0000000000 --- a/car/body/bodycan.py +++ /dev/null @@ -1,7 +0,0 @@ -def create_control(packer, torque_l, torque_r): - values = { - "TORQUE_L": torque_l, - "TORQUE_R": torque_r, - } - - return packer.make_can_msg("TORQUE_CMD", 0, values) diff --git a/car/body/carcontroller.py b/car/body/carcontroller.py deleted file mode 100644 index 259126c416..0000000000 --- a/car/body/carcontroller.py +++ /dev/null @@ -1,84 +0,0 @@ -import numpy as np - -from openpilot.common.realtime import DT_CTRL -from opendbc.can.packer import CANPacker -from openpilot.selfdrive.car.body import bodycan -from openpilot.selfdrive.car.body.values import SPEED_FROM_RPM -from openpilot.selfdrive.car.interfaces import CarControllerBase -from openpilot.selfdrive.controls.lib.pid import PIDController - - -MAX_TORQUE = 500 -MAX_TORQUE_RATE = 50 -MAX_ANGLE_ERROR = np.radians(7) -MAX_POS_INTEGRATOR = 0.2 # meters -MAX_TURN_INTEGRATOR = 0.1 # meters - - -class CarController(CarControllerBase): - def __init__(self, dbc_name, CP, VM): - self.frame = 0 - self.packer = CANPacker(dbc_name) - - # PIDs - self.turn_pid = PIDController(110, k_i=11.5, rate=1/DT_CTRL) - self.wheeled_speed_pid = PIDController(110, k_i=11.5, rate=1/DT_CTRL) - - self.torque_r_filtered = 0. - self.torque_l_filtered = 0. - - @staticmethod - def deadband_filter(torque, deadband): - if torque > 0: - torque += deadband - else: - torque -= deadband - return torque - - def update(self, CC, CS, now_nanos): - - torque_l = 0 - torque_r = 0 - - llk_valid = len(CC.orientationNED) > 1 and len(CC.angularVelocity) > 1 - if CC.enabled and llk_valid: - # Read these from the joystick - # TODO: this isn't acceleration, okay? - speed_desired = CC.actuators.accel / 5. - speed_diff_desired = -CC.actuators.steer / 2. - - speed_measured = SPEED_FROM_RPM * (CS.out.wheelSpeeds.fl + CS.out.wheelSpeeds.fr) / 2. - speed_error = speed_desired - speed_measured - - torque = self.wheeled_speed_pid.update(speed_error, freeze_integrator=False) - - speed_diff_measured = SPEED_FROM_RPM * (CS.out.wheelSpeeds.fl - CS.out.wheelSpeeds.fr) - turn_error = speed_diff_measured - speed_diff_desired - freeze_integrator = ((turn_error < 0 and self.turn_pid.error_integral <= -MAX_TURN_INTEGRATOR) or - (turn_error > 0 and self.turn_pid.error_integral >= MAX_TURN_INTEGRATOR)) - torque_diff = self.turn_pid.update(turn_error, freeze_integrator=freeze_integrator) - - # Combine 2 PIDs outputs - torque_r = torque + torque_diff - torque_l = torque - torque_diff - - # Torque rate limits - self.torque_r_filtered = np.clip(self.deadband_filter(torque_r, 10), - self.torque_r_filtered - MAX_TORQUE_RATE, - self.torque_r_filtered + MAX_TORQUE_RATE) - self.torque_l_filtered = np.clip(self.deadband_filter(torque_l, 10), - self.torque_l_filtered - MAX_TORQUE_RATE, - self.torque_l_filtered + MAX_TORQUE_RATE) - torque_r = int(np.clip(self.torque_r_filtered, -MAX_TORQUE, MAX_TORQUE)) - torque_l = int(np.clip(self.torque_l_filtered, -MAX_TORQUE, MAX_TORQUE)) - - can_sends = [] - can_sends.append(bodycan.create_control(self.packer, torque_l, torque_r)) - - new_actuators = CC.actuators.as_builder() - new_actuators.accel = torque_l - new_actuators.steer = torque_r - new_actuators.steerOutputCan = torque_r - - self.frame += 1 - return new_actuators, can_sends diff --git a/car/body/carstate.py b/car/body/carstate.py deleted file mode 100644 index fca9bcc627..0000000000 --- a/car/body/carstate.py +++ /dev/null @@ -1,40 +0,0 @@ -from cereal import car -from opendbc.can.parser import CANParser -from openpilot.selfdrive.car.interfaces import CarStateBase -from openpilot.selfdrive.car.body.values import DBC - -STARTUP_TICKS = 100 - -class CarState(CarStateBase): - def update(self, cp): - ret = car.CarState.new_message() - - ret.wheelSpeeds.fl = cp.vl['MOTORS_DATA']['SPEED_L'] - ret.wheelSpeeds.fr = cp.vl['MOTORS_DATA']['SPEED_R'] - - ret.vEgoRaw = ((ret.wheelSpeeds.fl + ret.wheelSpeeds.fr) / 2.) * self.CP.wheelSpeedFactor - - ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) - ret.standstill = False - - ret.steerFaultPermanent = any([cp.vl['VAR_VALUES']['MOTOR_ERR_L'], cp.vl['VAR_VALUES']['MOTOR_ERR_R'], - cp.vl['VAR_VALUES']['FAULT']]) - - ret.charging = cp.vl["BODY_DATA"]["CHARGER_CONNECTED"] == 1 - ret.fuelGauge = cp.vl["BODY_DATA"]["BATT_PERCENTAGE"] / 100 - - # irrelevant for non-car - ret.gearShifter = car.CarState.GearShifter.drive - ret.cruiseState.enabled = True - ret.cruiseState.available = True - - return ret - - @staticmethod - def get_can_parser(CP): - messages = [ - ("MOTORS_DATA", 100), - ("VAR_VALUES", 10), - ("BODY_DATA", 1), - ] - return CANParser(DBC[CP.carFingerprint]["pt"], messages, 0) diff --git a/car/body/fingerprints.py b/car/body/fingerprints.py deleted file mode 100644 index ab7a5f8d7b..0000000000 --- a/car/body/fingerprints.py +++ /dev/null @@ -1,28 +0,0 @@ -# ruff: noqa: E501 -from cereal import car -from openpilot.selfdrive.car.body.values import CAR - -Ecu = car.CarParams.Ecu - -# debug ecu fw version is the git hash of the firmware - - -FINGERPRINTS = { - CAR.COMMA_BODY: [{ - 513: 8, 516: 8, 514: 3, 515: 4 - }], -} - -FW_VERSIONS = { - CAR.COMMA_BODY: { - (Ecu.engine, 0x720, None): [ - b'0.0.01', - b'0.3.00a', - b'02/27/2022', - ], - (Ecu.debug, 0x721, None): [ - b'166bd860', - b'dc780f85', - ], - }, -} diff --git a/car/body/interface.py b/car/body/interface.py deleted file mode 100644 index f797a7ecf8..0000000000 --- a/car/body/interface.py +++ /dev/null @@ -1,39 +0,0 @@ -import math -from cereal import car -from openpilot.common.realtime import DT_CTRL -from openpilot.selfdrive.car import get_safety_config -from openpilot.selfdrive.car.interfaces import CarInterfaceBase -from openpilot.selfdrive.car.body.values import SPEED_FROM_RPM - -class CarInterface(CarInterfaceBase): - @staticmethod - def _get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs): - ret.notCar = True - ret.carName = "body" - ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.body)] - - ret.minSteerSpeed = -math.inf - ret.maxLateralAccel = math.inf # TODO: set to a reasonable value - ret.steerLimitTimer = 1.0 - ret.steerActuatorDelay = 0. - - ret.wheelSpeedFactor = SPEED_FROM_RPM - - ret.radarUnavailable = True - ret.openpilotLongitudinalControl = True - ret.steerControlType = car.CarParams.SteerControlType.angle - - return ret - - def _update(self, c): - ret = self.CS.update(self.cp) - - # wait for everything to init first - if self.frame > int(5. / DT_CTRL): - # body always wants to enable - ret.init('events', 1) - ret.events[0].name = car.CarEvent.EventName.pcmEnable - ret.events[0].enable = True - self.frame += 1 - - return ret diff --git a/car/body/radar_interface.py b/car/body/radar_interface.py deleted file mode 100644 index e654bd61fd..0000000000 --- a/car/body/radar_interface.py +++ /dev/null @@ -1,4 +0,0 @@ -from openpilot.selfdrive.car.interfaces import RadarInterfaceBase - -class RadarInterface(RadarInterfaceBase): - pass diff --git a/car/body/values.py b/car/body/values.py deleted file mode 100644 index a1195f7cb5..0000000000 --- a/car/body/values.py +++ /dev/null @@ -1,40 +0,0 @@ -from cereal import car -from openpilot.selfdrive.car import CarSpecs, PlatformConfig, Platforms, dbc_dict -from openpilot.selfdrive.car.docs_definitions import CarDocs -from openpilot.selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries - -Ecu = car.CarParams.Ecu - -SPEED_FROM_RPM = 0.008587 - - -class CarControllerParams: - ANGLE_DELTA_BP = [0., 5., 15.] - ANGLE_DELTA_V = [5., .8, .15] # windup limit - ANGLE_DELTA_VU = [5., 3.5, 0.4] # unwind limit - LKAS_MAX_TORQUE = 1 # A value of 1 is easy to overpower - STEER_THRESHOLD = 1.0 - - def __init__(self, CP): - pass - - -class CAR(Platforms): - COMMA_BODY = PlatformConfig( - [CarDocs("comma body", package="All")], - CarSpecs(mass=9, wheelbase=0.406, steerRatio=0.5, centerToFrontRatio=0.44), - dbc_dict('comma_body', None), - ) - - -FW_QUERY_CONFIG = FwQueryConfig( - requests=[ - Request( - [StdQueries.TESTER_PRESENT_REQUEST, StdQueries.UDS_VERSION_REQUEST], - [StdQueries.TESTER_PRESENT_RESPONSE, StdQueries.UDS_VERSION_RESPONSE], - bus=0, - ), - ], -) - -DBC = CAR.create_dbc_map() diff --git a/car/chrysler/__init__.py b/car/chrysler/__init__.py deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/car/chrysler/carcontroller.py b/car/chrysler/carcontroller.py deleted file mode 100644 index 85f53f68eb..0000000000 --- a/car/chrysler/carcontroller.py +++ /dev/null @@ -1,85 +0,0 @@ -from opendbc.can.packer import CANPacker -from openpilot.common.realtime import DT_CTRL -from openpilot.selfdrive.car import apply_meas_steer_torque_limits -from openpilot.selfdrive.car.chrysler import chryslercan -from openpilot.selfdrive.car.chrysler.values import RAM_CARS, CarControllerParams, ChryslerFlags -from openpilot.selfdrive.car.interfaces import CarControllerBase - - -class CarController(CarControllerBase): - def __init__(self, dbc_name, CP, VM): - self.CP = CP - self.apply_steer_last = 0 - self.frame = 0 - - self.hud_count = 0 - self.last_lkas_falling_edge = 0 - self.lkas_control_bit_prev = False - self.last_button_frame = 0 - - self.packer = CANPacker(dbc_name) - self.params = CarControllerParams(CP) - - def update(self, CC, CS, now_nanos): - can_sends = [] - - lkas_active = CC.latActive and self.lkas_control_bit_prev - - # cruise buttons - if (self.frame - self.last_button_frame)*DT_CTRL > 0.05: - das_bus = 2 if self.CP.carFingerprint in RAM_CARS else 0 - - # ACC cancellation - if CC.cruiseControl.cancel: - self.last_button_frame = self.frame - can_sends.append(chryslercan.create_cruise_buttons(self.packer, CS.button_counter + 1, das_bus, cancel=True)) - - # ACC resume from standstill - elif CC.cruiseControl.resume: - self.last_button_frame = self.frame - can_sends.append(chryslercan.create_cruise_buttons(self.packer, CS.button_counter + 1, das_bus, resume=True)) - - # HUD alerts - if self.frame % 25 == 0: - if CS.lkas_car_model != -1: - can_sends.append(chryslercan.create_lkas_hud(self.packer, self.CP, lkas_active, CC.hudControl.visualAlert, - self.hud_count, CS.lkas_car_model, CS.auto_high_beam)) - self.hud_count += 1 - - # steering - if self.frame % self.params.STEER_STEP == 0: - - # TODO: can we make this more sane? why is it different for all the cars? - lkas_control_bit = self.lkas_control_bit_prev - if CS.out.vEgo > self.CP.minSteerSpeed: - lkas_control_bit = True - elif self.CP.flags & ChryslerFlags.HIGHER_MIN_STEERING_SPEED: - if CS.out.vEgo < (self.CP.minSteerSpeed - 3.0): - lkas_control_bit = False - elif self.CP.carFingerprint in RAM_CARS: - if CS.out.vEgo < (self.CP.minSteerSpeed - 0.5): - lkas_control_bit = False - - # EPS faults if LKAS re-enables too quickly - lkas_control_bit = lkas_control_bit and (self.frame - self.last_lkas_falling_edge > 200) - - if not lkas_control_bit and self.lkas_control_bit_prev: - self.last_lkas_falling_edge = self.frame - self.lkas_control_bit_prev = lkas_control_bit - - # steer torque - new_steer = int(round(CC.actuators.steer * self.params.STEER_MAX)) - apply_steer = apply_meas_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorqueEps, self.params) - if not lkas_active or not lkas_control_bit: - apply_steer = 0 - self.apply_steer_last = apply_steer - - can_sends.append(chryslercan.create_lkas_command(self.packer, self.CP, int(apply_steer), lkas_control_bit)) - - self.frame += 1 - - new_actuators = CC.actuators.as_builder() - new_actuators.steer = self.apply_steer_last / self.params.STEER_MAX - new_actuators.steerOutputCan = self.apply_steer_last - - return new_actuators, can_sends diff --git a/car/chrysler/carstate.py b/car/chrysler/carstate.py deleted file mode 100644 index 91b922c596..0000000000 --- a/car/chrysler/carstate.py +++ /dev/null @@ -1,156 +0,0 @@ -from cereal import car -from openpilot.common.conversions import Conversions as CV -from opendbc.can.parser import CANParser -from opendbc.can.can_define import CANDefine -from openpilot.selfdrive.car.interfaces import CarStateBase -from openpilot.selfdrive.car.chrysler.values import DBC, STEER_THRESHOLD, RAM_CARS - - -class CarState(CarStateBase): - def __init__(self, CP): - super().__init__(CP) - self.CP = CP - can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) - - self.auto_high_beam = 0 - self.button_counter = 0 - self.lkas_car_model = -1 - - if CP.carFingerprint in RAM_CARS: - self.shifter_values = can_define.dv["Transmission_Status"]["Gear_State"] - else: - self.shifter_values = can_define.dv["GEAR"]["PRNDL"] - - self.prev_distance_button = 0 - self.distance_button = 0 - - def update(self, cp, cp_cam): - - ret = car.CarState.new_message() - - self.prev_distance_button = self.distance_button - self.distance_button = cp.vl["CRUISE_BUTTONS"]["ACC_Distance_Dec"] - - # lock info - ret.doorOpen = any([cp.vl["BCM_1"]["DOOR_OPEN_FL"], - cp.vl["BCM_1"]["DOOR_OPEN_FR"], - cp.vl["BCM_1"]["DOOR_OPEN_RL"], - cp.vl["BCM_1"]["DOOR_OPEN_RR"]]) - ret.seatbeltUnlatched = cp.vl["ORC_1"]["SEATBELT_DRIVER_UNLATCHED"] == 1 - - # brake pedal - ret.brake = 0 - ret.brakePressed = cp.vl["ESP_1"]['Brake_Pedal_State'] == 1 # Physical brake pedal switch - - # gas pedal - ret.gas = cp.vl["ECM_5"]["Accelerator_Position"] - ret.gasPressed = ret.gas > 1e-5 - - # car speed - if self.CP.carFingerprint in RAM_CARS: - ret.vEgoRaw = cp.vl["ESP_8"]["Vehicle_Speed"] * CV.KPH_TO_MS - ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(cp.vl["Transmission_Status"]["Gear_State"], None)) - else: - ret.vEgoRaw = (cp.vl["SPEED_1"]["SPEED_LEFT"] + cp.vl["SPEED_1"]["SPEED_RIGHT"]) / 2. - ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(cp.vl["GEAR"]["PRNDL"], None)) - ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) - ret.standstill = not ret.vEgoRaw > 0.001 - ret.wheelSpeeds = self.get_wheel_speeds( - cp.vl["ESP_6"]["WHEEL_SPEED_FL"], - cp.vl["ESP_6"]["WHEEL_SPEED_FR"], - cp.vl["ESP_6"]["WHEEL_SPEED_RL"], - cp.vl["ESP_6"]["WHEEL_SPEED_RR"], - unit=1, - ) - - # button presses - ret.leftBlinker, ret.rightBlinker = self.update_blinker_from_stalk(200, cp.vl["STEERING_LEVERS"]["TURN_SIGNALS"] == 1, - cp.vl["STEERING_LEVERS"]["TURN_SIGNALS"] == 2) - ret.genericToggle = cp.vl["STEERING_LEVERS"]["HIGH_BEAM_PRESSED"] == 1 - - # steering wheel - ret.steeringAngleDeg = cp.vl["STEERING"]["STEERING_ANGLE"] + cp.vl["STEERING"]["STEERING_ANGLE_HP"] - ret.steeringRateDeg = cp.vl["STEERING"]["STEERING_RATE"] - ret.steeringTorque = cp.vl["EPS_2"]["COLUMN_TORQUE"] - ret.steeringTorqueEps = cp.vl["EPS_2"]["EPS_TORQUE_MOTOR"] - ret.steeringPressed = abs(ret.steeringTorque) > STEER_THRESHOLD - - # cruise state - cp_cruise = cp_cam if self.CP.carFingerprint in RAM_CARS else cp - - ret.cruiseState.available = cp_cruise.vl["DAS_3"]["ACC_AVAILABLE"] == 1 - ret.cruiseState.enabled = cp_cruise.vl["DAS_3"]["ACC_ACTIVE"] == 1 - ret.cruiseState.speed = cp_cruise.vl["DAS_4"]["ACC_SET_SPEED_KPH"] * CV.KPH_TO_MS - ret.cruiseState.nonAdaptive = cp_cruise.vl["DAS_4"]["ACC_STATE"] in (1, 2) # 1 NormalCCOn and 2 NormalCCSet - ret.cruiseState.standstill = cp_cruise.vl["DAS_3"]["ACC_STANDSTILL"] == 1 - ret.accFaulted = cp_cruise.vl["DAS_3"]["ACC_FAULTED"] != 0 - - if self.CP.carFingerprint in RAM_CARS: - # Auto High Beam isn't Located in this message on chrysler or jeep currently located in 729 message - self.auto_high_beam = cp_cam.vl["DAS_6"]['AUTO_HIGH_BEAM_ON'] - ret.steerFaultTemporary = cp.vl["EPS_3"]["DASM_FAULT"] == 1 - else: - ret.steerFaultTemporary = cp.vl["EPS_2"]["LKAS_TEMPORARY_FAULT"] == 1 - ret.steerFaultPermanent = cp.vl["EPS_2"]["LKAS_STATE"] == 4 - - # blindspot sensors - if self.CP.enableBsm: - ret.leftBlindspot = cp.vl["BSM_1"]["LEFT_STATUS"] == 1 - ret.rightBlindspot = cp.vl["BSM_1"]["RIGHT_STATUS"] == 1 - - self.lkas_car_model = cp_cam.vl["DAS_6"]["CAR_MODEL"] - self.button_counter = cp.vl["CRUISE_BUTTONS"]["COUNTER"] - - return ret - - @staticmethod - def get_cruise_messages(): - messages = [ - ("DAS_3", 50), - ("DAS_4", 50), - ] - return messages - - @staticmethod - def get_can_parser(CP): - messages = [ - # sig_address, frequency - ("ESP_1", 50), - ("EPS_2", 100), - ("ESP_6", 50), - ("STEERING", 100), - ("ECM_5", 50), - ("CRUISE_BUTTONS", 50), - ("STEERING_LEVERS", 10), - ("ORC_1", 2), - ("BCM_1", 1), - ] - - if CP.enableBsm: - messages.append(("BSM_1", 2)) - - if CP.carFingerprint in RAM_CARS: - messages += [ - ("ESP_8", 50), - ("EPS_3", 50), - ("Transmission_Status", 50), - ] - else: - messages += [ - ("GEAR", 50), - ("SPEED_1", 100), - ] - messages += CarState.get_cruise_messages() - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, 0) - - @staticmethod - def get_cam_can_parser(CP): - messages = [ - ("DAS_6", 4), - ] - - if CP.carFingerprint in RAM_CARS: - messages += CarState.get_cruise_messages() - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, 2) diff --git a/car/chrysler/chryslercan.py b/car/chrysler/chryslercan.py deleted file mode 100644 index 96439f35d8..0000000000 --- a/car/chrysler/chryslercan.py +++ /dev/null @@ -1,71 +0,0 @@ -from cereal import car -from openpilot.selfdrive.car.chrysler.values import RAM_CARS - -GearShifter = car.CarState.GearShifter -VisualAlert = car.CarControl.HUDControl.VisualAlert - -def create_lkas_hud(packer, CP, lkas_active, hud_alert, hud_count, car_model, auto_high_beam): - # LKAS_HUD - Controls what lane-keeping icon is displayed - - # == Color == - # 0 hidden? - # 1 white - # 2 green - # 3 ldw - - # == Lines == - # 03 white Lines - # 04 grey lines - # 09 left lane close - # 0A right lane close - # 0B left Lane very close - # 0C right Lane very close - # 0D left cross cross - # 0E right lane cross - - # == Alerts == - # 7 Normal - # 6 lane departure place hands on wheel - - color = 2 if lkas_active else 1 - lines = 3 if lkas_active else 0 - alerts = 7 if lkas_active else 0 - - if hud_count < (1 * 4): # first 3 seconds, 4Hz - alerts = 1 - - if hud_alert in (VisualAlert.ldw, VisualAlert.steerRequired): - color = 4 - lines = 0 - alerts = 6 - - values = { - "LKAS_ICON_COLOR": color, - "CAR_MODEL": car_model, - "LKAS_LANE_LINES": lines, - "LKAS_ALERTS": alerts, - } - - if CP.carFingerprint in RAM_CARS: - values['AUTO_HIGH_BEAM_ON'] = auto_high_beam - - return packer.make_can_msg("DAS_6", 0, values) - - -def create_lkas_command(packer, CP, apply_steer, lkas_control_bit): - # LKAS_COMMAND Lane-keeping signal to turn the wheel - enabled_val = 2 if CP.carFingerprint in RAM_CARS else 1 - values = { - "STEERING_TORQUE": apply_steer, - "LKAS_CONTROL_BIT": enabled_val if lkas_control_bit else 0, - } - return packer.make_can_msg("LKAS_COMMAND", 0, values) - - -def create_cruise_buttons(packer, frame, bus, cancel=False, resume=False): - values = { - "ACC_Cancel": cancel, - "ACC_Resume": resume, - "COUNTER": frame % 0x10, - } - return packer.make_can_msg("CRUISE_BUTTONS", bus, values) diff --git a/car/chrysler/fingerprints.py b/car/chrysler/fingerprints.py deleted file mode 100644 index 01faa49bf7..0000000000 --- a/car/chrysler/fingerprints.py +++ /dev/null @@ -1,705 +0,0 @@ -from cereal import car -from openpilot.selfdrive.car.chrysler.values import CAR - -Ecu = car.CarParams.Ecu - -FW_VERSIONS = { - CAR.CHRYSLER_PACIFICA_2017_HYBRID: { - (Ecu.combinationMeter, 0x742, None): [ - b'68239262AH', - b'68239262AI', - b'68239262AJ', - b'68239263AH', - b'68239263AJ', - ], - (Ecu.srs, 0x744, None): [ - b'68238840AH', - ], - (Ecu.fwdRadar, 0x753, None): [ - b'68226356AI', - ], - (Ecu.eps, 0x75a, None): [ - b'68288309AC', - b'68288309AD', - ], - (Ecu.engine, 0x7e0, None): [ - b'68277480AV ', - b'68277480AX ', - b'68277480AZ ', - ], - (Ecu.hybrid, 0x7e2, None): [ - b'05190175BF', - b'05190175BH', - b'05190226AK', - ], - }, - CAR.CHRYSLER_PACIFICA_2018: { - (Ecu.combinationMeter, 0x742, None): [ - b'68227902AF', - b'68227902AG', - b'68227902AH', - b'68227905AG', - b'68360252AC', - ], - (Ecu.srs, 0x744, None): [ - b'68211617AF', - b'68211617AG', - b'68358974AC', - b'68405937AA', - ], - (Ecu.abs, 0x747, None): [ - b'68222747AG', - b'68330876AA', - b'68330876AB', - b'68352227AA', - ], - (Ecu.fwdRadar, 0x753, None): [ - b'04672758AA', - b'68226356AF', - b'68226356AH', - b'68226356AI', - ], - (Ecu.eps, 0x75a, None): [ - b'68288891AE', - b'68378884AA', - b'68525338AA', - b'68525338AB', - ], - (Ecu.engine, 0x7e0, None): [ - b'68267018AO ', - b'68267020AJ ', - b'68303534AG ', - b'68303534AJ ', - b'68340762AD ', - b'68340764AD ', - b'68352652AE ', - b'68352654AE ', - b'68366851AH ', - b'68366853AE ', - b'68372861AF ', - ], - (Ecu.transmission, 0x7e1, None): [ - b'68277370AJ', - b'68277370AM', - b'68277372AD', - b'68277372AE', - b'68277372AN', - b'68277374AA', - b'68277374AB', - b'68277374AD', - b'68277374AN', - b'68367471AC', - b'68380571AB', - ], - }, - CAR.CHRYSLER_PACIFICA_2020: { - (Ecu.combinationMeter, 0x742, None): [ - b'68405327AC', - b'68436233AB', - b'68436233AC', - b'68436234AB', - b'68436250AE', - b'68529067AA', - b'68594993AB', - b'68594994AB', - ], - (Ecu.srs, 0x744, None): [ - b'68405565AB', - b'68405565AC', - b'68444299AC', - b'68480707AC', - b'68480708AC', - b'68526663AB', - ], - (Ecu.abs, 0x747, None): [ - b'68397394AA', - b'68433480AB', - b'68453575AF', - b'68577676AA', - b'68593395AA', - ], - (Ecu.fwdRadar, 0x753, None): [ - b'04672758AA', - b'04672758AB', - b'68417813AF', - b'68540436AA', - b'68540436AC', - b'68540436AD', - b'68598670AB', - b'68598670AC', - ], - (Ecu.eps, 0x75a, None): [ - b'68416742AA', - b'68460393AA', - b'68460393AB', - b'68494461AB', - b'68494461AC', - b'68524936AA', - b'68524936AB', - b'68525338AB', - b'68594337AB', - b'68594340AB', - ], - (Ecu.engine, 0x7e0, None): [ - b'68413871AD ', - b'68413871AE ', - b'68413871AH ', - b'68413871AI ', - b'68413873AH ', - b'68413873AI ', - b'68443120AE ', - b'68443123AC ', - b'68443125AC ', - b'68496647AI ', - b'68496647AJ ', - b'68496650AH ', - b'68496650AI ', - b'68496652AH ', - b'68526752AD ', - b'68526752AE ', - b'68526754AE ', - b'68536264AE ', - b'68700304AB ', - b'68700306AB ', - ], - (Ecu.transmission, 0x7e1, None): [ - b'68414271AC', - b'68414271AD', - b'68414275AC', - b'68414275AD', - b'68443154AB', - b'68443155AC', - b'68443158AB', - b'68501050AD', - b'68501051AD', - b'68501055AD', - b'68527221AB', - b'68527223AB', - b'68586231AD', - b'68586233AD', - ], - }, - CAR.CHRYSLER_PACIFICA_2018_HYBRID: { - (Ecu.combinationMeter, 0x742, None): [ - b'68358439AE', - b'68358439AG', - ], - (Ecu.srs, 0x744, None): [ - b'68358990AC', - b'68405939AA', - ], - (Ecu.fwdRadar, 0x753, None): [ - b'04672758AA', - ], - (Ecu.eps, 0x75a, None): [ - b'68288309AD', - b'68525339AA', - ], - (Ecu.engine, 0x7e0, None): [ - b'68366580AI ', - b'68366580AK ', - b'68366580AM ', - ], - (Ecu.hybrid, 0x7e2, None): [ - b'05190226AI', - b'05190226AK', - b'05190226AM', - ], - }, - CAR.CHRYSLER_PACIFICA_2019_HYBRID: { - (Ecu.combinationMeter, 0x742, None): [ - b'68405292AC', - b'68434956AC', - b'68434956AD', - b'68434960AE', - b'68434960AF', - b'68529064AB', - b'68594990AB', - ], - (Ecu.srs, 0x744, None): [ - b'68405567AB', - b'68405567AC', - b'68453076AD', - b'68480710AC', - b'68526665AB', - ], - (Ecu.fwdRadar, 0x753, None): [ - b'04672758AB', - b'68417813AF', - b'68540436AA', - b'68540436AB', - b'68540436AC', - b'68540436AD', - b'68598670AB', - b'68598670AC', - ], - (Ecu.eps, 0x75a, None): [ - b'68416741AA', - b'68460392AA', - b'68525339AA', - b'68525339AB', - b'68594341AB', - ], - (Ecu.engine, 0x7e0, None): [ - b'68416680AE ', - b'68416680AF ', - b'68416680AG ', - b'68444228AD ', - b'68444228AE ', - b'68444228AF ', - b'68499122AD ', - b'68499122AE ', - b'68499122AF ', - b'68526772AD ', - b'68526772AH ', - b'68599493AC ', - ], - (Ecu.hybrid, 0x7e2, None): [ - b'05185116AF', - b'05185116AJ', - b'05185116AK', - b'05190240AP', - b'05190240AQ', - b'05190240AR', - b'05190265AG', - b'05190265AH', - b'05190289AE', - b'68540977AH', - b'68540977AK', - b'68597647AE', - ], - }, - CAR.JEEP_GRAND_CHEROKEE: { - (Ecu.combinationMeter, 0x742, None): [ - b'68243549AG', - b'68302211AC', - b'68302212AD', - b'68302223AC', - b'68302246AC', - b'68331511AC', - b'68331574AC', - b'68331687AC', - b'68331690AC', - b'68340272AD', - ], - (Ecu.srs, 0x744, None): [ - b'68309533AA', - b'68316742AB', - b'68355363AB', - ], - (Ecu.abs, 0x747, None): [ - b'68252642AG', - b'68306178AD', - b'68336276AB', - ], - (Ecu.fwdRadar, 0x753, None): [ - b'04672627AB', - b'68251506AF', - b'68332015AB', - ], - (Ecu.eps, 0x75a, None): [ - b'68276201AG', - b'68321644AB', - b'68321644AC', - b'68321646AC', - b'68321648AC', - ], - (Ecu.engine, 0x7e0, None): [ - b'05035920AE ', - b'68252272AG ', - b'68284455AI ', - b'68284456AI ', - b'68284477AF ', - b'68325564AH ', - b'68325565AH ', - b'68325565AI ', - b'68325618AD ', - ], - (Ecu.transmission, 0x7e1, None): [ - b'05035517AH', - b'68253222AF', - b'68311218AC', - b'68311223AF', - b'68311223AG', - b'68361911AE', - b'68361911AF', - b'68361911AH', - b'68361916AD', - ], - }, - CAR.JEEP_GRAND_CHEROKEE_2019: { - (Ecu.combinationMeter, 0x742, None): [ - b'68402703AB', - b'68402704AB', - b'68402708AB', - b'68402971AD', - b'68454144AD', - b'68454145AB', - b'68454152AB', - b'68454156AB', - b'68516650AB', - b'68516651AB', - b'68516669AB', - b'68516671AB', - b'68516683AB', - ], - (Ecu.srs, 0x744, None): [ - b'68355363AB', - b'68355364AB', - ], - (Ecu.abs, 0x747, None): [ - b'68408639AC', - b'68408639AD', - b'68499978AB', - ], - (Ecu.fwdRadar, 0x753, None): [ - b'04672788AA', - b'68456722AC', - ], - (Ecu.eps, 0x75a, None): [ - b'68417279AA', - b'68417280AA', - b'68417281AA', - b'68453431AA', - b'68453433AA', - b'68453435AA', - b'68499171AA', - b'68499171AB', - b'68501183AA', - ], - (Ecu.engine, 0x7e0, None): [ - b'05035674AB ', - b'68412635AG ', - b'68412660AD ', - b'68422860AB', - b'68449435AE ', - b'68496223AA ', - b'68504959AD ', - b'68504960AD ', - b'68504993AC ', - ], - (Ecu.transmission, 0x7e1, None): [ - b'05035707AA', - b'68419672AC', - b'68419678AB', - b'68423905AB', - b'68449258AC', - b'68495807AA', - b'68495807AB', - b'68503641AC', - b'68503664AC', - ], - }, - CAR.RAM_1500_5TH_GEN: { - (Ecu.combinationMeter, 0x742, None): [ - b'68294051AG', - b'68294051AI', - b'68294052AG', - b'68294052AH', - b'68294063AG', - b'68294063AH', - b'68294063AI', - b'68434846AC', - b'68434847AC', - b'68434849AC', - b'68434856AC', - b'68434858AC', - b'68434859AC', - b'68434860AC', - b'68453483AC', - b'68453483AD', - b'68453487AD', - b'68453491AC', - b'68453499AD', - b'68453503AC', - b'68453503AD', - b'68453505AC', - b'68453505AD', - b'68453511AC', - b'68453513AC', - b'68453513AD', - b'68453514AD', - b'68505633AB', - b'68510277AG', - b'68510277AH', - b'68510280AG', - b'68510282AG', - b'68510282AH', - b'68510283AG', - b'68527346AE', - b'68527361AD', - b'68527375AD', - b'68527381AE', - b'68527382AE', - b'68527383AD', - b'68527387AE', - b'68527403AC', - b'68527403AD', - b'68546047AF', - b'68631938AA', - b'68631939AA', - b'68631940AA', - b'68631940AB', - b'68631942AA', - b'68631943AB', - ], - (Ecu.srs, 0x744, None): [ - b'68428609AB', - b'68441329AB', - b'68473844AB', - b'68490898AA', - b'68500728AA', - b'68615033AA', - b'68615034AA', - ], - (Ecu.abs, 0x747, None): [ - b'68292406AG', - b'68292406AH', - b'68432418AB', - b'68432418AC', - b'68432418AD', - b'68436004AD', - b'68436004AE', - b'68438454AC', - b'68438454AD', - b'68438456AE', - b'68438456AF', - b'68535469AB', - b'68535470AC', - b'68548900AB', - b'68586307AB', - ], - (Ecu.fwdRadar, 0x753, None): [ - b'04672892AB', - b'04672932AB', - b'04672932AC', - b'22DTRHD_AA', - b'68320950AH', - b'68320950AI', - b'68320950AJ', - b'68320950AL', - b'68320950AM', - b'68454268AB', - b'68475160AE', - b'68475160AF', - b'68475160AG', - ], - (Ecu.eps, 0x75a, None): [ - b'21590101AA', - b'21590101AB', - b'68273275AF', - b'68273275AG', - b'68273275AH', - b'68312176AE', - b'68312176AG', - b'68440789AC', - b'68466110AA', - b'68466110AB', - b'68466113AA', - b'68469901AA', - b'68469907AA', - b'68522583AA', - b'68522583AB', - b'68522584AA', - b'68522585AB', - b'68552788AA', - b'68552789AA', - b'68552790AA', - b'68552791AB', - b'68552794AA', - b'68552794AD', - b'68585106AB', - b'68585107AB', - b'68585108AB', - b'68585109AB', - b'68585112AB', - ], - (Ecu.engine, 0x7e0, None): [ - b'05035699AG ', - b'05035841AC ', - b'05035841AD ', - b'05036026AB ', - b'05036065AE ', - b'05036066AE ', - b'05036193AA ', - b'05149368AA ', - b'05149591AD ', - b'05149591AE ', - b'05149592AE ', - b'05149599AE ', - b'05149600AD ', - b'05149605AE ', - b'05149846AA ', - b'05149848AA ', - b'05149848AC ', - b'05190341AD', - b'68378695AJ ', - b'68378696AJ ', - b'68378701AI ', - b'68378702AI ', - b'68378710AL ', - b'68378742AI ', - b'68378742AK ', - b'68378748AL ', - b'68378758AM ', - b'68448163AJ', - b'68448163AK', - b'68448163AL', - b'68448165AG', - b'68448165AK', - b'68455111AC ', - b'68455119AC ', - b'68455145AC ', - b'68455145AE ', - b'68455146AC ', - b'68467915AC ', - b'68467916AC ', - b'68467936AC ', - b'68500630AD', - b'68500630AE', - b'68500631AE', - b'68502719AC ', - b'68502722AC ', - b'68502733AC ', - b'68502734AF ', - b'68502740AF ', - b'68502741AF ', - b'68502742AC ', - b'68502742AF ', - b'68539650AD', - b'68539650AF', - b'68539651AD', - b'68586101AA ', - b'68586105AB ', - b'68629919AC ', - b'68629922AC ', - b'68629925AC ', - b'68629926AC ', - ], - (Ecu.transmission, 0x7e1, None): [ - b'05035706AD', - b'05035842AB', - b'05036069AA', - b'05036181AA', - b'05149536AC', - b'05149537AC', - b'05149543AC', - b'68360078AL', - b'68360080AL', - b'68360080AM', - b'68360081AM', - b'68360085AJ', - b'68360085AL', - b'68360086AH', - b'68360086AK', - b'68384328AD', - b'68384332AD', - b'68445531AC', - b'68445533AB', - b'68445536AB', - b'68445537AB', - b'68466081AB', - b'68466087AB', - b'68484466AC', - b'68484467AC', - b'68484471AC', - b'68502994AD', - b'68502996AD', - b'68520867AE', - b'68520867AF', - b'68520870AC', - b'68540431AB', - b'68540433AB', - b'68551676AA', - b'68629935AB', - b'68629936AC', - ], - }, - CAR.RAM_HD_5TH_GEN: { - (Ecu.combinationMeter, 0x742, None): [ - b'68361606AH', - b'68437735AC', - b'68492693AD', - b'68525485AB', - b'68525487AB', - b'68525498AB', - b'68528791AF', - b'68628474AB', - ], - (Ecu.srs, 0x744, None): [ - b'68399794AC', - b'68428503AA', - b'68428505AA', - b'68428507AA', - ], - (Ecu.abs, 0x747, None): [ - b'68334977AH', - b'68455481AC', - b'68504022AA', - b'68504022AB', - b'68504022AC', - b'68530686AB', - b'68530686AC', - b'68544596AC', - b'68641704AA', - ], - (Ecu.fwdRadar, 0x753, None): [ - b'04672895AB', - b'04672934AB', - b'56029827AG', - b'56029827AH', - b'68462657AE', - b'68484694AD', - b'68484694AE', - b'68615489AB', - ], - (Ecu.eps, 0x761, None): [ - b'68421036AC', - b'68507906AB', - b'68534023AC', - ], - (Ecu.engine, 0x7e0, None): [ - b'52370131AF', - b'52370231AF', - b'52370231AG', - b'52370491AA', - b'52370931CT', - b'52401032AE', - b'52421132AF', - b'52421332AF', - b'68527616AD ', - b'M2370131MB', - b'M2421132MB', - ], - }, - CAR.DODGE_DURANGO: { - (Ecu.combinationMeter, 0x742, None): [ - b'68454261AD', - b'68471535AE', - ], - (Ecu.srs, 0x744, None): [ - b'68355362AB', - b'68492238AD', - ], - (Ecu.abs, 0x747, None): [ - b'68408639AD', - b'68499978AB', - ], - (Ecu.fwdRadar, 0x753, None): [ - b'68440581AE', - b'68456722AC', - ], - (Ecu.eps, 0x75a, None): [ - b'68453435AA', - b'68498477AA', - ], - (Ecu.engine, 0x7e0, None): [ - b'05035786AE ', - b'68449476AE ', - ], - (Ecu.transmission, 0x7e1, None): [ - b'05035826AC', - b'68449265AC', - ], - }, -} diff --git a/car/chrysler/interface.py b/car/chrysler/interface.py deleted file mode 100755 index 217a1a756c..0000000000 --- a/car/chrysler/interface.py +++ /dev/null @@ -1,97 +0,0 @@ -#!/usr/bin/env python3 -from cereal import car -from panda import Panda -from openpilot.selfdrive.car import create_button_events, get_safety_config -from openpilot.selfdrive.car.chrysler.values import CAR, RAM_HD, RAM_DT, RAM_CARS, ChryslerFlags -from openpilot.selfdrive.car.interfaces import CarInterfaceBase - -ButtonType = car.CarState.ButtonEvent.Type - - -class CarInterface(CarInterfaceBase): - @staticmethod - def _get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs): - ret.carName = "chrysler" - ret.dashcamOnly = candidate in RAM_HD - - # radar parsing needs some work, see https://github.com/commaai/openpilot/issues/26842 - ret.radarUnavailable = True # DBC[candidate]['radar'] is None - ret.steerActuatorDelay = 0.1 - ret.steerLimitTimer = 0.4 - - # safety config - ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.chrysler)] - if candidate in RAM_HD: - ret.safetyConfigs[0].safetyParam |= Panda.FLAG_CHRYSLER_RAM_HD - elif candidate in RAM_DT: - ret.safetyConfigs[0].safetyParam |= Panda.FLAG_CHRYSLER_RAM_DT - - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) - if candidate not in RAM_CARS: - # Newer FW versions standard on the following platforms, or flashed by a dealer onto older platforms have a higher minimum steering speed. - new_eps_platform = candidate in (CAR.CHRYSLER_PACIFICA_2019_HYBRID, CAR.CHRYSLER_PACIFICA_2020, CAR.JEEP_GRAND_CHEROKEE_2019, CAR.DODGE_DURANGO) - new_eps_firmware = any(fw.ecu == 'eps' and fw.fwVersion[:4] >= b"6841" for fw in car_fw) - if new_eps_platform or new_eps_firmware: - ret.flags |= ChryslerFlags.HIGHER_MIN_STEERING_SPEED.value - - # Chrysler - if candidate in (CAR.CHRYSLER_PACIFICA_2017_HYBRID, CAR.CHRYSLER_PACIFICA_2018, CAR.CHRYSLER_PACIFICA_2018_HYBRID, \ - CAR.CHRYSLER_PACIFICA_2019_HYBRID, CAR.CHRYSLER_PACIFICA_2020, CAR.DODGE_DURANGO): - ret.lateralTuning.init('pid') - ret.lateralTuning.pid.kpBP, ret.lateralTuning.pid.kiBP = [[9., 20.], [9., 20.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.15, 0.30], [0.03, 0.05]] - ret.lateralTuning.pid.kf = 0.00006 - - # Jeep - elif candidate in (CAR.JEEP_GRAND_CHEROKEE, CAR.JEEP_GRAND_CHEROKEE_2019): - ret.steerActuatorDelay = 0.2 - - ret.lateralTuning.init('pid') - ret.lateralTuning.pid.kpBP, ret.lateralTuning.pid.kiBP = [[9., 20.], [9., 20.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.15, 0.30], [0.03, 0.05]] - ret.lateralTuning.pid.kf = 0.00006 - - # Ram - elif candidate == CAR.RAM_1500_5TH_GEN: - ret.steerActuatorDelay = 0.2 - ret.wheelbase = 3.88 - # Older EPS FW allow steer to zero - if any(fw.ecu == 'eps' and b"68" < fw.fwVersion[:4] <= b"6831" for fw in car_fw): - ret.minSteerSpeed = 0. - - elif candidate == CAR.RAM_HD_5TH_GEN: - ret.steerActuatorDelay = 0.2 - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning, 1.0, False) - - else: - raise ValueError(f"Unsupported car: {candidate}") - - if ret.flags & ChryslerFlags.HIGHER_MIN_STEERING_SPEED: - # TODO: allow these cars to steer down to 13 m/s if already engaged. - # TODO: Durango 2020 may be able to steer to zero once above 38 kph - ret.minSteerSpeed = 17.5 # m/s 17 on the way up, 13 on the way down once engaged. - - ret.centerToFront = ret.wheelbase * 0.44 - ret.enableBsm = 720 in fingerprint[0] - - return ret - - def _update(self, c): - ret = self.CS.update(self.cp, self.cp_cam) - - ret.buttonEvents = create_button_events(self.CS.distance_button, self.CS.prev_distance_button, {1: ButtonType.gapAdjustCruise}) - - # events - events = self.create_common_events(ret, extra_gears=[car.CarState.GearShifter.low]) - - # Low speed steer alert hysteresis logic - if self.CP.minSteerSpeed > 0. and ret.vEgo < (self.CP.minSteerSpeed + 0.5): - self.low_speed_alert = True - elif ret.vEgo > (self.CP.minSteerSpeed + 1.): - self.low_speed_alert = False - if self.low_speed_alert: - events.add(car.CarEvent.EventName.belowSteerSpeed) - - ret.events = events.to_msg() - - return ret diff --git a/car/chrysler/radar_interface.py b/car/chrysler/radar_interface.py deleted file mode 100755 index d982958422..0000000000 --- a/car/chrysler/radar_interface.py +++ /dev/null @@ -1,86 +0,0 @@ -#!/usr/bin/env python3 -from opendbc.can.parser import CANParser -from cereal import car -from openpilot.selfdrive.car.interfaces import RadarInterfaceBase -from openpilot.selfdrive.car.chrysler.values import DBC - -RADAR_MSGS_C = list(range(0x2c2, 0x2d4+2, 2)) # c_ messages 706,...,724 -RADAR_MSGS_D = list(range(0x2a2, 0x2b4+2, 2)) # d_ messages -LAST_MSG = max(RADAR_MSGS_C + RADAR_MSGS_D) -NUMBER_MSGS = len(RADAR_MSGS_C) + len(RADAR_MSGS_D) - -def _create_radar_can_parser(car_fingerprint): - dbc = DBC[car_fingerprint]['radar'] - if dbc is None: - return None - - msg_n = len(RADAR_MSGS_C) - # list of [(signal name, message name or number), (...)] - # [('RADAR_STATE', 1024), - # ('LONG_DIST', 1072), - # ('LONG_DIST', 1073), - # ('LONG_DIST', 1074), - # ('LONG_DIST', 1075), - - messages = list(zip(RADAR_MSGS_C + - RADAR_MSGS_D, - [20] * msg_n + # 20Hz (0.05s) - [20] * msg_n, strict=True)) # 20Hz (0.05s) - - return CANParser(DBC[car_fingerprint]['radar'], messages, 1) - -def _address_to_track(address): - if address in RADAR_MSGS_C: - return (address - RADAR_MSGS_C[0]) // 2 - if address in RADAR_MSGS_D: - return (address - RADAR_MSGS_D[0]) // 2 - raise ValueError("radar received unexpected address %d" % address) - -class RadarInterface(RadarInterfaceBase): - def __init__(self, CP): - super().__init__(CP) - self.CP = CP - self.rcp = _create_radar_can_parser(CP.carFingerprint) - self.updated_messages = set() - self.trigger_msg = LAST_MSG - - def update(self, can_strings): - if self.rcp is None or self.CP.radarUnavailable: - return super().update(None) - - vls = self.rcp.update_strings(can_strings) - self.updated_messages.update(vls) - - if self.trigger_msg not in self.updated_messages: - return None - - ret = car.RadarData.new_message() - errors = [] - if not self.rcp.can_valid: - errors.append("canError") - ret.errors = errors - - for ii in self.updated_messages: # ii should be the message ID as a number - cpt = self.rcp.vl[ii] - trackId = _address_to_track(ii) - - if trackId not in self.pts: - self.pts[trackId] = car.RadarData.RadarPoint.new_message() - self.pts[trackId].trackId = trackId - self.pts[trackId].aRel = float('nan') - self.pts[trackId].yvRel = float('nan') - self.pts[trackId].measured = True - - if 'LONG_DIST' in cpt: # c_* message - self.pts[trackId].dRel = cpt['LONG_DIST'] # from front of car - # our lat_dist is positive to the right in car's frame. - # TODO what does yRel want? - self.pts[trackId].yRel = cpt['LAT_DIST'] # in car frame's y axis, left is positive - else: # d_* message - self.pts[trackId].vRel = cpt['REL_SPEED'] - - # We want a list, not a dictionary. Filter out LONG_DIST==0 because that means it's not valid. - ret.points = [x for x in self.pts.values() if x.dRel != 0] - - self.updated_messages.clear() - return ret diff --git a/car/chrysler/values.py b/car/chrysler/values.py deleted file mode 100644 index 42ea94cf86..0000000000 --- a/car/chrysler/values.py +++ /dev/null @@ -1,156 +0,0 @@ -from enum import IntFlag -from dataclasses import dataclass, field - -from cereal import car -from panda.python import uds -from openpilot.selfdrive.car import CarSpecs, DbcDict, PlatformConfig, Platforms, dbc_dict -from openpilot.selfdrive.car.docs_definitions import CarHarness, CarDocs, CarParts -from openpilot.selfdrive.car.fw_query_definitions import FwQueryConfig, Request, p16 - -Ecu = car.CarParams.Ecu - - -class ChryslerFlags(IntFlag): - # Detected flags - HIGHER_MIN_STEERING_SPEED = 1 - -@dataclass -class ChryslerCarDocs(CarDocs): - package: str = "Adaptive Cruise Control (ACC)" - car_parts: CarParts = field(default_factory=CarParts.common([CarHarness.fca])) - - -@dataclass -class ChryslerPlatformConfig(PlatformConfig): - dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict('chrysler_pacifica_2017_hybrid_generated', 'chrysler_pacifica_2017_hybrid_private_fusion')) - - -@dataclass(frozen=True) -class ChryslerCarSpecs(CarSpecs): - minSteerSpeed: float = 3.8 # m/s - - -class CAR(Platforms): - # Chrysler - CHRYSLER_PACIFICA_2017_HYBRID = ChryslerPlatformConfig( - [ChryslerCarDocs("Chrysler Pacifica Hybrid 2017")], - ChryslerCarSpecs(mass=2242., wheelbase=3.089, steerRatio=16.2), - ) - CHRYSLER_PACIFICA_2018_HYBRID = ChryslerPlatformConfig( - [ChryslerCarDocs("Chrysler Pacifica Hybrid 2018")], - CHRYSLER_PACIFICA_2017_HYBRID.specs, - ) - CHRYSLER_PACIFICA_2019_HYBRID = ChryslerPlatformConfig( - [ChryslerCarDocs("Chrysler Pacifica Hybrid 2019-23")], - CHRYSLER_PACIFICA_2017_HYBRID.specs, - ) - CHRYSLER_PACIFICA_2018 = ChryslerPlatformConfig( - [ChryslerCarDocs("Chrysler Pacifica 2017-18")], - CHRYSLER_PACIFICA_2017_HYBRID.specs, - ) - CHRYSLER_PACIFICA_2020 = ChryslerPlatformConfig( - [ - ChryslerCarDocs("Chrysler Pacifica 2019-20"), - ChryslerCarDocs("Chrysler Pacifica 2021-23", package="All"), - ], - CHRYSLER_PACIFICA_2017_HYBRID.specs, - ) - - # Dodge - DODGE_DURANGO = ChryslerPlatformConfig( - [ChryslerCarDocs("Dodge Durango 2020-21")], - CHRYSLER_PACIFICA_2017_HYBRID.specs, - ) - - # Jeep - JEEP_GRAND_CHEROKEE = ChryslerPlatformConfig( # includes 2017 Trailhawk - [ChryslerCarDocs("Jeep Grand Cherokee 2016-18", video_link="https://www.youtube.com/watch?v=eLR9o2JkuRk")], - ChryslerCarSpecs(mass=1778., wheelbase=2.71, steerRatio=16.7), - ) - - JEEP_GRAND_CHEROKEE_2019 = ChryslerPlatformConfig( # includes 2020 Trailhawk - [ChryslerCarDocs("Jeep Grand Cherokee 2019-21", video_link="https://www.youtube.com/watch?v=jBe4lWnRSu4")], - JEEP_GRAND_CHEROKEE.specs, - ) - - # Ram - RAM_1500_5TH_GEN = ChryslerPlatformConfig( - [ChryslerCarDocs("Ram 1500 2019-24", car_parts=CarParts.common([CarHarness.ram]))], - ChryslerCarSpecs(mass=2493., wheelbase=3.88, steerRatio=16.3, minSteerSpeed=14.5), - dbc_dict('chrysler_ram_dt_generated', None), - ) - RAM_HD_5TH_GEN = ChryslerPlatformConfig( - [ - ChryslerCarDocs("Ram 2500 2020-24", car_parts=CarParts.common([CarHarness.ram])), - ChryslerCarDocs("Ram 3500 2019-22", car_parts=CarParts.common([CarHarness.ram])), - ], - ChryslerCarSpecs(mass=3405., wheelbase=3.785, steerRatio=15.61, minSteerSpeed=16.), - dbc_dict('chrysler_ram_hd_generated', None), - ) - - -class CarControllerParams: - def __init__(self, CP): - self.STEER_STEP = 2 # 50 Hz - self.STEER_ERROR_MAX = 80 - if CP.carFingerprint in RAM_HD: - self.STEER_DELTA_UP = 14 - self.STEER_DELTA_DOWN = 14 - self.STEER_MAX = 361 # higher than this faults the EPS - elif CP.carFingerprint in RAM_DT: - self.STEER_DELTA_UP = 6 - self.STEER_DELTA_DOWN = 6 - self.STEER_MAX = 261 # EPS allows more, up to 350? - else: - self.STEER_DELTA_UP = 3 - self.STEER_DELTA_DOWN = 3 - self.STEER_MAX = 261 # higher than this faults the EPS - - -STEER_THRESHOLD = 120 - -RAM_DT = {CAR.RAM_1500_5TH_GEN, } -RAM_HD = {CAR.RAM_HD_5TH_GEN, } -RAM_CARS = RAM_DT | RAM_HD - - -CHRYSLER_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ - p16(0xf132) -CHRYSLER_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ - p16(0xf132) - -CHRYSLER_SOFTWARE_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ - p16(uds.DATA_IDENTIFIER_TYPE.SYSTEM_SUPPLIER_ECU_SOFTWARE_NUMBER) -CHRYSLER_SOFTWARE_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ - p16(uds.DATA_IDENTIFIER_TYPE.SYSTEM_SUPPLIER_ECU_SOFTWARE_NUMBER) - -CHRYSLER_RX_OFFSET = -0x280 - -FW_QUERY_CONFIG = FwQueryConfig( - requests=[ - Request( - [CHRYSLER_VERSION_REQUEST], - [CHRYSLER_VERSION_RESPONSE], - whitelist_ecus=[Ecu.abs, Ecu.eps, Ecu.srs, Ecu.fwdRadar, Ecu.fwdCamera, Ecu.combinationMeter], - rx_offset=CHRYSLER_RX_OFFSET, - bus=0, - ), - Request( - [CHRYSLER_VERSION_REQUEST], - [CHRYSLER_VERSION_RESPONSE], - whitelist_ecus=[Ecu.abs, Ecu.hybrid, Ecu.engine, Ecu.transmission], - bus=0, - ), - Request( - [CHRYSLER_SOFTWARE_VERSION_REQUEST], - [CHRYSLER_SOFTWARE_VERSION_RESPONSE], - whitelist_ecus=[Ecu.engine, Ecu.transmission], - bus=0, - ), - ], - extra_ecus=[ - (Ecu.abs, 0x7e4, None), # alt address for abs on hybrids, NOTE: not on all hybrid platforms - ], -) - -DBC = CAR.create_dbc_map() diff --git a/car/ford/__init__.py b/car/ford/__init__.py deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/car/ford/carcontroller.py b/car/ford/carcontroller.py deleted file mode 100644 index 7be3b2ebe9..0000000000 --- a/car/ford/carcontroller.py +++ /dev/null @@ -1,120 +0,0 @@ -from cereal import car -from opendbc.can.packer import CANPacker -from openpilot.common.numpy_fast import clip -from openpilot.selfdrive.car import apply_std_steer_angle_limits -from openpilot.selfdrive.car.ford import fordcan -from openpilot.selfdrive.car.ford.values import CarControllerParams, FordFlags -from openpilot.selfdrive.car.interfaces import CarControllerBase -from openpilot.selfdrive.controls.lib.drive_helpers import V_CRUISE_MAX - -LongCtrlState = car.CarControl.Actuators.LongControlState -VisualAlert = car.CarControl.HUDControl.VisualAlert - - -def apply_ford_curvature_limits(apply_curvature, apply_curvature_last, current_curvature, v_ego_raw): - # No blending at low speed due to lack of torque wind-up and inaccurate current curvature - if v_ego_raw > 9: - apply_curvature = clip(apply_curvature, current_curvature - CarControllerParams.CURVATURE_ERROR, - current_curvature + CarControllerParams.CURVATURE_ERROR) - - # Curvature rate limit after driver torque limit - apply_curvature = apply_std_steer_angle_limits(apply_curvature, apply_curvature_last, v_ego_raw, CarControllerParams) - - return clip(apply_curvature, -CarControllerParams.CURVATURE_MAX, CarControllerParams.CURVATURE_MAX) - - -class CarController(CarControllerBase): - def __init__(self, dbc_name, CP, VM): - self.CP = CP - self.VM = VM - self.packer = CANPacker(dbc_name) - self.CAN = fordcan.CanBus(CP) - self.frame = 0 - - self.apply_curvature_last = 0 - self.main_on_last = False - self.lkas_enabled_last = False - self.steer_alert_last = False - self.lead_distance_bars_last = None - - def update(self, CC, CS, now_nanos): - can_sends = [] - - actuators = CC.actuators - hud_control = CC.hudControl - - main_on = CS.out.cruiseState.available - steer_alert = hud_control.visualAlert in (VisualAlert.steerRequired, VisualAlert.ldw) - fcw_alert = hud_control.visualAlert == VisualAlert.fcw - - ### acc buttons ### - if CC.cruiseControl.cancel: - can_sends.append(fordcan.create_button_msg(self.packer, self.CAN.camera, CS.buttons_stock_values, cancel=True)) - can_sends.append(fordcan.create_button_msg(self.packer, self.CAN.main, CS.buttons_stock_values, cancel=True)) - elif CC.cruiseControl.resume and (self.frame % CarControllerParams.BUTTONS_STEP) == 0: - can_sends.append(fordcan.create_button_msg(self.packer, self.CAN.camera, CS.buttons_stock_values, resume=True)) - can_sends.append(fordcan.create_button_msg(self.packer, self.CAN.main, CS.buttons_stock_values, resume=True)) - # if stock lane centering isn't off, send a button press to toggle it off - # the stock system checks for steering pressed, and eventually disengages cruise control - elif CS.acc_tja_status_stock_values["Tja_D_Stat"] != 0 and (self.frame % CarControllerParams.ACC_UI_STEP) == 0: - can_sends.append(fordcan.create_button_msg(self.packer, self.CAN.camera, CS.buttons_stock_values, tja_toggle=True)) - - ### lateral control ### - # send steer msg at 20Hz - if (self.frame % CarControllerParams.STEER_STEP) == 0: - if CC.latActive: - # apply rate limits, curvature error limit, and clip to signal range - current_curvature = -CS.out.yawRate / max(CS.out.vEgoRaw, 0.1) - apply_curvature = apply_ford_curvature_limits(actuators.curvature, self.apply_curvature_last, current_curvature, CS.out.vEgoRaw) - else: - apply_curvature = 0. - - self.apply_curvature_last = apply_curvature - - if self.CP.flags & FordFlags.CANFD: - # TODO: extended mode - mode = 1 if CC.latActive else 0 - counter = (self.frame // CarControllerParams.STEER_STEP) % 0x10 - can_sends.append(fordcan.create_lat_ctl2_msg(self.packer, self.CAN, mode, 0., 0., -apply_curvature, 0., counter)) - else: - can_sends.append(fordcan.create_lat_ctl_msg(self.packer, self.CAN, CC.latActive, 0., 0., -apply_curvature, 0.)) - - # send lka msg at 33Hz - if (self.frame % CarControllerParams.LKA_STEP) == 0: - can_sends.append(fordcan.create_lka_msg(self.packer, self.CAN)) - - ### longitudinal control ### - # send acc msg at 50Hz - if self.CP.openpilotLongitudinalControl and (self.frame % CarControllerParams.ACC_CONTROL_STEP) == 0: - # Both gas and accel are in m/s^2, accel is used solely for braking - accel = clip(actuators.accel, CarControllerParams.ACCEL_MIN, CarControllerParams.ACCEL_MAX) - gas = accel - if not CC.longActive or gas < CarControllerParams.MIN_GAS: - gas = CarControllerParams.INACTIVE_GAS - stopping = CC.actuators.longControlState == LongCtrlState.stopping - can_sends.append(fordcan.create_acc_msg(self.packer, self.CAN, CC.longActive, gas, accel, stopping, v_ego_kph=V_CRUISE_MAX)) - - ### ui ### - send_ui = (self.main_on_last != main_on) or (self.lkas_enabled_last != CC.latActive) or (self.steer_alert_last != steer_alert) - # send lkas ui msg at 1Hz or if ui state changes - if (self.frame % CarControllerParams.LKAS_UI_STEP) == 0 or send_ui: - can_sends.append(fordcan.create_lkas_ui_msg(self.packer, self.CAN, main_on, CC.latActive, steer_alert, hud_control, CS.lkas_status_stock_values)) - - # send acc ui msg at 5Hz or if ui state changes - if hud_control.leadDistanceBars != self.lead_distance_bars_last: - send_ui = True - if (self.frame % CarControllerParams.ACC_UI_STEP) == 0 or send_ui: - can_sends.append(fordcan.create_acc_ui_msg(self.packer, self.CAN, self.CP, main_on, CC.latActive, - fcw_alert, CS.out.cruiseState.standstill, hud_control, - CS.acc_tja_status_stock_values)) - - self.main_on_last = main_on - self.lkas_enabled_last = CC.latActive - self.steer_alert_last = steer_alert - self.lead_distance_bars_last = hud_control.leadDistanceBars - - new_actuators = actuators.as_builder() - new_actuators.curvature = self.apply_curvature_last - - self.frame += 1 - return new_actuators, can_sends diff --git a/car/ford/carstate.py b/car/ford/carstate.py deleted file mode 100644 index 78f48ec5c4..0000000000 --- a/car/ford/carstate.py +++ /dev/null @@ -1,174 +0,0 @@ -from cereal import car -from opendbc.can.can_define import CANDefine -from opendbc.can.parser import CANParser -from openpilot.common.conversions import Conversions as CV -from openpilot.selfdrive.car.ford.fordcan import CanBus -from openpilot.selfdrive.car.ford.values import DBC, CarControllerParams, FordFlags -from openpilot.selfdrive.car.interfaces import CarStateBase - -GearShifter = car.CarState.GearShifter -TransmissionType = car.CarParams.TransmissionType - - -class CarState(CarStateBase): - def __init__(self, CP): - super().__init__(CP) - can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) - if CP.transmissionType == TransmissionType.automatic: - self.shifter_values = can_define.dv["Gear_Shift_by_Wire_FD1"]["TrnRng_D_RqGsm"] - - self.vehicle_sensors_valid = False - - self.prev_distance_button = 0 - self.distance_button = 0 - - def update(self, cp, cp_cam): - ret = car.CarState.new_message() - - # Occasionally on startup, the ABS module recalibrates the steering pinion offset, so we need to block engagement - # The vehicle usually recovers out of this state within a minute of normal driving - self.vehicle_sensors_valid = cp.vl["SteeringPinion_Data"]["StePinCompAnEst_D_Qf"] == 3 - - # car speed - ret.vEgoRaw = cp.vl["BrakeSysFeatures"]["Veh_V_ActlBrk"] * CV.KPH_TO_MS - ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) - ret.yawRate = cp.vl["Yaw_Data_FD1"]["VehYaw_W_Actl"] - ret.standstill = cp.vl["DesiredTorqBrk"]["VehStop_D_Stat"] == 1 - - # gas pedal - ret.gas = cp.vl["EngVehicleSpThrottle"]["ApedPos_Pc_ActlArb"] / 100. - ret.gasPressed = ret.gas > 1e-6 - - # brake pedal - ret.brake = cp.vl["BrakeSnData_4"]["BrkTot_Tq_Actl"] / 32756. # torque in Nm - ret.brakePressed = cp.vl["EngBrakeData"]["BpedDrvAppl_D_Actl"] == 2 - ret.parkingBrake = cp.vl["DesiredTorqBrk"]["PrkBrkStatus"] in (1, 2) - - # steering wheel - ret.steeringAngleDeg = cp.vl["SteeringPinion_Data"]["StePinComp_An_Est"] - ret.steeringTorque = cp.vl["EPAS_INFO"]["SteeringColumnTorque"] - ret.steeringPressed = self.update_steering_pressed(abs(ret.steeringTorque) > CarControllerParams.STEER_DRIVER_ALLOWANCE, 5) - ret.steerFaultTemporary = cp.vl["EPAS_INFO"]["EPAS_Failure"] == 1 - ret.steerFaultPermanent = cp.vl["EPAS_INFO"]["EPAS_Failure"] in (2, 3) - ret.espDisabled = cp.vl["Cluster_Info1_FD1"]["DrvSlipCtlMde_D_Rq"] != 0 # 0 is default mode - - if self.CP.flags & FordFlags.CANFD: - # this signal is always 0 on non-CAN FD cars - ret.steerFaultTemporary |= cp.vl["Lane_Assist_Data3_FD1"]["LatCtlSte_D_Stat"] not in (1, 2, 3) - - # cruise state - is_metric = cp.vl["INSTRUMENT_PANEL"]["METRIC_UNITS"] == 1 if not self.CP.flags & FordFlags.CANFD else False - ret.cruiseState.speed = cp.vl["EngBrakeData"]["Veh_V_DsplyCcSet"] * (CV.KPH_TO_MS if is_metric else CV.MPH_TO_MS) - ret.cruiseState.enabled = cp.vl["EngBrakeData"]["CcStat_D_Actl"] in (4, 5) - ret.cruiseState.available = cp.vl["EngBrakeData"]["CcStat_D_Actl"] in (3, 4, 5) - ret.cruiseState.nonAdaptive = cp.vl["Cluster_Info1_FD1"]["AccEnbl_B_RqDrv"] == 0 - ret.cruiseState.standstill = cp.vl["EngBrakeData"]["AccStopMde_D_Rq"] == 3 - ret.accFaulted = cp.vl["EngBrakeData"]["CcStat_D_Actl"] in (1, 2) - if not self.CP.openpilotLongitudinalControl: - ret.accFaulted = ret.accFaulted or cp_cam.vl["ACCDATA"]["CmbbDeny_B_Actl"] == 1 - - # gear - if self.CP.transmissionType == TransmissionType.automatic: - gear = self.shifter_values.get(cp.vl["Gear_Shift_by_Wire_FD1"]["TrnRng_D_RqGsm"]) - ret.gearShifter = self.parse_gear_shifter(gear) - elif self.CP.transmissionType == TransmissionType.manual: - ret.clutchPressed = cp.vl["Engine_Clutch_Data"]["CluPdlPos_Pc_Meas"] > 0 - if bool(cp.vl["BCM_Lamp_Stat_FD1"]["RvrseLghtOn_B_Stat"]): - ret.gearShifter = GearShifter.reverse - else: - ret.gearShifter = GearShifter.drive - - # safety - ret.stockFcw = bool(cp_cam.vl["ACCDATA_3"]["FcwVisblWarn_B_Rq"]) - ret.stockAeb = bool(cp_cam.vl["ACCDATA_2"]["CmbbBrkDecel_B_Rq"]) - - # button presses - ret.leftBlinker = cp.vl["Steering_Data_FD1"]["TurnLghtSwtch_D_Stat"] == 1 - ret.rightBlinker = cp.vl["Steering_Data_FD1"]["TurnLghtSwtch_D_Stat"] == 2 - # TODO: block this going to the camera otherwise it will enable stock TJA - ret.genericToggle = bool(cp.vl["Steering_Data_FD1"]["TjaButtnOnOffPress"]) - self.prev_distance_button = self.distance_button - self.distance_button = cp.vl["Steering_Data_FD1"]["AccButtnGapTogglePress"] - - # lock info - ret.doorOpen = any([cp.vl["BodyInfo_3_FD1"]["DrStatDrv_B_Actl"], cp.vl["BodyInfo_3_FD1"]["DrStatPsngr_B_Actl"], - cp.vl["BodyInfo_3_FD1"]["DrStatRl_B_Actl"], cp.vl["BodyInfo_3_FD1"]["DrStatRr_B_Actl"]]) - ret.seatbeltUnlatched = cp.vl["RCMStatusMessage2_FD1"]["FirstRowBuckleDriver"] == 2 - - # blindspot sensors - if self.CP.enableBsm: - cp_bsm = cp_cam if self.CP.flags & FordFlags.CANFD else cp - ret.leftBlindspot = cp_bsm.vl["Side_Detect_L_Stat"]["SodDetctLeft_D_Stat"] != 0 - ret.rightBlindspot = cp_bsm.vl["Side_Detect_R_Stat"]["SodDetctRight_D_Stat"] != 0 - - # Stock steering buttons so that we can passthru blinkers etc. - self.buttons_stock_values = cp.vl["Steering_Data_FD1"] - # Stock values from IPMA so that we can retain some stock functionality - self.acc_tja_status_stock_values = cp_cam.vl["ACCDATA_3"] - self.lkas_status_stock_values = cp_cam.vl["IPMA_Data"] - - return ret - - @staticmethod - def get_can_parser(CP): - messages = [ - # sig_address, frequency - ("VehicleOperatingModes", 100), - ("BrakeSysFeatures", 50), - ("Yaw_Data_FD1", 100), - ("DesiredTorqBrk", 50), - ("EngVehicleSpThrottle", 100), - ("BrakeSnData_4", 50), - ("EngBrakeData", 10), - ("Cluster_Info1_FD1", 10), - ("SteeringPinion_Data", 100), - ("EPAS_INFO", 50), - ("Steering_Data_FD1", 10), - ("BodyInfo_3_FD1", 2), - ("RCMStatusMessage2_FD1", 10), - ] - - if CP.flags & FordFlags.CANFD: - messages += [ - ("Lane_Assist_Data3_FD1", 33), - ] - else: - messages += [ - ("INSTRUMENT_PANEL", 1), - ] - - if CP.transmissionType == TransmissionType.automatic: - messages += [ - ("Gear_Shift_by_Wire_FD1", 10), - ] - elif CP.transmissionType == TransmissionType.manual: - messages += [ - ("Engine_Clutch_Data", 33), - ("BCM_Lamp_Stat_FD1", 1), - ] - - if CP.enableBsm and not (CP.flags & FordFlags.CANFD): - messages += [ - ("Side_Detect_L_Stat", 5), - ("Side_Detect_R_Stat", 5), - ] - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus(CP).main) - - @staticmethod - def get_cam_can_parser(CP): - messages = [ - # sig_address, frequency - ("ACCDATA", 50), - ("ACCDATA_2", 50), - ("ACCDATA_3", 5), - ("IPMA_Data", 1), - ] - - if CP.enableBsm and CP.flags & FordFlags.CANFD: - messages += [ - ("Side_Detect_L_Stat", 5), - ("Side_Detect_R_Stat", 5), - ] - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus(CP).camera) diff --git a/car/ford/fingerprints.py b/car/ford/fingerprints.py deleted file mode 100644 index 2201072fa3..0000000000 --- a/car/ford/fingerprints.py +++ /dev/null @@ -1,166 +0,0 @@ -from cereal import car -from openpilot.selfdrive.car.ford.values import CAR - -Ecu = car.CarParams.Ecu - -FW_VERSIONS = { - CAR.FORD_BRONCO_SPORT_MK1: { - (Ecu.eps, 0x730, None): [ - b'LX6C-14D003-AH\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LX6C-14D003-AK\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LX6C-14D003-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'LX6C-2D053-RD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LX6C-2D053-RE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LX6C-2D053-RF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'LB5T-14D049-AB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'M1PT-14F397-AC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'M1PT-14F397-AD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - CAR.FORD_ESCAPE_MK4: { - (Ecu.eps, 0x730, None): [ - b'LX6C-14D003-AF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LX6C-14D003-AH\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LX6C-14D003-AK\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LX6C-14D003-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'LX6C-2D053-NS\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LX6C-2D053-NT\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LX6C-2D053-NY\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LX6C-2D053-SA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LX6C-2D053-SD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'LB5T-14D049-AB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'LJ6T-14F397-AD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LJ6T-14F397-AE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LV4T-14F397-GG\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - CAR.FORD_EXPLORER_MK6: { - (Ecu.eps, 0x730, None): [ - b'L1MC-14D003-AJ\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'L1MC-14D003-AK\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'L1MC-14D003-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'M1MC-14D003-AB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'M1MC-14D003-AC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'P1MC-14D003-AA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'L1MC-2D053-AJ\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'L1MC-2D053-BA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'L1MC-2D053-BB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'L1MC-2D053-BD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'L1MC-2D053-BF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'L1MC-2D053-BJ\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'L1MC-2D053-KB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'LB5T-14D049-AB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'LB5T-14F397-AD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LB5T-14F397-AE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LB5T-14F397-AF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LC5T-14F397-AE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LC5T-14F397-AH\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - CAR.FORD_F_150_MK14: { - (Ecu.eps, 0x730, None): [ - b'ML3V-14D003-BC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'PL34-2D053-CA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'ML3T-14D049-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'ML3T-14H102-ABR\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PJ6T-14H102-ABJ\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - CAR.FORD_F_150_LIGHTNING_MK1: { - (Ecu.abs, 0x760, None): [ - b'PL38-2D053-AA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'ML3T-14H102-ABT\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'ML3T-14D049-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - CAR.FORD_MUSTANG_MACH_E_MK1: { - (Ecu.eps, 0x730, None): [ - b'LJ9C-14D003-AM\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'LJ9C-14D003-CC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'LK9C-2D053-CK\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'ML3T-14D049-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'ML3T-14H102-ABS\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - CAR.FORD_FOCUS_MK4: { - (Ecu.eps, 0x730, None): [ - b'JX6C-14D003-AH\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'JX61-2D053-CJ\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'JX7T-14D049-AC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'JX7T-14F397-AH\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - CAR.FORD_MAVERICK_MK1: { - (Ecu.eps, 0x730, None): [ - b'NZ6C-14D003-AK\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'NZ6C-14D003-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'NZ6C-2D053-AE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'NZ6C-2D053-AG\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PZ6C-2D053-ED\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PZ6C-2D053-EE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PZ6C-2D053-EF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'NZ6T-14D049-AA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'NZ6T-14F397-AC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - CAR.FORD_RANGER_MK2: { - (Ecu.eps, 0x730, None): [ - b'NL14-14D003-AE\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'PB3C-2D053-ZD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'ML3T-14D049-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'PJ6T-14H102-ABJ\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, -} diff --git a/car/ford/fordcan.py b/car/ford/fordcan.py deleted file mode 100644 index 2cfd61a191..0000000000 --- a/car/ford/fordcan.py +++ /dev/null @@ -1,340 +0,0 @@ -from cereal import car -from openpilot.selfdrive.car import CanBusBase - -HUDControl = car.CarControl.HUDControl - - -class CanBus(CanBusBase): - def __init__(self, CP=None, fingerprint=None) -> None: - super().__init__(CP, fingerprint) - - @property - def main(self) -> int: - return self.offset - - @property - def radar(self) -> int: - return self.offset + 1 - - @property - def camera(self) -> int: - return self.offset + 2 - - -def calculate_lat_ctl2_checksum(mode: int, counter: int, dat: bytearray) -> int: - curvature = (dat[2] << 3) | ((dat[3]) >> 5) - curvature_rate = (dat[6] << 3) | ((dat[7]) >> 5) - path_angle = ((dat[3] & 0x1F) << 6) | ((dat[4]) >> 2) - path_offset = ((dat[4] & 0x3) << 8) | dat[5] - - checksum = mode + counter - for sig_val in (curvature, curvature_rate, path_angle, path_offset): - checksum += sig_val + (sig_val >> 8) - - return 0xFF - (checksum & 0xFF) - - -def create_lka_msg(packer, CAN: CanBus): - """ - Creates an empty CAN message for the Ford LKA Command. - - This command can apply "Lane Keeping Aid" manoeuvres, which are subject to the PSCM lockout. - - Frequency is 33Hz. - """ - - return packer.make_can_msg("Lane_Assist_Data1", CAN.main, {}) - - -def create_lat_ctl_msg(packer, CAN: CanBus, lat_active: bool, path_offset: float, path_angle: float, curvature: float, - curvature_rate: float): - """ - Creates a CAN message for the Ford TJA/LCA Command. - - This command can apply "Lane Centering" manoeuvres: continuous lane centering for traffic jam assist and highway - driving. It is not subject to the PSCM lockout. - - Ford lane centering command uses a third order polynomial to describe the road centerline. The polynomial is defined - by the following coefficients: - c0: lateral offset between the vehicle and the centerline (positive is right) - c1: heading angle between the vehicle and the centerline (positive is right) - c2: curvature of the centerline (positive is left) - c3: rate of change of curvature of the centerline - As the PSCM combines this information with other sensor data, such as the vehicle's yaw rate and speed, the steering - angle cannot be easily controlled. - - The PSCM should be configured to accept TJA/LCA commands before these commands will be processed. This can be done - using tools such as Forscan. - - Frequency is 20Hz. - """ - - values = { - "LatCtlRng_L_Max": 0, # Unknown [0|126] meter - "HandsOffCnfm_B_Rq": 0, # Unknown: 0=Inactive, 1=Active [0|1] - "LatCtl_D_Rq": 1 if lat_active else 0, # Mode: 0=None, 1=ContinuousPathFollowing, 2=InterventionLeft, - # 3=InterventionRight, 4-7=NotUsed [0|7] - "LatCtlRampType_D_Rq": 0, # Ramp speed: 0=Slow, 1=Medium, 2=Fast, 3=Immediate [0|3] - # Makes no difference with curvature control - "LatCtlPrecision_D_Rq": 1, # Precision: 0=Comfortable, 1=Precise, 2/3=NotUsed [0|3] - # The stock system always uses comfortable - "LatCtlPathOffst_L_Actl": path_offset, # Path offset [-5.12|5.11] meter - "LatCtlPath_An_Actl": path_angle, # Path angle [-0.5|0.5235] radians - "LatCtlCurv_NoRate_Actl": curvature_rate, # Curvature rate [-0.001024|0.00102375] 1/meter^2 - "LatCtlCurv_No_Actl": curvature, # Curvature [-0.02|0.02094] 1/meter - } - return packer.make_can_msg("LateralMotionControl", CAN.main, values) - - -def create_lat_ctl2_msg(packer, CAN: CanBus, mode: int, path_offset: float, path_angle: float, curvature: float, - curvature_rate: float, counter: int): - """ - Create a CAN message for the new Ford Lane Centering command. - - This message is used on the CAN FD platform and replaces the old LateralMotionControl message. It is similar but has - additional signals for a counter and checksum. - - Frequency is 20Hz. - """ - - values = { - "LatCtl_D2_Rq": mode, # Mode: 0=None, 1=PathFollowingLimitedMode, 2=PathFollowingExtendedMode, - # 3=SafeRampOut, 4-7=NotUsed [0|7] - "LatCtlRampType_D_Rq": 0, # 0=Slow, 1=Medium, 2=Fast, 3=Immediate [0|3] - "LatCtlPrecision_D_Rq": 1, # 0=Comfortable, 1=Precise, 2/3=NotUsed [0|3] - "LatCtlPathOffst_L_Actl": path_offset, # [-5.12|5.11] meter - "LatCtlPath_An_Actl": path_angle, # [-0.5|0.5235] radians - "LatCtlCurv_No_Actl": curvature, # [-0.02|0.02094] 1/meter - "LatCtlCrv_NoRate2_Actl": curvature_rate, # [-0.001024|0.001023] 1/meter^2 - "HandsOffCnfm_B_Rq": 0, # 0=Inactive, 1=Active [0|1] - "LatCtlPath_No_Cnt": counter, # [0|15] - "LatCtlPath_No_Cs": 0, # [0|255] - } - - # calculate checksum - dat = packer.make_can_msg("LateralMotionControl2", 0, values)[2] - values["LatCtlPath_No_Cs"] = calculate_lat_ctl2_checksum(mode, counter, dat) - - return packer.make_can_msg("LateralMotionControl2", CAN.main, values) - - -def create_acc_msg(packer, CAN: CanBus, long_active: bool, gas: float, accel: float, stopping: bool, v_ego_kph: float): - """ - Creates a CAN message for the Ford ACC Command. - - This command can be used to enable ACC, to set the ACC gas/brake/decel values - and to disable ACC. - - Frequency is 50Hz. - """ - decel = accel < 0 and long_active - values = { - "AccBrkTot_A_Rq": accel, # Brake total accel request: [-20|11.9449] m/s^2 - "Cmbb_B_Enbl": 1 if long_active else 0, # Enabled: 0=No, 1=Yes - "AccPrpl_A_Rq": gas, # Acceleration request: [-5|5.23] m/s^2 - "AccPrpl_A_Pred": -5.0, # Acceleration request: [-5|5.23] m/s^2 - "AccResumEnbl_B_Rq": 1 if long_active else 0, - "AccVeh_V_Trg": v_ego_kph, # Target speed: [0|255] km/h - # TODO: we may be able to improve braking response by utilizing pre-charging better - "AccBrkPrchg_B_Rq": 1 if decel else 0, # Pre-charge brake request: 0=No, 1=Yes - "AccBrkDecel_B_Rq": 1 if decel else 0, # Deceleration request: 0=Inactive, 1=Active - "AccStopStat_B_Rq": 1 if stopping else 0, - } - return packer.make_can_msg("ACCDATA", CAN.main, values) - - -def create_acc_ui_msg(packer, CAN: CanBus, CP, main_on: bool, enabled: bool, fcw_alert: bool, standstill: bool, - hud_control, stock_values: dict): - """ - Creates a CAN message for the Ford IPC adaptive cruise, forward collision warning and traffic jam - assist status. - - Stock functionality is maintained by passing through unmodified signals. - - Frequency is 5Hz. - """ - - # Tja_D_Stat - if enabled: - if hud_control.leftLaneDepart: - status = 3 # ActiveInterventionLeft - elif hud_control.rightLaneDepart: - status = 4 # ActiveInterventionRight - else: - status = 2 # Active - elif main_on: - if hud_control.leftLaneDepart: - status = 5 # ActiveWarningLeft - elif hud_control.rightLaneDepart: - status = 6 # ActiveWarningRight - else: - status = 1 # Standby - else: - status = 0 # Off - - values = {s: stock_values[s] for s in [ - "HaDsply_No_Cs", - "HaDsply_No_Cnt", - "AccStopStat_D_Dsply", # ACC stopped status message - "AccTrgDist2_D_Dsply", # ACC target distance - "AccStopRes_B_Dsply", - "TjaWarn_D_Rq", # TJA warning - "TjaMsgTxt_D_Dsply", # TJA text - "IaccLamp_D_Rq", # iACC status icon - "AccMsgTxt_D2_Rq", # ACC text - "FcwDeny_B_Dsply", # FCW disabled - "FcwMemStat_B_Actl", # FCW enabled setting - "AccTGap_B_Dsply", # ACC time gap display setting - "CadsAlignIncplt_B_Actl", - "AccFllwMde_B_Dsply", # ACC follow mode display setting - "CadsRadrBlck_B_Actl", - "CmbbPostEvnt_B_Dsply", # AEB event status - "AccStopMde_B_Dsply", # ACC stop mode display setting - "FcwMemSens_D_Actl", # FCW sensitivity setting - "FcwMsgTxt_D_Rq", # FCW text - "AccWarn_D_Dsply", # ACC warning - "FcwVisblWarn_B_Rq", # FCW visible alert - "FcwAudioWarn_B_Rq", # FCW audio alert - "AccTGap_D_Dsply", # ACC time gap - "AccMemEnbl_B_RqDrv", # ACC adaptive/normal setting - "FdaMem_B_Stat", # FDA enabled setting - ]} - - values.update({ - "Tja_D_Stat": status, # TJA status - }) - - if CP.openpilotLongitudinalControl: - values.update({ - "AccStopStat_D_Dsply": 2 if standstill else 0, # Stopping status text - "AccMsgTxt_D2_Rq": 0, # ACC text - "AccTGap_B_Dsply": 0, # Show time gap control UI - "AccFllwMde_B_Dsply": 1 if hud_control.leadVisible else 0, # Lead indicator - "AccStopMde_B_Dsply": 1 if standstill else 0, - "AccWarn_D_Dsply": 0, # ACC warning - "AccTGap_D_Dsply": hud_control.leadDistanceBars, # Time gap - }) - - # Forwards FCW alert from IPMA - if fcw_alert: - values["FcwVisblWarn_B_Rq"] = 1 # FCW visible alert - - return packer.make_can_msg("ACCDATA_3", CAN.main, values) - - -def create_lkas_ui_msg(packer, CAN: CanBus, main_on: bool, enabled: bool, steer_alert: bool, hud_control, - stock_values: dict): - """ - Creates a CAN message for the Ford IPC IPMA/LKAS status. - - Show the LKAS status with the "driver assist" lines in the IPC. - - Stock functionality is maintained by passing through unmodified signals. - - Frequency is 1Hz. - """ - - # LaActvStats_D_Dsply - # R Intvn Warn Supprs Avail No - # L - # Intvn 24 19 14 9 4 - # Warn 23 18 13 8 3 - # Supprs 22 17 12 7 2 - # Avail 21 16 11 6 1 - # No 20 15 10 5 0 - # - # TODO: test suppress state - if enabled: - lines = 0 # NoLeft_NoRight - if hud_control.leftLaneDepart: - lines += 4 - elif hud_control.leftLaneVisible: - lines += 1 - if hud_control.rightLaneDepart: - lines += 20 - elif hud_control.rightLaneVisible: - lines += 5 - elif main_on: - lines = 0 - else: - if hud_control.leftLaneDepart: - lines = 3 # WarnLeft_NoRight - elif hud_control.rightLaneDepart: - lines = 15 # NoLeft_WarnRight - else: - lines = 30 # LA_Off - - hands_on_wheel_dsply = 1 if steer_alert else 0 - - values = {s: stock_values[s] for s in [ - "FeatConfigIpmaActl", - "FeatNoIpmaActl", - "PersIndexIpma_D_Actl", - "AhbcRampingV_D_Rq", # AHB ramping - "LaDenyStats_B_Dsply", # LKAS error - "CamraDefog_B_Req", # Windshield heater? - "CamraStats_D_Dsply", # Camera status - "DasAlrtLvl_D_Dsply", # DAS alert level - "DasStats_D_Dsply", # DAS status - "DasWarn_D_Dsply", # DAS warning - "AhbHiBeam_D_Rq", # AHB status - "Passthru_63", - "Passthru_48", - ]} - - values.update({ - "LaActvStats_D_Dsply": lines, # LKAS status (lines) [0|31] - "LaHandsOff_D_Dsply": hands_on_wheel_dsply, # 0=HandsOn, 1=Level1 (w/o chime), 2=Level2 (w/ chime), 3=Suppressed - }) - return packer.make_can_msg("IPMA_Data", CAN.main, values) - - -def create_button_msg(packer, bus: int, stock_values: dict, cancel=False, resume=False, tja_toggle=False): - """ - Creates a CAN message for the Ford SCCM buttons/switches. - - Includes cruise control buttons, turn lights and more. - - Frequency is 10Hz. - """ - - values = {s: stock_values[s] for s in [ - "HeadLghtHiFlash_D_Stat", # SCCM Passthrough the remaining buttons - "TurnLghtSwtch_D_Stat", # SCCM Turn signal switch - "WiprFront_D_Stat", - "LghtAmb_D_Sns", - "AccButtnGapDecPress", - "AccButtnGapIncPress", - "AslButtnOnOffCnclPress", - "AslButtnOnOffPress", - "LaSwtchPos_D_Stat", - "CcAslButtnCnclResPress", - "CcAslButtnDeny_B_Actl", - "CcAslButtnIndxDecPress", - "CcAslButtnIndxIncPress", - "CcAslButtnOffCnclPress", - "CcAslButtnOnOffCncl", - "CcAslButtnOnPress", - "CcAslButtnResDecPress", - "CcAslButtnResIncPress", - "CcAslButtnSetDecPress", - "CcAslButtnSetIncPress", - "CcAslButtnSetPress", - "CcButtnOffPress", - "CcButtnOnOffCnclPress", - "CcButtnOnOffPress", - "CcButtnOnPress", - "HeadLghtHiFlash_D_Actl", - "HeadLghtHiOn_B_StatAhb", - "AhbStat_B_Dsply", - "AccButtnGapTogglePress", - "WiprFrontSwtch_D_Stat", - "HeadLghtHiCtrl_D_RqAhb", - ]} - - values.update({ - "CcAslButtnCnclPress": 1 if cancel else 0, # CC cancel button - "CcAsllButtnResPress": 1 if resume else 0, # CC resume button - "TjaButtnOnOffPress": 1 if tja_toggle else 0, # LCA/TJA toggle button - }) - return packer.make_can_msg("Steering_Data_FD1", bus, values) diff --git a/car/ford/interface.py b/car/ford/interface.py deleted file mode 100644 index 2ef5d427e6..0000000000 --- a/car/ford/interface.py +++ /dev/null @@ -1,85 +0,0 @@ -from cereal import car -from panda import Panda -from openpilot.common.conversions import Conversions as CV -from openpilot.selfdrive.car import create_button_events, get_safety_config -from openpilot.selfdrive.car.ford.fordcan import CanBus -from openpilot.selfdrive.car.ford.values import Ecu, FordFlags -from openpilot.selfdrive.car.interfaces import CarInterfaceBase - -ButtonType = car.CarState.ButtonEvent.Type -TransmissionType = car.CarParams.TransmissionType -GearShifter = car.CarState.GearShifter - - -class CarInterface(CarInterfaceBase): - @staticmethod - def _get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs): - ret.carName = "ford" - ret.dashcamOnly = bool(ret.flags & FordFlags.CANFD) - - ret.radarUnavailable = True - ret.steerControlType = car.CarParams.SteerControlType.angle - ret.steerActuatorDelay = 0.2 - ret.steerLimitTimer = 1.0 - - ret.longitudinalTuning.kpBP = [0.] - ret.longitudinalTuning.kpV = [0.5] - ret.longitudinalTuning.kiV = [0.] - - CAN = CanBus(fingerprint=fingerprint) - cfgs = [get_safety_config(car.CarParams.SafetyModel.ford)] - if CAN.main >= 4: - cfgs.insert(0, get_safety_config(car.CarParams.SafetyModel.noOutput)) - ret.safetyConfigs = cfgs - - ret.experimentalLongitudinalAvailable = True - if experimental_long: - ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_FORD_LONG_CONTROL - ret.openpilotLongitudinalControl = True - - if ret.flags & FordFlags.CANFD: - ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_FORD_CANFD - else: - # Lock out if the car does not have needed lateral and longitudinal control APIs. - # Note that we also check CAN for adaptive cruise, but no known signal for LCA exists - pscm_config = next((fw for fw in car_fw if fw.ecu == Ecu.eps and b'\x22\xDE\x01' in fw.request), None) - if pscm_config: - if len(pscm_config.fwVersion) != 24: - ret.dashcamOnly = True - else: - config_tja = pscm_config.fwVersion[7] # Traffic Jam Assist - config_lca = pscm_config.fwVersion[8] # Lane Centering Assist - if config_tja != 0xFF or config_lca != 0xFF: - ret.dashcamOnly = True - - # Auto Transmission: 0x732 ECU or Gear_Shift_by_Wire_FD1 - found_ecus = [fw.ecu for fw in car_fw] - if Ecu.shiftByWire in found_ecus or 0x5A in fingerprint[CAN.main] or docs: - ret.transmissionType = TransmissionType.automatic - else: - ret.transmissionType = TransmissionType.manual - ret.minEnableSpeed = 20.0 * CV.MPH_TO_MS - - # BSM: Side_Detect_L_Stat, Side_Detect_R_Stat - # TODO: detect bsm in car_fw? - ret.enableBsm = 0x3A6 in fingerprint[CAN.main] and 0x3A7 in fingerprint[CAN.main] - - # LCA can steer down to zero - ret.minSteerSpeed = 0. - - ret.autoResumeSng = ret.minEnableSpeed == -1. - ret.centerToFront = ret.wheelbase * 0.44 - return ret - - def _update(self, c): - ret = self.CS.update(self.cp, self.cp_cam) - - ret.buttonEvents = create_button_events(self.CS.distance_button, self.CS.prev_distance_button, {1: ButtonType.gapAdjustCruise}) - - events = self.create_common_events(ret, extra_gears=[GearShifter.manumatic]) - if not self.CS.vehicle_sensors_valid: - events.add(car.CarEvent.EventName.vehicleSensorsInvalid) - - ret.events = events.to_msg() - - return ret diff --git a/car/ford/radar_interface.py b/car/ford/radar_interface.py deleted file mode 100644 index 209bbebae3..0000000000 --- a/car/ford/radar_interface.py +++ /dev/null @@ -1,143 +0,0 @@ -from math import cos, sin -from cereal import car -from opendbc.can.parser import CANParser -from openpilot.common.conversions import Conversions as CV -from openpilot.selfdrive.car.ford.fordcan import CanBus -from openpilot.selfdrive.car.ford.values import DBC, RADAR -from openpilot.selfdrive.car.interfaces import RadarInterfaceBase - -DELPHI_ESR_RADAR_MSGS = list(range(0x500, 0x540)) - -DELPHI_MRR_RADAR_START_ADDR = 0x120 -DELPHI_MRR_RADAR_MSG_COUNT = 64 - - -def _create_delphi_esr_radar_can_parser(CP) -> CANParser: - msg_n = len(DELPHI_ESR_RADAR_MSGS) - messages = list(zip(DELPHI_ESR_RADAR_MSGS, [20] * msg_n, strict=True)) - - return CANParser(RADAR.DELPHI_ESR, messages, CanBus(CP).radar) - - -def _create_delphi_mrr_radar_can_parser(CP) -> CANParser: - messages = [] - - for i in range(1, DELPHI_MRR_RADAR_MSG_COUNT + 1): - msg = f"MRR_Detection_{i:03d}" - messages += [(msg, 20)] - - return CANParser(RADAR.DELPHI_MRR, messages, CanBus(CP).radar) - - -class RadarInterface(RadarInterfaceBase): - def __init__(self, CP): - super().__init__(CP) - - self.updated_messages = set() - self.track_id = 0 - self.radar = DBC[CP.carFingerprint]['radar'] - if self.radar is None or CP.radarUnavailable: - self.rcp = None - elif self.radar == RADAR.DELPHI_ESR: - self.rcp = _create_delphi_esr_radar_can_parser(CP) - self.trigger_msg = DELPHI_ESR_RADAR_MSGS[-1] - self.valid_cnt = {key: 0 for key in DELPHI_ESR_RADAR_MSGS} - elif self.radar == RADAR.DELPHI_MRR: - self.rcp = _create_delphi_mrr_radar_can_parser(CP) - self.trigger_msg = DELPHI_MRR_RADAR_START_ADDR + DELPHI_MRR_RADAR_MSG_COUNT - 1 - else: - raise ValueError(f"Unsupported radar: {self.radar}") - - def update(self, can_strings): - if self.rcp is None: - return super().update(None) - - vls = self.rcp.update_strings(can_strings) - self.updated_messages.update(vls) - - if self.trigger_msg not in self.updated_messages: - return None - - ret = car.RadarData.new_message() - errors = [] - if not self.rcp.can_valid: - errors.append("canError") - ret.errors = errors - - if self.radar == RADAR.DELPHI_ESR: - self._update_delphi_esr() - elif self.radar == RADAR.DELPHI_MRR: - self._update_delphi_mrr() - - ret.points = list(self.pts.values()) - self.updated_messages.clear() - return ret - - def _update_delphi_esr(self): - for ii in sorted(self.updated_messages): - cpt = self.rcp.vl[ii] - - if cpt['X_Rel'] > 0.00001: - self.valid_cnt[ii] = 0 # reset counter - - if cpt['X_Rel'] > 0.00001: - self.valid_cnt[ii] += 1 - else: - self.valid_cnt[ii] = max(self.valid_cnt[ii] - 1, 0) - #print ii, self.valid_cnt[ii], cpt['VALID'], cpt['X_Rel'], cpt['Angle'] - - # radar point only valid if there have been enough valid measurements - if self.valid_cnt[ii] > 0: - if ii not in self.pts: - self.pts[ii] = car.RadarData.RadarPoint.new_message() - self.pts[ii].trackId = self.track_id - self.track_id += 1 - self.pts[ii].dRel = cpt['X_Rel'] # from front of car - self.pts[ii].yRel = cpt['X_Rel'] * cpt['Angle'] * CV.DEG_TO_RAD # in car frame's y axis, left is positive - self.pts[ii].vRel = cpt['V_Rel'] - self.pts[ii].aRel = float('nan') - self.pts[ii].yvRel = float('nan') - self.pts[ii].measured = True - else: - if ii in self.pts: - del self.pts[ii] - - def _update_delphi_mrr(self): - for ii in range(1, DELPHI_MRR_RADAR_MSG_COUNT + 1): - msg = self.rcp.vl[f"MRR_Detection_{ii:03d}"] - - # SCAN_INDEX rotates through 0..3 on each message - # treat these as separate points - scanIndex = msg[f"CAN_SCAN_INDEX_2LSB_{ii:02d}"] - i = (ii - 1) * 4 + scanIndex - - if i not in self.pts: - self.pts[i] = car.RadarData.RadarPoint.new_message() - self.pts[i].trackId = self.track_id - self.pts[i].aRel = float('nan') - self.pts[i].yvRel = float('nan') - self.track_id += 1 - - valid = bool(msg[f"CAN_DET_VALID_LEVEL_{ii:02d}"]) - - if valid: - azimuth = msg[f"CAN_DET_AZIMUTH_{ii:02d}"] # rad [-3.1416|3.13964] - dist = msg[f"CAN_DET_RANGE_{ii:02d}"] # m [0|255.984] - distRate = msg[f"CAN_DET_RANGE_RATE_{ii:02d}"] # m/s [-128|127.984] - dRel = cos(azimuth) * dist # m from front of car - yRel = -sin(azimuth) * dist # in car frame's y axis, left is positive - - # delphi doesn't notify of track switches, so do it manually - # TODO: refactor this to radard if more radars behave this way - if abs(self.pts[i].vRel - distRate) > 2 or abs(self.pts[i].dRel - dRel) > 5: - self.track_id += 1 - self.pts[i].trackId = self.track_id - - self.pts[i].dRel = dRel - self.pts[i].yRel = yRel - self.pts[i].vRel = distRate - - self.pts[i].measured = True - - else: - del self.pts[i] diff --git a/car/ford/tests/__init__.py b/car/ford/tests/__init__.py deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/car/ford/tests/print_platform_codes.py b/car/ford/tests/print_platform_codes.py deleted file mode 100755 index 670199980a..0000000000 --- a/car/ford/tests/print_platform_codes.py +++ /dev/null @@ -1,30 +0,0 @@ -#!/usr/bin/env python3 -from collections import defaultdict - -from cereal import car -from openpilot.selfdrive.car.ford.values import get_platform_codes -from openpilot.selfdrive.car.ford.fingerprints import FW_VERSIONS - -Ecu = car.CarParams.Ecu -ECU_NAME = {v: k for k, v in Ecu.schema.enumerants.items()} - - -if __name__ == "__main__": - cars_for_code: defaultdict = defaultdict(lambda: defaultdict(set)) - - for car_model, ecus in FW_VERSIONS.items(): - print(car_model) - for ecu in sorted(ecus, key=lambda x: int(x[0])): - platform_codes = get_platform_codes(ecus[ecu]) - for code in platform_codes: - cars_for_code[ecu][code].add(car_model) - - print(f' (Ecu.{ECU_NAME[ecu[0]]}, {hex(ecu[1])}, {ecu[2]}):') - print(f' Codes: {sorted(platform_codes)}') - print() - - print('\nCar models vs. platform codes:') - for ecu, codes in cars_for_code.items(): - print(f' (Ecu.{ECU_NAME[ecu[0]]}, {hex(ecu[1])}, {ecu[2]}):') - for code, cars in codes.items(): - print(f' {code!r}: {sorted(map(str, cars))}') diff --git a/car/ford/tests/test_ford.py b/car/ford/tests/test_ford.py deleted file mode 100644 index b1a19017d4..0000000000 --- a/car/ford/tests/test_ford.py +++ /dev/null @@ -1,143 +0,0 @@ -import random -from collections.abc import Iterable - -import capnp -from hypothesis import settings, given, strategies as st -from parameterized import parameterized - -from cereal import car -from openpilot.selfdrive.car.fw_versions import build_fw_dict -from openpilot.selfdrive.car.ford.values import CAR, FW_QUERY_CONFIG, FW_PATTERN, get_platform_codes -from openpilot.selfdrive.car.ford.fingerprints import FW_VERSIONS - -Ecu = car.CarParams.Ecu - - -ECU_ADDRESSES = { - Ecu.eps: 0x730, # Power Steering Control Module (PSCM) - Ecu.abs: 0x760, # Anti-Lock Brake System (ABS) - Ecu.fwdRadar: 0x764, # Cruise Control Module (CCM) - Ecu.fwdCamera: 0x706, # Image Processing Module A (IPMA) - Ecu.engine: 0x7E0, # Powertrain Control Module (PCM) - Ecu.shiftByWire: 0x732, # Gear Shift Module (GSM) - Ecu.debug: 0x7D0, # Accessory Protocol Interface Module (APIM) -} - - -ECU_PART_NUMBER = { - Ecu.eps: [ - b"14D003", - ], - Ecu.abs: [ - b"2D053", - ], - Ecu.fwdRadar: [ - b"14D049", - ], - Ecu.fwdCamera: [ - b"14F397", # Ford Q3 - b"14H102", # Ford Q4 - ], -} - - -class TestFordFW: - def test_fw_query_config(self): - for (ecu, addr, subaddr) in FW_QUERY_CONFIG.extra_ecus: - assert ecu in ECU_ADDRESSES, "Unknown ECU" - assert addr == ECU_ADDRESSES[ecu], "ECU address mismatch" - assert subaddr is None, "Unexpected ECU subaddress" - - @parameterized.expand(FW_VERSIONS.items()) - def test_fw_versions(self, car_model: str, fw_versions: dict[tuple[capnp.lib.capnp._EnumModule, int, int | None], Iterable[bytes]]): - for (ecu, addr, subaddr), fws in fw_versions.items(): - assert ecu in ECU_PART_NUMBER, "Unexpected ECU" - assert addr == ECU_ADDRESSES[ecu], "ECU address mismatch" - assert subaddr is None, "Unexpected ECU subaddress" - - for fw in fws: - assert len(fw) == 24, "Expected ECU response to be 24 bytes" - - match = FW_PATTERN.match(fw) - assert match is not None, f"Unable to parse FW: {fw!r}" - if match: - part_number = match.group("part_number") - assert part_number in ECU_PART_NUMBER[ecu], f"Unexpected part number for {fw!r}" - - codes = get_platform_codes([fw]) - assert 1 == len(codes), f"Unable to parse FW: {fw!r}" - - @settings(max_examples=100) - @given(data=st.data()) - def test_platform_codes_fuzzy_fw(self, data): - """Ensure function doesn't raise an exception""" - fw_strategy = st.lists(st.binary()) - fws = data.draw(fw_strategy) - get_platform_codes(fws) - - def test_platform_codes_spot_check(self): - # Asserts basic platform code parsing behavior for a few cases - results = get_platform_codes([ - b"JX6A-14C204-BPL\x00\x00\x00\x00\x00\x00\x00\x00\x00", - b"NZ6T-14F397-AC\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00", - b"PJ6T-14H102-ABJ\x00\x00\x00\x00\x00\x00\x00\x00\x00", - b"LB5A-14C204-EAC\x00\x00\x00\x00\x00\x00\x00\x00\x00", - ]) - assert results == {(b"X6A", b"J"), (b"Z6T", b"N"), (b"J6T", b"P"), (b"B5A", b"L")} - - def test_fuzzy_match(self): - for platform, fw_by_addr in FW_VERSIONS.items(): - # Ensure there's no overlaps in platform codes - for _ in range(20): - car_fw = [] - for ecu, fw_versions in fw_by_addr.items(): - ecu_name, addr, sub_addr = ecu - fw = random.choice(fw_versions) - car_fw.append({"ecu": ecu_name, "fwVersion": fw, "address": addr, - "subAddress": 0 if sub_addr is None else sub_addr}) - - CP = car.CarParams.new_message(carFw=car_fw) - matches = FW_QUERY_CONFIG.match_fw_to_car_fuzzy(build_fw_dict(CP.carFw), CP.carVin, FW_VERSIONS) - assert matches == {platform} - - def test_match_fw_fuzzy(self): - offline_fw = { - (Ecu.eps, 0x730, None): [ - b"L1MC-14D003-AJ\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00", - b"L1MC-14D003-AL\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00", - ], - (Ecu.abs, 0x760, None): [ - b"L1MC-2D053-BA\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00", - b"L1MC-2D053-BD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00", - ], - (Ecu.fwdRadar, 0x764, None): [ - b"LB5T-14D049-AB\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00", - b"LB5T-14D049-AD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00", - ], - # We consider all model year hints for ECU, even with different platform codes - (Ecu.fwdCamera, 0x706, None): [ - b"LB5T-14F397-AD\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00", - b"NC5T-14F397-AF\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00", - ], - } - expected_fingerprint = CAR.FORD_EXPLORER_MK6 - - # ensure that we fuzzy match on all non-exact FW with changed revisions - live_fw = { - (0x730, None): {b"L1MC-14D003-XX\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00"}, - (0x760, None): {b"L1MC-2D053-XX\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00"}, - (0x764, None): {b"LB5T-14D049-XX\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00"}, - (0x706, None): {b"LB5T-14F397-XX\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00"}, - } - candidates = FW_QUERY_CONFIG.match_fw_to_car_fuzzy(live_fw, '', {expected_fingerprint: offline_fw}) - assert candidates == {expected_fingerprint} - - # model year hint in between the range should match - live_fw[(0x706, None)] = {b"MB5T-14F397-XX\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00"} - candidates = FW_QUERY_CONFIG.match_fw_to_car_fuzzy(live_fw, '', {expected_fingerprint: offline_fw,}) - assert candidates == {expected_fingerprint} - - # unseen model year hint should not match - live_fw[(0x760, None)] = {b"M1MC-2D053-XX\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00"} - candidates = FW_QUERY_CONFIG.match_fw_to_car_fuzzy(live_fw, '', {expected_fingerprint: offline_fw}) - assert len(candidates) == 0, "Should not match new model year hint" diff --git a/car/ford/values.py b/car/ford/values.py deleted file mode 100644 index b1868bfa9b..0000000000 --- a/car/ford/values.py +++ /dev/null @@ -1,279 +0,0 @@ -import copy -import re -from dataclasses import dataclass, field, replace -from enum import Enum, IntFlag - -import panda.python.uds as uds -from cereal import car -from openpilot.selfdrive.car import AngleRateLimit, CarSpecs, dbc_dict, DbcDict, PlatformConfig, Platforms -from openpilot.selfdrive.car.docs_definitions import CarFootnote, CarHarness, CarDocs, CarParts, Column, \ - Device -from openpilot.selfdrive.car.fw_query_definitions import FwQueryConfig, LiveFwVersions, OfflineFwVersions, Request, StdQueries, p16 - -Ecu = car.CarParams.Ecu - - -class CarControllerParams: - STEER_STEP = 5 # LateralMotionControl, 20Hz - LKA_STEP = 3 # Lane_Assist_Data1, 33Hz - ACC_CONTROL_STEP = 2 # ACCDATA, 50Hz - LKAS_UI_STEP = 100 # IPMA_Data, 1Hz - ACC_UI_STEP = 20 # ACCDATA_3, 5Hz - BUTTONS_STEP = 5 # Steering_Data_FD1, 10Hz, but send twice as fast - - CURVATURE_MAX = 0.02 # Max curvature for steering command, m^-1 - STEER_DRIVER_ALLOWANCE = 1.0 # Driver intervention threshold, Nm - - # Curvature rate limits - # The curvature signal is limited to 0.003 to 0.009 m^-1/sec by the EPS depending on speed and direction - # Limit to ~2 m/s^3 up, ~3 m/s^3 down at 75 mph - # Worst case, the low speed limits will allow 4.3 m/s^3 up, 4.9 m/s^3 down at 75 mph - ANGLE_RATE_LIMIT_UP = AngleRateLimit(speed_bp=[5, 25], angle_v=[0.0002, 0.0001]) - ANGLE_RATE_LIMIT_DOWN = AngleRateLimit(speed_bp=[5, 25], angle_v=[0.000225, 0.00015]) - CURVATURE_ERROR = 0.002 # ~6 degrees at 10 m/s, ~10 degrees at 35 m/s - - ACCEL_MAX = 2.0 # m/s^2 max acceleration - ACCEL_MIN = -3.5 # m/s^2 max deceleration - MIN_GAS = -0.5 - INACTIVE_GAS = -5.0 - - def __init__(self, CP): - pass - - -class FordFlags(IntFlag): - # Static flags - CANFD = 1 - - -class RADAR: - DELPHI_ESR = 'ford_fusion_2018_adas' - DELPHI_MRR = 'FORD_CADS' - - -class Footnote(Enum): - FOCUS = CarFootnote( - "Refers only to the Focus Mk4 (C519) available in Europe/China/Taiwan/Australasia, not the Focus Mk3 (C346) in " + - "North and South America/Southeast Asia.", - Column.MODEL, - ) - - -@dataclass -class FordCarDocs(CarDocs): - package: str = "Co-Pilot360 Assist+" - hybrid: bool = False - plug_in_hybrid: bool = False - - def init_make(self, CP: car.CarParams): - harness = CarHarness.ford_q4 if CP.flags & FordFlags.CANFD else CarHarness.ford_q3 - if CP.carFingerprint in (CAR.FORD_BRONCO_SPORT_MK1, CAR.FORD_MAVERICK_MK1, CAR.FORD_F_150_MK14, CAR.FORD_F_150_LIGHTNING_MK1): - self.car_parts = CarParts([Device.threex_angled_mount, harness]) - else: - self.car_parts = CarParts([Device.threex, harness]) - - -@dataclass -class FordPlatformConfig(PlatformConfig): - dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict('ford_lincoln_base_pt', RADAR.DELPHI_MRR)) - - def init(self): - for car_docs in list(self.car_docs): - if car_docs.hybrid: - name = f"{car_docs.make} {car_docs.model} Hybrid {car_docs.years}" - self.car_docs.append(replace(copy.deepcopy(car_docs), name=name)) - if car_docs.plug_in_hybrid: - name = f"{car_docs.make} {car_docs.model} Plug-in Hybrid {car_docs.years}" - self.car_docs.append(replace(copy.deepcopy(car_docs), name=name)) - - -@dataclass -class FordCANFDPlatformConfig(FordPlatformConfig): - dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict('ford_lincoln_base_pt', None)) - - def init(self): - super().init() - self.flags |= FordFlags.CANFD - - -class CAR(Platforms): - FORD_BRONCO_SPORT_MK1 = FordPlatformConfig( - [FordCarDocs("Ford Bronco Sport 2021-23")], - CarSpecs(mass=1625, wheelbase=2.67, steerRatio=17.7), - ) - FORD_ESCAPE_MK4 = FordPlatformConfig( - [ - FordCarDocs("Ford Escape 2020-22", hybrid=True, plug_in_hybrid=True), - FordCarDocs("Ford Kuga 2020-22", "Adaptive Cruise Control with Lane Centering", hybrid=True, plug_in_hybrid=True), - ], - CarSpecs(mass=1750, wheelbase=2.71, steerRatio=16.7), - ) - FORD_EXPLORER_MK6 = FordPlatformConfig( - [ - FordCarDocs("Ford Explorer 2020-23", hybrid=True), # Hybrid: Limited and Platinum only - FordCarDocs("Lincoln Aviator 2020-23", "Co-Pilot360 Plus", plug_in_hybrid=True), # Hybrid: Grand Touring only - ], - CarSpecs(mass=2050, wheelbase=3.025, steerRatio=16.8), - ) - FORD_F_150_MK14 = FordCANFDPlatformConfig( - [FordCarDocs("Ford F-150 2022-23", "Co-Pilot360 Active 2.0", hybrid=True)], - CarSpecs(mass=2000, wheelbase=3.69, steerRatio=17.0), - ) - FORD_F_150_LIGHTNING_MK1 = FordCANFDPlatformConfig( - [FordCarDocs("Ford F-150 Lightning 2021-23", "Co-Pilot360 Active 2.0")], - CarSpecs(mass=2948, wheelbase=3.70, steerRatio=16.9), - ) - FORD_FOCUS_MK4 = FordPlatformConfig( - [FordCarDocs("Ford Focus 2018", "Adaptive Cruise Control with Lane Centering", footnotes=[Footnote.FOCUS], hybrid=True)], # mHEV only - CarSpecs(mass=1350, wheelbase=2.7, steerRatio=15.0), - ) - FORD_MAVERICK_MK1 = FordPlatformConfig( - [ - FordCarDocs("Ford Maverick 2022", "LARIAT Luxury", hybrid=True), - FordCarDocs("Ford Maverick 2023-24", "Co-Pilot360 Assist", hybrid=True), - ], - CarSpecs(mass=1650, wheelbase=3.076, steerRatio=17.0), - ) - FORD_MUSTANG_MACH_E_MK1 = FordCANFDPlatformConfig( - [FordCarDocs("Ford Mustang Mach-E 2021-23", "Co-Pilot360 Active 2.0")], - CarSpecs(mass=2200, wheelbase=2.984, steerRatio=17.0), # TODO: check steer ratio - ) - FORD_RANGER_MK2 = FordCANFDPlatformConfig( - [FordCarDocs("Ford Ranger 2024", "Adaptive Cruise Control with Lane Centering")], - CarSpecs(mass=2000, wheelbase=3.27, steerRatio=17.0), - ) - - -# FW response contains a combined software and part number -# A-Z except no I, O or W -# e.g. NZ6A-14C204-AAA -# 1222-333333-444 -# 1 = Model year hint (approximates model year/generation) -# 2 = Platform hint -# 3 = Part number -# 4 = Software version -FW_ALPHABET = b'A-HJ-NP-VX-Z' -FW_PATTERN = re.compile(b'^(?P[' + FW_ALPHABET + b'])' + - b'(?P[0-9' + FW_ALPHABET + b']{3})-' + - b'(?P[0-9' + FW_ALPHABET + b']{5,6})-' + - b'(?P[' + FW_ALPHABET + b']{2,})\x00*$') - - -def get_platform_codes(fw_versions: list[bytes] | set[bytes]) -> set[tuple[bytes, bytes]]: - codes = set() - for fw in fw_versions: - match = FW_PATTERN.match(fw) - if match is not None: - codes.add((match.group('platform_hint'), match.group('model_year_hint'))) - - return codes - - -def match_fw_to_car_fuzzy(live_fw_versions: LiveFwVersions, vin: str, offline_fw_versions: OfflineFwVersions) -> set[str]: - candidates: set[str] = set() - - for candidate, fws in offline_fw_versions.items(): - # Keep track of ECUs which pass all checks (platform hint, within model year hint range) - valid_found_ecus = set() - valid_expected_ecus = {ecu[1:] for ecu in fws if ecu[0] in PLATFORM_CODE_ECUS} - for ecu, expected_versions in fws.items(): - addr = ecu[1:] - # Only check ECUs expected to have platform codes - if ecu[0] not in PLATFORM_CODE_ECUS: - continue - - # Expected platform codes & model year hints - codes = get_platform_codes(expected_versions) - expected_platform_codes = {code for code, _ in codes} - expected_model_year_hints = {model_year_hint for _, model_year_hint in codes} - - # Found platform codes & model year hints - codes = get_platform_codes(live_fw_versions.get(addr, set())) - found_platform_codes = {code for code, _ in codes} - found_model_year_hints = {model_year_hint for _, model_year_hint in codes} - - # Check platform code matches for any found versions - if not any(found_platform_code in expected_platform_codes for found_platform_code in found_platform_codes): - break - - # Check any model year hint within range in the database. Note that some models have more than one - # platform code per ECU which we don't consider as separate ranges - if not any(min(expected_model_year_hints) <= found_model_year_hint <= max(expected_model_year_hints) for - found_model_year_hint in found_model_year_hints): - break - - valid_found_ecus.add(addr) - - # If all live ECUs pass all checks for candidate, add it as a match - if valid_expected_ecus.issubset(valid_found_ecus): - candidates.add(candidate) - - return candidates - - -# All of these ECUs must be present and are expected to have platform codes we can match -PLATFORM_CODE_ECUS = (Ecu.abs, Ecu.fwdCamera, Ecu.fwdRadar, Ecu.eps) - -DATA_IDENTIFIER_FORD_ASBUILT = 0xDE00 - -ASBUILT_BLOCKS: list[tuple[int, list]] = [ - (1, [Ecu.debug, Ecu.fwdCamera, Ecu.eps]), - (2, [Ecu.abs, Ecu.debug, Ecu.eps]), - (3, [Ecu.abs, Ecu.debug, Ecu.eps]), - (4, [Ecu.debug, Ecu.fwdCamera]), - (5, [Ecu.debug]), - (6, [Ecu.debug]), - (7, [Ecu.debug]), - (8, [Ecu.debug]), - (9, [Ecu.debug]), - (16, [Ecu.debug, Ecu.fwdCamera]), - (18, [Ecu.fwdCamera]), - (20, [Ecu.fwdCamera]), - (21, [Ecu.fwdCamera]), -] - - -def ford_asbuilt_block_request(block_id: int): - return bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + p16(DATA_IDENTIFIER_FORD_ASBUILT + block_id - 1) - - -def ford_asbuilt_block_response(block_id: int): - return bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + p16(DATA_IDENTIFIER_FORD_ASBUILT + block_id - 1) - - -FW_QUERY_CONFIG = FwQueryConfig( - requests=[ - # CAN and CAN FD queries are combined. - # FIXME: For CAN FD, ECUs respond with frames larger than 8 bytes on the powertrain bus - Request( - [StdQueries.TESTER_PRESENT_REQUEST, StdQueries.MANUFACTURER_SOFTWARE_VERSION_REQUEST], - [StdQueries.TESTER_PRESENT_RESPONSE, StdQueries.MANUFACTURER_SOFTWARE_VERSION_RESPONSE], - whitelist_ecus=[Ecu.abs, Ecu.debug, Ecu.engine, Ecu.eps, Ecu.fwdCamera, Ecu.fwdRadar, Ecu.shiftByWire], - logging=True, - ), - Request( - [StdQueries.TESTER_PRESENT_REQUEST, StdQueries.MANUFACTURER_SOFTWARE_VERSION_REQUEST], - [StdQueries.TESTER_PRESENT_RESPONSE, StdQueries.MANUFACTURER_SOFTWARE_VERSION_RESPONSE], - whitelist_ecus=[Ecu.abs, Ecu.debug, Ecu.engine, Ecu.eps, Ecu.fwdCamera, Ecu.fwdRadar, Ecu.shiftByWire], - bus=0, - auxiliary=True, - ), - *[Request( - [StdQueries.TESTER_PRESENT_REQUEST, ford_asbuilt_block_request(block_id)], - [StdQueries.TESTER_PRESENT_RESPONSE, ford_asbuilt_block_response(block_id)], - whitelist_ecus=ecus, - bus=0, - logging=True, - ) for block_id, ecus in ASBUILT_BLOCKS], - ], - extra_ecus=[ - (Ecu.engine, 0x7e0, None), # Powertrain Control Module - # Note: We are unlikely to get a response from behind the gateway - (Ecu.shiftByWire, 0x732, None), # Gear Shift Module - (Ecu.debug, 0x7d0, None), # Accessory Protocol Interface Module - ], - # Custom fuzzy fingerprinting function using platform and model year hints - match_fw_to_car_fuzzy=match_fw_to_car_fuzzy, -) - -DBC = CAR.create_dbc_map() diff --git a/car/gm/__init__.py b/car/gm/__init__.py deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/car/gm/carcontroller.py b/car/gm/carcontroller.py deleted file mode 100644 index b204d3b80f..0000000000 --- a/car/gm/carcontroller.py +++ /dev/null @@ -1,165 +0,0 @@ -from cereal import car -from openpilot.common.conversions import Conversions as CV -from openpilot.common.numpy_fast import interp -from openpilot.common.realtime import DT_CTRL -from opendbc.can.packer import CANPacker -from openpilot.selfdrive.car import apply_driver_steer_torque_limits -from openpilot.selfdrive.car.gm import gmcan -from openpilot.selfdrive.car.gm.values import DBC, CanBus, CarControllerParams, CruiseButtons -from openpilot.selfdrive.car.interfaces import CarControllerBase - -VisualAlert = car.CarControl.HUDControl.VisualAlert -NetworkLocation = car.CarParams.NetworkLocation -LongCtrlState = car.CarControl.Actuators.LongControlState - -# Camera cancels up to 0.1s after brake is pressed, ECM allows 0.5s -CAMERA_CANCEL_DELAY_FRAMES = 10 -# Enforce a minimum interval between steering messages to avoid a fault -MIN_STEER_MSG_INTERVAL_MS = 15 - - -class CarController(CarControllerBase): - def __init__(self, dbc_name, CP, VM): - self.CP = CP - self.start_time = 0. - self.apply_steer_last = 0 - self.apply_gas = 0 - self.apply_brake = 0 - self.frame = 0 - self.last_steer_frame = 0 - self.last_button_frame = 0 - self.cancel_counter = 0 - - self.lka_steering_cmd_counter = 0 - self.lka_icon_status_last = (False, False) - - self.params = CarControllerParams(self.CP) - - self.packer_pt = CANPacker(DBC[self.CP.carFingerprint]['pt']) - self.packer_obj = CANPacker(DBC[self.CP.carFingerprint]['radar']) - self.packer_ch = CANPacker(DBC[self.CP.carFingerprint]['chassis']) - - def update(self, CC, CS, now_nanos): - actuators = CC.actuators - hud_control = CC.hudControl - hud_alert = hud_control.visualAlert - hud_v_cruise = hud_control.setSpeed - if hud_v_cruise > 70: - hud_v_cruise = 0 - - # Send CAN commands. - can_sends = [] - - # Steering (Active: 50Hz, inactive: 10Hz) - steer_step = self.params.STEER_STEP if CC.latActive else self.params.INACTIVE_STEER_STEP - - if self.CP.networkLocation == NetworkLocation.fwdCamera: - # Also send at 50Hz: - # - on startup, first few msgs are blocked - # - until we're in sync with camera so counters align when relay closes, preventing a fault. - # openpilot can subtly drift, so this is activated throughout a drive to stay synced - out_of_sync = self.lka_steering_cmd_counter % 4 != (CS.cam_lka_steering_cmd_counter + 1) % 4 - if CS.loopback_lka_steering_cmd_ts_nanos == 0 or out_of_sync: - steer_step = self.params.STEER_STEP - - self.lka_steering_cmd_counter += 1 if CS.loopback_lka_steering_cmd_updated else 0 - - # Avoid GM EPS faults when transmitting messages too close together: skip this transmit if we - # received the ASCMLKASteeringCmd loopback confirmation too recently - last_lka_steer_msg_ms = (now_nanos - CS.loopback_lka_steering_cmd_ts_nanos) * 1e-6 - if (self.frame - self.last_steer_frame) >= steer_step and last_lka_steer_msg_ms > MIN_STEER_MSG_INTERVAL_MS: - # Initialize ASCMLKASteeringCmd counter using the camera until we get a msg on the bus - if CS.loopback_lka_steering_cmd_ts_nanos == 0: - self.lka_steering_cmd_counter = CS.pt_lka_steering_cmd_counter + 1 - - if CC.latActive: - new_steer = int(round(actuators.steer * self.params.STEER_MAX)) - apply_steer = apply_driver_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.params) - else: - apply_steer = 0 - - self.last_steer_frame = self.frame - self.apply_steer_last = apply_steer - idx = self.lka_steering_cmd_counter % 4 - can_sends.append(gmcan.create_steering_control(self.packer_pt, CanBus.POWERTRAIN, apply_steer, idx, CC.latActive)) - - if self.CP.openpilotLongitudinalControl: - # Gas/regen, brakes, and UI commands - all at 25Hz - if self.frame % 4 == 0: - stopping = actuators.longControlState == LongCtrlState.stopping - if not CC.longActive: - # ASCM sends max regen when not enabled - self.apply_gas = self.params.INACTIVE_REGEN - self.apply_brake = 0 - else: - self.apply_gas = int(round(interp(actuators.accel, self.params.GAS_LOOKUP_BP, self.params.GAS_LOOKUP_V))) - self.apply_brake = int(round(interp(actuators.accel, self.params.BRAKE_LOOKUP_BP, self.params.BRAKE_LOOKUP_V))) - # Don't allow any gas above inactive regen while stopping - # FIXME: brakes aren't applied immediately when enabling at a stop - if stopping: - self.apply_gas = self.params.INACTIVE_REGEN - - idx = (self.frame // 4) % 4 - - at_full_stop = CC.longActive and CS.out.standstill - near_stop = CC.longActive and (CS.out.vEgo < self.params.NEAR_STOP_BRAKE_PHASE) - friction_brake_bus = CanBus.CHASSIS - # GM Camera exceptions - # TODO: can we always check the longControlState? - if self.CP.networkLocation == NetworkLocation.fwdCamera: - at_full_stop = at_full_stop and stopping - friction_brake_bus = CanBus.POWERTRAIN - - # GasRegenCmdActive needs to be 1 to avoid cruise faults. It describes the ACC state, not actuation - can_sends.append(gmcan.create_gas_regen_command(self.packer_pt, CanBus.POWERTRAIN, self.apply_gas, idx, CC.enabled, at_full_stop)) - can_sends.append(gmcan.create_friction_brake_command(self.packer_ch, friction_brake_bus, self.apply_brake, - idx, CC.enabled, near_stop, at_full_stop, self.CP)) - - # Send dashboard UI commands (ACC status) - send_fcw = hud_alert == VisualAlert.fcw - can_sends.append(gmcan.create_acc_dashboard_command(self.packer_pt, CanBus.POWERTRAIN, CC.enabled, - hud_v_cruise * CV.MS_TO_KPH, hud_control, send_fcw)) - - # Radar needs to know current speed and yaw rate (50hz), - # and that ADAS is alive (10hz) - if not self.CP.radarUnavailable: - tt = self.frame * DT_CTRL - time_and_headlights_step = 10 - if self.frame % time_and_headlights_step == 0: - idx = (self.frame // time_and_headlights_step) % 4 - can_sends.append(gmcan.create_adas_time_status(CanBus.OBSTACLE, int((tt - self.start_time) * 60), idx)) - can_sends.append(gmcan.create_adas_headlights_status(self.packer_obj, CanBus.OBSTACLE)) - - speed_and_accelerometer_step = 2 - if self.frame % speed_and_accelerometer_step == 0: - idx = (self.frame // speed_and_accelerometer_step) % 4 - can_sends.append(gmcan.create_adas_steering_status(CanBus.OBSTACLE, idx)) - can_sends.append(gmcan.create_adas_accelerometer_speed_status(CanBus.OBSTACLE, CS.out.vEgo, idx)) - - if self.CP.networkLocation == NetworkLocation.gateway and self.frame % self.params.ADAS_KEEPALIVE_STEP == 0: - can_sends += gmcan.create_adas_keepalive(CanBus.POWERTRAIN) - - else: - # While car is braking, cancel button causes ECM to enter a soft disable state with a fault status. - # A delayed cancellation allows camera to cancel and avoids a fault when user depresses brake quickly - self.cancel_counter = self.cancel_counter + 1 if CC.cruiseControl.cancel else 0 - - # Stock longitudinal, integrated at camera - if (self.frame - self.last_button_frame) * DT_CTRL > 0.04: - if self.cancel_counter > CAMERA_CANCEL_DELAY_FRAMES: - self.last_button_frame = self.frame - can_sends.append(gmcan.create_buttons(self.packer_pt, CanBus.CAMERA, CS.buttons_counter, CruiseButtons.CANCEL)) - - if self.CP.networkLocation == NetworkLocation.fwdCamera: - # Silence "Take Steering" alert sent by camera, forward PSCMStatus with HandsOffSWlDetectionStatus=1 - if self.frame % 10 == 0: - can_sends.append(gmcan.create_pscm_status(self.packer_pt, CanBus.CAMERA, CS.pscm_status)) - - new_actuators = actuators.as_builder() - new_actuators.steer = self.apply_steer_last / self.params.STEER_MAX - new_actuators.steerOutputCan = self.apply_steer_last - new_actuators.gas = self.apply_gas - new_actuators.brake = self.apply_brake - - self.frame += 1 - return new_actuators, can_sends diff --git a/car/gm/carstate.py b/car/gm/carstate.py deleted file mode 100644 index a1129c59c8..0000000000 --- a/car/gm/carstate.py +++ /dev/null @@ -1,180 +0,0 @@ -import copy -from cereal import car -from openpilot.common.conversions import Conversions as CV -from openpilot.common.numpy_fast import mean -from opendbc.can.can_define import CANDefine -from opendbc.can.parser import CANParser -from openpilot.selfdrive.car.interfaces import CarStateBase -from openpilot.selfdrive.car.gm.values import DBC, AccState, CanBus, STEER_THRESHOLD - -TransmissionType = car.CarParams.TransmissionType -NetworkLocation = car.CarParams.NetworkLocation -STANDSTILL_THRESHOLD = 10 * 0.0311 * CV.KPH_TO_MS - - -class CarState(CarStateBase): - def __init__(self, CP): - super().__init__(CP) - can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) - self.shifter_values = can_define.dv["ECMPRDNL2"]["PRNDL2"] - self.cluster_speed_hyst_gap = CV.KPH_TO_MS / 2. - self.cluster_min_speed = CV.KPH_TO_MS / 2. - - self.loopback_lka_steering_cmd_updated = False - self.loopback_lka_steering_cmd_ts_nanos = 0 - self.pt_lka_steering_cmd_counter = 0 - self.cam_lka_steering_cmd_counter = 0 - self.buttons_counter = 0 - - self.prev_distance_button = 0 - self.distance_button = 0 - - def update(self, pt_cp, cam_cp, loopback_cp): - ret = car.CarState.new_message() - - self.prev_cruise_buttons = self.cruise_buttons - self.prev_distance_button = self.distance_button - self.cruise_buttons = pt_cp.vl["ASCMSteeringButton"]["ACCButtons"] - self.distance_button = pt_cp.vl["ASCMSteeringButton"]["DistanceButton"] - self.buttons_counter = pt_cp.vl["ASCMSteeringButton"]["RollingCounter"] - self.pscm_status = copy.copy(pt_cp.vl["PSCMStatus"]) - # This is to avoid a fault where you engage while still moving backwards after shifting to D. - # An Equinox has been seen with an unsupported status (3), so only check if either wheel is in reverse (2) - self.moving_backward = (pt_cp.vl["EBCMWheelSpdRear"]["RLWheelDir"] == 2) or (pt_cp.vl["EBCMWheelSpdRear"]["RRWheelDir"] == 2) - - # Variables used for avoiding LKAS faults - self.loopback_lka_steering_cmd_updated = len(loopback_cp.vl_all["ASCMLKASteeringCmd"]["RollingCounter"]) > 0 - if self.loopback_lka_steering_cmd_updated: - self.loopback_lka_steering_cmd_ts_nanos = loopback_cp.ts_nanos["ASCMLKASteeringCmd"]["RollingCounter"] - if self.CP.networkLocation == NetworkLocation.fwdCamera: - self.pt_lka_steering_cmd_counter = pt_cp.vl["ASCMLKASteeringCmd"]["RollingCounter"] - self.cam_lka_steering_cmd_counter = cam_cp.vl["ASCMLKASteeringCmd"]["RollingCounter"] - - ret.wheelSpeeds = self.get_wheel_speeds( - pt_cp.vl["EBCMWheelSpdFront"]["FLWheelSpd"], - pt_cp.vl["EBCMWheelSpdFront"]["FRWheelSpd"], - pt_cp.vl["EBCMWheelSpdRear"]["RLWheelSpd"], - pt_cp.vl["EBCMWheelSpdRear"]["RRWheelSpd"], - ) - 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) - # sample rear wheel speeds, standstill=True if ECM allows engagement with brake - ret.standstill = ret.wheelSpeeds.rl <= STANDSTILL_THRESHOLD and ret.wheelSpeeds.rr <= STANDSTILL_THRESHOLD - - 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)) - - ret.brake = pt_cp.vl["ECMAcceleratorPos"]["BrakePedalPos"] - if self.CP.networkLocation == NetworkLocation.fwdCamera: - ret.brakePressed = pt_cp.vl["ECMEngineStatus"]["BrakePressed"] != 0 - else: - # Some Volt 2016-17 have loose brake pedal push rod retainers which causes the ECM to believe - # that the brake is being intermittently pressed without user interaction. - # To avoid a cruise fault we need to use a conservative brake position threshold - # https://static.nhtsa.gov/odi/tsbs/2017/MC-10137629-9999.pdf - ret.brakePressed = ret.brake >= 8 - - # Regen braking is braking - if self.CP.transmissionType == TransmissionType.direct: - ret.regenBraking = pt_cp.vl["EBCMRegenPaddle"]["RegenPaddle"] != 0 - - ret.gas = pt_cp.vl["AcceleratorPedal2"]["AcceleratorPedal2"] / 254. - ret.gasPressed = ret.gas > 1e-5 - - ret.steeringAngleDeg = pt_cp.vl["PSCMSteeringAngle"]["SteeringWheelAngle"] - ret.steeringRateDeg = pt_cp.vl["PSCMSteeringAngle"]["SteeringWheelRate"] - ret.steeringTorque = pt_cp.vl["PSCMStatus"]["LKADriverAppldTrq"] - ret.steeringTorqueEps = pt_cp.vl["PSCMStatus"]["LKATorqueDelivered"] - ret.steeringPressed = abs(ret.steeringTorque) > STEER_THRESHOLD - - # 0 inactive, 1 active, 2 temporarily limited, 3 failed - self.lkas_status = pt_cp.vl["PSCMStatus"]["LKATorqueDeliveredStatus"] - ret.steerFaultTemporary = self.lkas_status == 2 - ret.steerFaultPermanent = self.lkas_status == 3 - - # 1 - open, 0 - closed - ret.doorOpen = (pt_cp.vl["BCMDoorBeltStatus"]["FrontLeftDoor"] == 1 or - pt_cp.vl["BCMDoorBeltStatus"]["FrontRightDoor"] == 1 or - pt_cp.vl["BCMDoorBeltStatus"]["RearLeftDoor"] == 1 or - pt_cp.vl["BCMDoorBeltStatus"]["RearRightDoor"] == 1) - - # 1 - latched - ret.seatbeltUnlatched = pt_cp.vl["BCMDoorBeltStatus"]["LeftSeatBelt"] == 0 - ret.leftBlinker = pt_cp.vl["BCMTurnSignals"]["TurnSignals"] == 1 - ret.rightBlinker = pt_cp.vl["BCMTurnSignals"]["TurnSignals"] == 2 - - ret.parkingBrake = pt_cp.vl["BCMGeneralPlatformStatus"]["ParkBrakeSwActive"] == 1 - ret.cruiseState.available = pt_cp.vl["ECMEngineStatus"]["CruiseMainOn"] != 0 - ret.espDisabled = pt_cp.vl["ESPStatus"]["TractionControlOn"] != 1 - ret.accFaulted = (pt_cp.vl["AcceleratorPedal2"]["CruiseState"] == AccState.FAULTED or - pt_cp.vl["EBCMFrictionBrakeStatus"]["FrictionBrakeUnavailable"] == 1) - - ret.cruiseState.enabled = pt_cp.vl["AcceleratorPedal2"]["CruiseState"] != AccState.OFF - ret.cruiseState.standstill = pt_cp.vl["AcceleratorPedal2"]["CruiseState"] == AccState.STANDSTILL - if self.CP.networkLocation == NetworkLocation.fwdCamera: - ret.cruiseState.speed = cam_cp.vl["ASCMActiveCruiseControlStatus"]["ACCSpeedSetpoint"] * CV.KPH_TO_MS - ret.stockAeb = cam_cp.vl["AEBCmd"]["AEBCmdActive"] != 0 - # openpilot controls nonAdaptive when not pcmCruise - if self.CP.pcmCruise: - ret.cruiseState.nonAdaptive = cam_cp.vl["ASCMActiveCruiseControlStatus"]["ACCCruiseState"] not in (2, 3) - - if self.CP.enableBsm: - ret.leftBlindspot = pt_cp.vl["BCMBlindSpotMonitor"]["LeftBSM"] == 1 - ret.rightBlindspot = pt_cp.vl["BCMBlindSpotMonitor"]["RightBSM"] == 1 - - return ret - - @staticmethod - def get_cam_can_parser(CP): - messages = [] - if CP.networkLocation == NetworkLocation.fwdCamera: - messages += [ - ("AEBCmd", 10), - ("ASCMLKASteeringCmd", 10), - ("ASCMActiveCruiseControlStatus", 25), - ] - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus.CAMERA) - - @staticmethod - def get_can_parser(CP): - messages = [ - ("BCMTurnSignals", 1), - ("ECMPRDNL2", 10), - ("PSCMStatus", 10), - ("ESPStatus", 10), - ("BCMDoorBeltStatus", 10), - ("BCMGeneralPlatformStatus", 10), - ("EBCMWheelSpdFront", 20), - ("EBCMWheelSpdRear", 20), - ("EBCMFrictionBrakeStatus", 20), - ("AcceleratorPedal2", 33), - ("ASCMSteeringButton", 33), - ("ECMEngineStatus", 100), - ("PSCMSteeringAngle", 100), - ("ECMAcceleratorPos", 80), - ] - - if CP.enableBsm: - messages.append(("BCMBlindSpotMonitor", 10)) - - # Used to read back last counter sent to PT by camera - if CP.networkLocation == NetworkLocation.fwdCamera: - messages += [ - ("ASCMLKASteeringCmd", 0), - ] - - if CP.transmissionType == TransmissionType.direct: - messages.append(("EBCMRegenPaddle", 50)) - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus.POWERTRAIN) - - @staticmethod - def get_loopback_can_parser(CP): - messages = [ - ("ASCMLKASteeringCmd", 0), - ] - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus.LOOPBACK) diff --git a/car/gm/fingerprints.py b/car/gm/fingerprints.py deleted file mode 100644 index 3752fbb8d3..0000000000 --- a/car/gm/fingerprints.py +++ /dev/null @@ -1,63 +0,0 @@ -# ruff: noqa: E501 -from openpilot.selfdrive.car.gm.values import CAR - -# Trailblazer also matches as a SILVERADO, TODO: split with fw versions -# FIXME: There are Equinox users with different message lengths, specifically 304 and 320 - - -FINGERPRINTS = { - CAR.HOLDEN_ASTRA: [{ - 190: 8, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 8, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 393: 8, 398: 8, 401: 8, 413: 8, 417: 8, 419: 8, 422: 1, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 8, 455: 7, 456: 8, 458: 5, 479: 8, 481: 7, 485: 8, 489: 8, 497: 8, 499: 3, 500: 8, 501: 8, 508: 8, 528: 5, 532: 6, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 567: 5, 647: 5, 707: 8, 715: 8, 723: 8, 753: 5, 761: 7, 806: 1, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 961: 8, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1009: 8, 1011: 6, 1017: 8, 1019: 3, 1020: 8, 1105: 6, 1217: 8, 1221: 5, 1225: 8, 1233: 8, 1249: 8, 1257: 6, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 8, 1280: 4, 1300: 8, 1328: 4, 1417: 8, 1906: 7, 1907: 7, 1908: 7, 1912: 7, 1919: 7 - }], - CAR.CHEVROLET_VOLT: [{ - 170: 8, 171: 8, 189: 7, 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 288: 5, 289: 8, 298: 8, 304: 1, 308: 4, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 389: 2, 390: 7, 417: 7, 419: 1, 426: 7, 451: 8, 452: 8, 453: 6, 454: 8, 456: 8, 479: 3, 481: 7, 485: 8, 489: 8, 493: 8, 495: 4, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 528: 4, 532: 6, 546: 7, 550: 8, 554: 3, 558: 8, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 566: 5, 567: 3, 568: 1, 573: 1, 577: 8, 647: 3, 707: 8, 711: 6, 715: 8, 761: 7, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 961: 8, 969: 8, 977: 8, 979: 7, 988: 6, 989: 8, 995: 7, 1001: 8, 1005: 6, 1009: 8, 1017: 8, 1019: 2, 1020: 8, 1105: 6, 1187: 4, 1217: 8, 1221: 5, 1223: 3, 1225: 7, 1227: 4, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1273: 3, 1275: 3, 1280: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1601: 8, 1905: 7, 1906: 7, 1907: 7, 1910: 7, 1912: 7, 1922: 7, 1927: 7, 1928: 7, 2016: 8, 2020: 8, 2024: 8, 2028: 8 - }, - { - 170: 8, 171: 8, 189: 7, 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 288: 5, 298: 8, 304: 1, 308: 4, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 389: 2, 390: 7, 417: 7, 419: 1, 426: 7, 451: 8, 452: 8, 453: 6, 454: 8, 456: 8, 479: 3, 481: 7, 485: 8, 489: 8, 493: 8, 495: 4, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 528: 4, 532: 6, 546: 7, 550: 8, 554: 3, 558: 8, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 566: 5, 567: 3, 568: 1, 573: 1, 577: 8, 578: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 3, 707: 8, 711: 6, 715: 8, 717: 5, 761: 7, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 961: 8, 967: 4, 969: 8, 977: 8, 979: 7, 988: 6, 989: 8, 995: 7, 1001: 8, 1005: 6, 1009: 8, 1017: 8, 1019: 2, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1187: 4, 1217: 8, 1221: 5, 1223: 3, 1225: 7, 1227: 4, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1273: 3, 1275: 3, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1516: 8, 1601: 8, 1618: 8, 1905: 7, 1906: 7, 1907: 7, 1910: 7, 1912: 7, 1922: 7, 1927: 7, 1930: 7, 2016: 8, 2018: 8, 2020: 8, 2024: 8, 2028: 8 - }, - { - 170: 8, 171: 8, 189: 7, 190: 6, 192: 5, 193: 8, 197: 8, 199: 4, 201: 6, 209: 7, 211: 2, 241: 6, 288: 5, 289: 1, 290: 1, 298: 2, 304: 1, 308: 4, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 368: 8, 381: 2, 384: 8, 386: 5, 388: 8, 389: 2, 390: 7, 417: 7, 419: 1, 426: 7, 451: 8, 452: 8, 453: 6, 454: 8, 456: 8, 458: 8, 479: 3, 481: 7, 485: 8, 489: 5, 493: 8, 495: 4, 497: 8, 499: 3, 500: 6, 501: 3, 508: 8, 512: 3, 528: 4, 530: 8, 532: 6, 537: 5, 539: 8, 542: 7, 546: 7, 550: 8, 554: 3, 558: 8, 560: 6, 562: 4, 563: 5, 564: 5, 565: 5, 566: 5, 567: 3, 568: 1, 573: 1, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 3, 707: 8, 711: 6, 761: 7, 810: 8, 821: 4, 823: 7, 832: 8, 840: 5, 842: 5, 844: 8, 853: 8, 866: 4, 961: 8, 967: 4, 969: 8, 977: 8, 979: 7, 988: 6, 989: 8, 995: 7, 1001: 5, 1003: 5, 1005: 6, 1009: 8, 1017: 8, 1019: 2, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1187: 4, 1217: 8, 1221: 5, 1223: 3, 1225: 7, 1227: 4, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1273: 3, 1275: 3, 1280: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1905: 7, 1906: 7, 1907: 7, 1910: 7, 1912: 7, 1922: 7, 1927: 7 - }], - CAR.BUICK_LACROSSE: [{ - 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 322: 7, 328: 1, 352: 5, 353: 3, 381: 6, 386: 8, 388: 8, 393: 7, 398: 8, 407: 7, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 455: 7, 456: 8, 463: 3, 479: 3, 481: 7, 485: 8, 487: 8, 489: 8, 495: 4, 497: 8, 499: 3, 500: 6, 501: 8, 503: 1, 508: 8, 510: 8, 528: 5, 532: 6, 534: 2, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 567: 5, 573: 1, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 5, 707: 8, 753: 5, 761: 7, 801: 8, 804: 3, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 872: 1, 882: 8, 890: 1, 892: 2, 893: 1, 894: 1, 961: 8, 967: 4, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1005: 6, 1009: 8, 1011: 6, 1013: 3, 1017: 8, 1019: 2, 1020: 8, 1022: 1, 1105: 6, 1217: 8, 1221: 5, 1223: 2, 1225: 7, 1233: 8, 1243: 3, 1249: 8, 1257: 6, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 1, 1280: 4, 1300: 8, 1322: 6, 1328: 4, 1417: 8, 1609: 8, 1613: 8, 1649: 8, 1792: 8, 1798: 8, 1824: 8, 1825: 8, 1840: 8, 1842: 8, 1858: 8, 1860: 8, 1863: 8, 1872: 8, 1875: 8, 1882: 8, 1888: 8, 1889: 8, 1892: 8, 1904: 7, 1906: 7, 1907: 7, 1912: 7, 1913: 7, 1914: 7, 1916: 7, 1918: 7, 1919: 7, 1937: 8, 1953: 8, 1968: 8, 2001: 8, 2017: 8, 2018: 8, 2020: 8, 2026: 8 - }], - CAR.BUICK_REGAL: [{ - 190: 8, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 8, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 322: 7, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 393: 7, 398: 8, 407: 7, 413: 8, 417: 8, 419: 8, 422: 4, 426: 8, 431: 8, 442: 8, 451: 8, 452: 8, 453: 8, 455: 7, 456: 8, 463: 3, 479: 8, 481: 7, 485: 8, 487: 8, 489: 8, 495: 8, 497: 8, 499: 3, 500: 8, 501: 8, 508: 8, 528: 5, 532: 6, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 567: 5, 569: 3, 573: 1, 577: 8, 578: 8, 579: 8, 587: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 3, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 882: 8, 884: 8, 890: 1, 892: 2, 893: 2, 894: 1, 961: 8, 967: 8, 969: 8, 977: 8, 979: 8, 985: 8, 1001: 8, 1005: 6, 1009: 8, 1011: 8, 1013: 3, 1017: 8, 1020: 8, 1024: 8, 1025: 8, 1026: 8, 1027: 8, 1028: 8, 1029: 8, 1030: 8, 1031: 8, 1032: 2, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1223: 8, 1225: 7, 1233: 8, 1249: 8, 1257: 6, 1259: 8, 1261: 8, 1263: 8, 1265: 8, 1267: 8, 1271: 8, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1328: 4, 1417: 8, 1601: 8, 1602: 8, 1603: 7, 1611: 8, 1618: 8, 1906: 8, 1907: 7, 1912: 7, 1914: 7, 1916: 7, 1919: 7, 1930: 7, 2016: 8, 2018: 8, 2019: 8, 2024: 8, 2026: 8 - }], - CAR.CADILLAC_ATS: [{ - 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 322: 7, 328: 1, 352: 5, 368: 3, 381: 6, 384: 4, 386: 8, 388: 8, 393: 7, 398: 8, 401: 8, 407: 7, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 455: 7, 456: 8, 462: 4, 479: 3, 481: 7, 485: 8, 487: 8, 489: 8, 491: 2, 493: 8, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 510: 8, 528: 5, 532: 6, 534: 2, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 567: 5, 573: 1, 577: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 6, 707: 8, 715: 8, 717: 5, 719: 5, 723: 2, 753: 5, 761: 7, 801: 8, 804: 3, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 882: 8, 890: 1, 892: 2, 893: 2, 894: 1, 961: 8, 967: 4, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1005: 6, 1009: 8, 1011: 6, 1013: 3, 1017: 8, 1019: 2, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1223: 3, 1225: 7, 1233: 8, 1241: 3, 1249: 8, 1257: 6, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 1, 1271: 8, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1601: 8, 1904: 7, 1906: 7, 1907: 7, 1912: 7, 1916: 7, 1917: 7, 1918: 7, 1919: 7, 1920: 7, 1930: 7, 2016: 8, 2024: 8 - }], - CAR.CHEVROLET_MALIBU: [{ - 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 393: 7, 398: 8, 407: 7, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 455: 7, 456: 8, 479: 3, 481: 7, 485: 8, 487: 8, 489: 8, 495: 4, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 510: 8, 528: 5, 532: 6, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 565: 5, 567: 5, 573: 1, 577: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 6, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 961: 8, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1005: 6, 1009: 8, 1013: 3, 1017: 8, 1019: 2, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1223: 2, 1225: 7, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1601: 8, 1906: 7, 1907: 7, 1912: 7, 1919: 7, 1930: 7, 2016: 8, 2024: 8 - }], - CAR.GMC_ACADIA: [{ - 190: 6, 192: 5, 193: 8, 197: 8, 199: 4, 201: 6, 208: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 289: 1, 290: 1, 298: 8, 304: 8, 309: 8, 313: 8, 320: 8, 322: 7, 328: 1, 352: 7, 368: 8, 381: 8, 384: 8, 386: 8, 388: 8, 393: 8, 398: 8, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 454: 8, 455: 7, 458: 8, 460: 4, 462: 4, 463: 3, 479: 3, 481: 7, 485: 8, 489: 5, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 510: 8, 512: 3, 530: 8, 532: 6, 534: 2, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 567: 5, 568: 2, 573: 1, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 6, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 789: 5, 800: 6, 801: 8, 803: 8, 804: 3, 805: 8, 832: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 961: 8, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1003: 5, 1005: 6, 1009: 8, 1017: 8, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1225: 8, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1328: 4, 1417: 8, 1906: 7, 1907: 7, 1912: 7, 1914: 7, 1918: 7, 1919: 7, 1920: 7, 1930: 7 - }, - { - 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 208: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 289: 8, 298: 8, 304: 1, 309: 8, 313: 8, 320: 3, 322: 7, 328: 1, 338: 6, 340: 6, 352: 5, 381: 8, 384: 4, 386: 8, 388: 8, 393: 8, 398: 8, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 454: 8, 455: 7, 462: 4, 463: 3, 479: 3, 481: 7, 485: 8, 489: 8, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 510: 8, 532: 6, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 567: 5, 573: 1, 577: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 6, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 961: 8, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1005: 6, 1009: 8, 1017: 8, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1225: 8, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1328: 4, 1417: 8, 1601: 8, 1906: 7, 1907: 7, 1912: 7, 1914: 7, 1919: 7, 1920: 7, 1930: 7, 2016: 8, 2024: 8 - }], - CAR.CADILLAC_ESCALADE: [{ - 170: 8, 190: 6, 193: 8, 197: 8, 199: 4, 201: 8, 208: 8, 209: 7, 211: 2, 241: 6, 249: 8, 288: 5, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 322: 7, 328: 1, 352: 5, 381: 6, 384: 4, 386: 8, 388: 8, 393: 7, 398: 8, 407: 4, 413: 8, 417: 7, 419: 1, 422: 4, 426: 7, 431: 8, 442: 8, 451: 8, 452: 8, 453: 6, 454: 8, 455: 7, 460: 5, 462: 4, 463: 3, 479: 3, 481: 7, 485: 8, 487: 8, 489: 8, 497: 8, 499: 3, 500: 6, 501: 8, 508: 8, 510: 8, 532: 6, 534: 2, 554: 3, 560: 8, 562: 8, 563: 5, 564: 5, 573: 1, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 647: 6, 707: 8, 715: 8, 717: 5, 719: 5, 761: 7, 801: 8, 804: 3, 810: 8, 840: 5, 842: 5, 844: 8, 866: 4, 869: 4, 880: 6, 961: 8, 967: 4, 969: 8, 977: 8, 979: 8, 985: 5, 1001: 8, 1005: 6, 1009: 8, 1017: 8, 1019: 2, 1020: 8, 1033: 7, 1034: 7, 1105: 6, 1217: 8, 1221: 5, 1223: 2, 1225: 7, 1233: 8, 1249: 8, 1257: 6, 1265: 8, 1267: 1, 1280: 4, 1296: 4, 1300: 8, 1322: 6, 1323: 4, 1328: 4, 1417: 8, 1609: 8, 1613: 8, 1649: 8, 1792: 8, 1798: 8, 1824: 8, 1825: 8, 1840: 8, 1842: 8, 1858: 8, 1860: 8, 1863: 8, 1872: 8, 1875: 8, 1882: 8, 1888: 8, 1889: 8, 1892: 8, 1906: 7, 1907: 7, 1912: 7, 1914: 7, 1917: 7, 1918: 7, 1919: 7, 1920: 7, 1930: 7, 1937: 8, 1953: 8, 1968: 8, 2001: 8, 2017: 8, 2018: 8, 2020: 8, 2026: 8 - }], - CAR.CADILLAC_ESCALADE_ESV: [{ - 309: 1, 848: 8, 849: 8, 850: 8, 851: 8, 852: 8, 853: 8, 854: 3, 1056: 6, 1057: 8, 1058: 8, 1059: 8, 1060: 8, 1061: 8, 1062: 8, 1063: 8, 1064: 8, 1065: 8, 1066: 8, 1067: 8, 1068: 8, 1120: 8, 1121: 8, 1122: 8, 1123: 8, 1124: 8, 1125: 8, 1126: 8, 1127: 8, 1128: 8, 1129: 8, 1130: 8, 1131: 8, 1132: 8, 1133: 8, 1134: 8, 1135: 8, 1136: 8, 1137: 8, 1138: 8, 1139: 8, 1140: 8, 1141: 8, 1142: 8, 1143: 8, 1146: 8, 1147: 8, 1148: 8, 1149: 8, 1150: 8, 1151: 8, 1216: 8, 1217: 8, 1218: 8, 1219: 8, 1220: 8, 1221: 8, 1222: 8, 1223: 8, 1224: 8, 1225: 8, 1226: 8, 1232: 8, 1233: 8, 1234: 8, 1235: 8, 1236: 8, 1237: 8, 1238: 8, 1239: 8, 1240: 8, 1241: 8, 1242: 8, 1787: 8, 1788: 8 - }], - CAR.CADILLAC_ESCALADE_ESV_2019: [{ - 715: 8, 840: 5, 717: 5, 869: 4, 880: 6, 289: 8, 454: 8, 842: 5, 460: 5, 463: 3, 801: 8, 170: 8, 190: 6, 241: 6, 201: 8, 417: 7, 211: 2, 419: 1, 398: 8, 426: 7, 487: 8, 442: 8, 451: 8, 452: 8, 453: 6, 479: 3, 311: 8, 500: 6, 647: 6, 193: 8, 707: 8, 197: 8, 209: 7, 199: 4, 455: 7, 313: 8, 481: 7, 485: 8, 489: 8, 249: 8, 393: 7, 407: 7, 413: 8, 422: 4, 431: 8, 501: 8, 499: 3, 810: 8, 508: 8, 381: 8, 462: 4, 532: 6, 562: 8, 386: 8, 761: 7, 573: 1, 554: 3, 719: 5, 560: 8, 1279: 4, 388: 8, 288: 5, 1005: 6, 497: 8, 844: 8, 961: 8, 967: 4, 977: 8, 979: 8, 985: 5, 1001: 8, 1017: 8, 1019: 2, 1020: 8, 1217: 8, 510: 8, 866: 4, 304: 1, 969: 8, 384: 4, 1033: 7, 1009: 8, 1034: 7, 1296: 4, 1930: 7, 1105: 5, 1013: 5, 1225: 7, 1919: 7, 320: 3, 534: 2, 352: 5, 298: 8, 1223: 2, 1233: 8, 608: 8, 1265: 8, 609: 6, 1267: 1, 1417: 8, 610: 6, 1906: 7, 611: 6, 612: 8, 613: 8, 208: 8, 564: 5, 309: 8, 1221: 5, 1280: 4, 1249: 8, 1907: 7, 1257: 6, 1300: 8, 1920: 7, 563: 5, 1322: 6, 1323: 4, 1328: 4, 1917: 7, 328: 1, 1912: 7, 1914: 7, 804: 3, 1918: 7 - }], - CAR.CHEVROLET_BOLT_EUV: [{ - 189: 7, 190: 7, 193: 8, 197: 8, 201: 8, 209: 7, 211: 3, 241: 6, 257: 8, 288: 5, 289: 8, 298: 8, 304: 3, 309: 8, 311: 8, 313: 8, 320: 4, 322: 7, 328: 1, 352: 5, 381: 8, 384: 4, 386: 8, 388: 8, 451: 8, 452: 8, 453: 6, 458: 5, 463: 3, 479: 3, 481: 7, 485: 8, 489: 8, 497: 8, 500: 6, 501: 8, 528: 5, 532: 6, 560: 8, 562: 8, 563: 5, 565: 5, 566: 8, 587: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 789: 5, 800: 6, 810: 8, 840: 5, 842: 5, 844: 8, 848: 4, 869: 4, 880: 6, 977: 8, 1001: 8, 1017: 8, 1020: 8, 1217: 8, 1221: 5, 1233: 8, 1249: 8, 1265: 8, 1280: 4, 1296: 4, 1300: 8, 1611: 8, 1930: 7 - }], - CAR.CHEVROLET_SILVERADO: [{ - 190: 6, 193: 8, 197: 8, 201: 8, 208: 8, 209: 7, 211: 2, 241: 6, 249: 8, 257: 8, 288: 5, 289: 8, 298: 8, 304: 3, 309: 8, 311: 8, 313: 8, 320: 4, 322: 7, 328: 1, 352: 5, 381: 8, 384: 4, 386: 8, 388: 8, 413: 8, 451: 8, 452: 8, 453: 6, 455: 7, 460: 5, 463: 3, 479: 3, 481: 7, 485: 8, 489: 8, 497: 8, 500: 6, 501: 8, 528: 5, 532: 6, 534: 2, 560: 8, 562: 8, 563: 5, 565: 5, 587: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 707: 8, 715: 8, 717: 5, 761: 7, 789: 5, 800: 6, 801: 8, 810: 8, 840: 5, 842: 5, 844: 8, 848: 4, 869: 4, 880: 6, 977: 8, 1001: 8, 1011: 6, 1017: 8, 1020: 8, 1033: 7, 1034: 7, 1217: 8, 1221: 5, 1233: 8, 1249: 8, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 1, 1271: 8, 1280: 4, 1296: 4, 1300: 8, 1611: 8, 1930: 7 - }], - CAR.CHEVROLET_EQUINOX: [{ - 190: 6, 193: 8, 197: 8, 201: 8, 209: 7, 211: 2, 241: 6, 249: 8, 257: 8, 288: 5, 289: 8, 298: 8, 304: 1, 309: 8, 311: 8, 313: 8, 320: 3, 328: 1, 352: 5, 381: 8, 384: 4, 386: 8, 388: 8, 413: 8, 451: 8, 452: 8, 453: 6, 455: 7, 463: 3, 479: 3, 481: 7, 485: 8, 489: 8, 497: 8, 500: 6, 501: 8, 510: 8, 528: 5, 532: 6, 560: 8, 562: 8, 563: 5, 565: 5, 587: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 707: 8, 715: 8, 717: 5, 753: 5, 761: 7, 789: 5, 800: 6, 810: 8, 840: 5, 842: 5, 844: 8, 869: 4, 880: 6, 977: 8, 1001: 8, 1011: 6, 1017: 8, 1020: 8, 1033: 7, 1034: 7, 1217: 8, 1221: 5, 1233: 8, 1249: 8, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 1, 1271: 8, 1280: 4, 1296: 4, 1300: 8, 1611: 8, 1930: 7 - }, - { - 190: 6, 201: 8, 211: 2, 717: 5, 241: 6, 451: 8, 298: 8, 452: 8, 453: 6, 479: 3, 485: 8, 249: 8, 500: 6, 587: 8, 1611: 8, 289: 8, 481: 7, 193: 8, 197: 8, 209: 7, 455: 7, 489: 8, 309: 8, 413: 8, 501: 8, 608: 8, 609: 6, 610: 6, 611: 6, 612: 8, 613: 8, 311: 8, 510: 8, 528: 5, 532: 6, 715: 8, 560: 8, 562: 8, 707: 8, 789: 5, 869: 4, 880: 6, 761: 7, 840: 5, 842: 5, 844: 8, 313: 8, 381: 8, 386: 8, 810: 8, 322: 7, 384: 4, 800: 6, 1033: 7, 1034: 7, 1296: 4, 753: 5, 388: 8, 288: 5, 497: 8, 463: 3, 304: 3, 977: 8, 1001: 8, 1280: 4, 320: 4, 352: 5, 563: 5, 565: 5, 1221: 5, 1011: 6, 1017: 8, 1020: 8, 1249: 8, 1300: 8, 328: 1, 1217: 8, 1233: 8, 1259: 8, 1261: 7, 1263: 4, 1265: 8, 1267: 1, 1930: 7, 1271: 8 - }], -} - -FW_VERSIONS: dict[str, dict[tuple, list[bytes]]] = { -} diff --git a/car/gm/gmcan.py b/car/gm/gmcan.py deleted file mode 100644 index e833e77636..0000000000 --- a/car/gm/gmcan.py +++ /dev/null @@ -1,173 +0,0 @@ -from openpilot.selfdrive.car import make_can_msg -from openpilot.selfdrive.car.gm.values import CAR - - -def create_buttons(packer, bus, idx, button): - values = { - "ACCButtons": button, - "RollingCounter": idx, - "ACCAlwaysOne": 1, - "DistanceButton": 0, - } - - checksum = 240 + int(values["ACCAlwaysOne"] * 0xf) - checksum += values["RollingCounter"] * (0x4ef if values["ACCAlwaysOne"] != 0 else 0x3f0) - checksum -= int(values["ACCButtons"] - 1) << 4 # not correct if value is 0 - checksum -= 2 * values["DistanceButton"] - - values["SteeringButtonChecksum"] = checksum - return packer.make_can_msg("ASCMSteeringButton", bus, values) - - -def create_pscm_status(packer, bus, pscm_status): - values = {s: pscm_status[s] for s in [ - "HandsOffSWDetectionMode", - "HandsOffSWlDetectionStatus", - "LKATorqueDeliveredStatus", - "LKADriverAppldTrq", - "LKATorqueDelivered", - "LKATotalTorqueDelivered", - "RollingCounter", - "PSCMStatusChecksum", - ]} - checksum_mod = int(1 - values["HandsOffSWlDetectionStatus"]) << 5 - values["HandsOffSWlDetectionStatus"] = 1 - values["PSCMStatusChecksum"] += checksum_mod - return packer.make_can_msg("PSCMStatus", bus, values) - - -def create_steering_control(packer, bus, apply_steer, idx, lkas_active): - values = { - "LKASteeringCmdActive": lkas_active, - "LKASteeringCmd": apply_steer, - "RollingCounter": idx, - "LKASteeringCmdChecksum": 0x1000 - (lkas_active << 11) - (apply_steer & 0x7ff) - idx - } - - return packer.make_can_msg("ASCMLKASteeringCmd", bus, values) - - -def create_adas_keepalive(bus): - dat = b"\x00\x00\x00\x00\x00\x00\x00" - return [make_can_msg(0x409, dat, bus), make_can_msg(0x40a, dat, bus)] - - -def create_gas_regen_command(packer, bus, throttle, idx, enabled, at_full_stop): - values = { - "GasRegenCmdActive": enabled, - "RollingCounter": idx, - "GasRegenCmdActiveInv": 1 - enabled, - "GasRegenCmd": throttle, - "GasRegenFullStopActive": at_full_stop, - "GasRegenAlwaysOne": 1, - "GasRegenAlwaysOne2": 1, - "GasRegenAlwaysOne3": 1, - } - - dat = packer.make_can_msg("ASCMGasRegenCmd", bus, values)[2] - values["GasRegenChecksum"] = (((0xff - dat[1]) & 0xff) << 16) | \ - (((0xff - dat[2]) & 0xff) << 8) | \ - ((0x100 - dat[3] - idx) & 0xff) - - return packer.make_can_msg("ASCMGasRegenCmd", bus, values) - - -def create_friction_brake_command(packer, bus, apply_brake, idx, enabled, near_stop, at_full_stop, CP): - mode = 0x1 - - # TODO: Understand this better. Volts and ICE Camera ACC cars are 0x1 when enabled with no brake - if enabled and CP.carFingerprint in (CAR.CHEVROLET_BOLT_EUV,): - mode = 0x9 - - if apply_brake > 0: - mode = 0xa - if at_full_stop: - mode = 0xd - - # TODO: this is to have GM bringing the car to complete stop, - # but currently it conflicts with OP controls, so turned off. Not set by all cars - #elif near_stop: - # mode = 0xb - - brake = (0x1000 - apply_brake) & 0xfff - checksum = (0x10000 - (mode << 12) - brake - idx) & 0xffff - - values = { - "RollingCounter": idx, - "FrictionBrakeMode": mode, - "FrictionBrakeChecksum": checksum, - "FrictionBrakeCmd": -apply_brake - } - - return packer.make_can_msg("EBCMFrictionBrakeCmd", bus, values) - - -def create_acc_dashboard_command(packer, bus, enabled, target_speed_kph, hud_control, fcw): - target_speed = min(target_speed_kph, 255) - - values = { - "ACCAlwaysOne": 1, - "ACCResumeButton": 0, - "ACCSpeedSetpoint": target_speed, - "ACCGapLevel": hud_control.leadDistanceBars * enabled, # 3 "far", 0 "inactive" - "ACCCmdActive": enabled, - "ACCAlwaysOne2": 1, - "ACCLeadCar": hud_control.leadVisible, - "FCWAlert": 0x3 if fcw else 0 - } - - return packer.make_can_msg("ASCMActiveCruiseControlStatus", bus, values) - - -def create_adas_time_status(bus, tt, idx): - dat = [(tt >> 20) & 0xff, (tt >> 12) & 0xff, (tt >> 4) & 0xff, - ((tt & 0xf) << 4) + (idx << 2)] - chksum = 0x1000 - dat[0] - dat[1] - dat[2] - dat[3] - chksum = chksum & 0xfff - dat += [0x40 + (chksum >> 8), chksum & 0xff, 0x12] - return make_can_msg(0xa1, bytes(dat), bus) - - -def create_adas_steering_status(bus, idx): - dat = [idx << 6, 0xf0, 0x20, 0, 0, 0] - chksum = 0x60 + sum(dat) - dat += [chksum >> 8, chksum & 0xff] - return make_can_msg(0x306, bytes(dat), bus) - - -def create_adas_accelerometer_speed_status(bus, speed_ms, idx): - spd = int(speed_ms * 16) & 0xfff - accel = 0 & 0xfff - # 0 if in park/neutral, 0x10 if in reverse, 0x08 for D/L - #stick = 0x08 - near_range_cutoff = 0x27 - near_range_mode = 1 if spd <= near_range_cutoff else 0 - far_range_mode = 1 - near_range_mode - dat = [0x08, spd >> 4, ((spd & 0xf) << 4) | (accel >> 8), accel & 0xff, 0] - chksum = 0x62 + far_range_mode + (idx << 2) + dat[0] + dat[1] + dat[2] + dat[3] + dat[4] - dat += [(idx << 5) + (far_range_mode << 4) + (near_range_mode << 3) + (chksum >> 8), chksum & 0xff] - return make_can_msg(0x308, bytes(dat), bus) - - -def create_adas_headlights_status(packer, bus): - values = { - "Always42": 0x42, - "Always4": 0x4, - } - return packer.make_can_msg("ASCMHeadlight", bus, values) - - -def create_lka_icon_command(bus, active, critical, steer): - if active and steer == 1: - if critical: - dat = b"\x50\xc0\x14" - else: - dat = b"\x50\x40\x18" - elif active: - if critical: - dat = b"\x40\xc0\x14" - else: - dat = b"\x40\x40\x18" - else: - dat = b"\x00\x00\x00" - return make_can_msg(0x104c006c, dat, bus) diff --git a/car/gm/interface.py b/car/gm/interface.py deleted file mode 100755 index 358bc9e5ba..0000000000 --- a/car/gm/interface.py +++ /dev/null @@ -1,239 +0,0 @@ -#!/usr/bin/env python3 -import os -from cereal import car -from math import fabs, exp -from panda import Panda - -from openpilot.common.basedir import BASEDIR -from openpilot.common.conversions import Conversions as CV -from openpilot.selfdrive.car import create_button_events, get_safety_config -from openpilot.selfdrive.car.gm.radar_interface import RADAR_HEADER_MSG -from openpilot.selfdrive.car.gm.values import CAR, CruiseButtons, CarControllerParams, EV_CAR, CAMERA_ACC_CAR, CanBus -from openpilot.selfdrive.car.interfaces import CarInterfaceBase, TorqueFromLateralAccelCallbackType, FRICTION_THRESHOLD, LatControlInputs, NanoFFModel -from openpilot.selfdrive.controls.lib.drive_helpers import get_friction - -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, - CruiseButtons.MAIN: ButtonType.altButton3, CruiseButtons.CANCEL: ButtonType.cancel} - - -NON_LINEAR_TORQUE_PARAMS = { - CAR.CHEVROLET_BOLT_EUV: [2.6531724862969748, 1.0, 0.1919764879840985, 0.009054123646805178], - CAR.GMC_ACADIA: [4.78003305, 1.0, 0.3122, 0.05591772], - CAR.CHEVROLET_SILVERADO: [3.29974374, 1.0, 0.25571356, 0.0465122] -} - -NEURAL_PARAMS_PATH = os.path.join(BASEDIR, 'selfdrive/car/torque_data/neural_ff_weights.json') - - -class CarInterface(CarInterfaceBase): - @staticmethod - def get_pid_accel_limits(CP, current_speed, cruise_speed): - return CarControllerParams.ACCEL_MIN, CarControllerParams.ACCEL_MAX - - # Determined by iteratively plotting and minimizing error for f(angle, speed) = steer. - @staticmethod - def get_steer_feedforward_volt(desired_angle, v_ego): - desired_angle *= 0.02904609 - sigmoid = desired_angle / (1 + fabs(desired_angle)) - return 0.10006696 * sigmoid * (v_ego + 3.12485927) - - def get_steer_feedforward_function(self): - if self.CP.carFingerprint == CAR.CHEVROLET_VOLT: - return self.get_steer_feedforward_volt - else: - return CarInterfaceBase.get_steer_feedforward_default - - def torque_from_lateral_accel_siglin(self, latcontrol_inputs: LatControlInputs, torque_params: car.CarParams.LateralTorqueTuning, lateral_accel_error: float, - lateral_accel_deadzone: float, friction_compensation: bool, gravity_adjusted: bool) -> float: - friction = get_friction(lateral_accel_error, lateral_accel_deadzone, FRICTION_THRESHOLD, torque_params, friction_compensation) - - def sig(val): - return 1 / (1 + exp(-val)) - 0.5 - - # The "lat_accel vs torque" relationship is assumed to be the sum of "sigmoid + linear" curves - # An important thing to consider is that the slope at 0 should be > 0 (ideally >1) - # This has big effect on the stability about 0 (noise when going straight) - # ToDo: To generalize to other GMs, explore tanh function as the nonlinear - non_linear_torque_params = NON_LINEAR_TORQUE_PARAMS.get(self.CP.carFingerprint) - assert non_linear_torque_params, "The params are not defined" - a, b, c, _ = non_linear_torque_params - steer_torque = (sig(latcontrol_inputs.lateral_acceleration * a) * b) + (latcontrol_inputs.lateral_acceleration * c) - return float(steer_torque) + friction - - def torque_from_lateral_accel_neural(self, latcontrol_inputs: LatControlInputs, torque_params: car.CarParams.LateralTorqueTuning, lateral_accel_error: float, - lateral_accel_deadzone: float, friction_compensation: bool, gravity_adjusted: bool) -> float: - friction = get_friction(lateral_accel_error, lateral_accel_deadzone, FRICTION_THRESHOLD, torque_params, friction_compensation) - inputs = list(latcontrol_inputs) - if gravity_adjusted: - inputs[0] += inputs[1] - return float(self.neural_ff_model.predict(inputs)) + friction - - def torque_from_lateral_accel(self) -> TorqueFromLateralAccelCallbackType: - if self.CP.carFingerprint == CAR.CHEVROLET_BOLT_EUV: - self.neural_ff_model = NanoFFModel(NEURAL_PARAMS_PATH, self.CP.carFingerprint) - return self.torque_from_lateral_accel_neural - elif self.CP.carFingerprint in NON_LINEAR_TORQUE_PARAMS: - return self.torque_from_lateral_accel_siglin - else: - return self.torque_from_lateral_accel_linear - - @staticmethod - def _get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs): - ret.carName = "gm" - ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.gm)] - ret.autoResumeSng = False - ret.enableBsm = 0x142 in fingerprint[CanBus.POWERTRAIN] - - if candidate in EV_CAR: - ret.transmissionType = TransmissionType.direct - else: - ret.transmissionType = TransmissionType.automatic - - ret.longitudinalTuning.deadzoneBP = [0.] - ret.longitudinalTuning.deadzoneV = [0.15] - - ret.longitudinalTuning.kpBP = [5., 35.] - ret.longitudinalTuning.kiBP = [0.] - - if candidate in CAMERA_ACC_CAR: - ret.experimentalLongitudinalAvailable = True - ret.networkLocation = NetworkLocation.fwdCamera - ret.radarUnavailable = True # no radar - ret.pcmCruise = True - ret.safetyConfigs[0].safetyParam |= Panda.FLAG_GM_HW_CAM - ret.minEnableSpeed = 5 * CV.KPH_TO_MS - ret.minSteerSpeed = 10 * CV.KPH_TO_MS - - # Tuning for experimental long - ret.longitudinalTuning.kpV = [2.0, 1.5] - ret.longitudinalTuning.kiV = [0.72] - ret.stoppingDecelRate = 2.0 # reach brake quickly after enabling - ret.vEgoStopping = 0.25 - ret.vEgoStarting = 0.25 - - if experimental_long: - ret.pcmCruise = False - ret.openpilotLongitudinalControl = True - ret.safetyConfigs[0].safetyParam |= Panda.FLAG_GM_HW_CAM_LONG - - else: # ASCM, OBD-II harness - ret.openpilotLongitudinalControl = True - ret.networkLocation = NetworkLocation.gateway - ret.radarUnavailable = RADAR_HEADER_MSG not in fingerprint[CanBus.OBSTACLE] and not docs - ret.pcmCruise = False # stock non-adaptive cruise control is kept off - # supports stop and go, but initial engage must (conservatively) be above 18mph - ret.minEnableSpeed = 18 * CV.MPH_TO_MS - ret.minSteerSpeed = 7 * CV.MPH_TO_MS - - # Tuning - ret.longitudinalTuning.kpV = [2.4, 1.5] - ret.longitudinalTuning.kiV = [0.36] - - # These cars have been put into dashcam only due to both a lack of users and test coverage. - # These cars likely still work fine. Once a user confirms each car works and a test route is - # added to selfdrive/car/tests/routes.py, we can remove it from this list. - ret.dashcamOnly = candidate in {CAR.CADILLAC_ATS, CAR.HOLDEN_ASTRA, CAR.CHEVROLET_MALIBU, CAR.BUICK_REGAL} or \ - (ret.networkLocation == NetworkLocation.gateway and ret.radarUnavailable) - - # Start with a baseline tuning for all GM vehicles. Override tuning as needed in each model section below. - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2], [0.00]] - ret.lateralTuning.pid.kf = 0.00004 # full torque for 20 deg at 80mph means 0.00007818594 - ret.steerActuatorDelay = 0.1 # Default delay, not measured yet - - 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 - - if candidate == CAR.CHEVROLET_VOLT: - ret.lateralTuning.pid.kpBP = [0., 40.] - ret.lateralTuning.pid.kpV = [0., 0.17] - ret.lateralTuning.pid.kiBP = [0.] - ret.lateralTuning.pid.kiV = [0.] - ret.lateralTuning.pid.kf = 1. # get_steer_feedforward_volt() - ret.steerActuatorDelay = 0.2 - - elif candidate == CAR.GMC_ACADIA: - ret.minEnableSpeed = -1. # engage speed is decided by pcm - ret.steerActuatorDelay = 0.2 - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) - - elif candidate == CAR.BUICK_LACROSSE: - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) - - elif candidate == CAR.CADILLAC_ESCALADE: - ret.minEnableSpeed = -1. # engage speed is decided by pcm - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) - - elif candidate in (CAR.CADILLAC_ESCALADE_ESV, CAR.CADILLAC_ESCALADE_ESV_2019): - ret.minEnableSpeed = -1. # engage speed is decided by pcm - - if candidate == CAR.CADILLAC_ESCALADE_ESV: - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[10., 41.0], [10., 41.0]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.13, 0.24], [0.01, 0.02]] - ret.lateralTuning.pid.kf = 0.000045 - else: - ret.steerActuatorDelay = 0.2 - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) - - elif candidate == CAR.CHEVROLET_BOLT_EUV: - ret.steerActuatorDelay = 0.2 - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) - - elif candidate == CAR.CHEVROLET_SILVERADO: - # On the Bolt, the ECM and camera independently check that you are either above 5 kph or at a stop - # with foot on brake to allow engagement, but this platform only has that check in the camera. - # TODO: check if this is split by EV/ICE with more platforms in the future - if ret.openpilotLongitudinalControl: - ret.minEnableSpeed = -1. - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) - - elif candidate == CAR.CHEVROLET_EQUINOX: - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) - - elif candidate == CAR.CHEVROLET_TRAILBLAZER: - ret.steerActuatorDelay = 0.2 - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) - - return ret - - # returns a car.CarState - def _update(self, c): - ret = self.CS.update(self.cp, self.cp_cam, self.cp_loopback) - - # Don't add event if transitioning from INIT, unless it's to an actual button - if self.CS.cruise_buttons != CruiseButtons.UNPRESS or self.CS.prev_cruise_buttons != CruiseButtons.INIT: - ret.buttonEvents = [ - *create_button_events(self.CS.cruise_buttons, self.CS.prev_cruise_buttons, BUTTONS_DICT, - unpressed_btn=CruiseButtons.UNPRESS), - *create_button_events(self.CS.distance_button, self.CS.prev_distance_button, - {1: ButtonType.gapAdjustCruise}) - ] - - # The ECM allows enabling on falling edge of set, but only rising edge of resume - events = self.create_common_events(ret, extra_gears=[GearShifter.sport, GearShifter.low, - GearShifter.eco, GearShifter.manumatic], - pcm_enable=self.CP.pcmCruise, enable_buttons=(ButtonType.decelCruise,)) - if not self.CP.pcmCruise: - if any(b.type == ButtonType.accelCruise and b.pressed for b in ret.buttonEvents): - events.add(EventName.buttonEnable) - - # Enabling at a standstill with brake is allowed - # TODO: verify 17 Volt can enable for the first time at a stop and allow for all GMs - below_min_enable_speed = ret.vEgo < self.CP.minEnableSpeed or self.CS.moving_backward - if below_min_enable_speed and not (ret.standstill and ret.brake >= 20 and - self.CP.networkLocation == NetworkLocation.fwdCamera): - events.add(EventName.belowEngageSpeed) - if ret.cruiseState.standstill: - events.add(EventName.resumeRequired) - if ret.vEgo < self.CP.minSteerSpeed: - events.add(EventName.belowSteerSpeed) - - ret.events = events.to_msg() - - return ret diff --git a/car/gm/radar_interface.py b/car/gm/radar_interface.py deleted file mode 100755 index b893babd31..0000000000 --- a/car/gm/radar_interface.py +++ /dev/null @@ -1,101 +0,0 @@ -#!/usr/bin/env python3 -import math -from cereal import car -from openpilot.common.conversions import Conversions as CV -from opendbc.can.parser import CANParser -from openpilot.selfdrive.car.gm.values import DBC, CanBus -from openpilot.selfdrive.car.interfaces import RadarInterfaceBase - -RADAR_HEADER_MSG = 1120 -SLOT_1_MSG = RADAR_HEADER_MSG + 1 -NUM_SLOTS = 20 - -# Actually it's 0x47f, but can parser only reports -# messages that are present in DBC -LAST_RADAR_MSG = RADAR_HEADER_MSG + NUM_SLOTS - - -def create_radar_can_parser(car_fingerprint): - # C1A-ARS3-A by Continental - radar_targets = list(range(SLOT_1_MSG, SLOT_1_MSG + NUM_SLOTS)) - signals = list(zip(['FLRRNumValidTargets', - 'FLRRSnsrBlckd', 'FLRRYawRtPlsblityFlt', - 'FLRRHWFltPrsntInt', 'FLRRAntTngFltPrsnt', - 'FLRRAlgnFltPrsnt', 'FLRRSnstvFltPrsntInt'] + - ['TrkRange'] * NUM_SLOTS + ['TrkRangeRate'] * NUM_SLOTS + - ['TrkRangeAccel'] * NUM_SLOTS + ['TrkAzimuth'] * NUM_SLOTS + - ['TrkWidth'] * NUM_SLOTS + ['TrkObjectID'] * NUM_SLOTS, - [RADAR_HEADER_MSG] * 7 + radar_targets * 6, strict=True)) - - messages = list({(s[1], 14) for s in signals}) - - return CANParser(DBC[car_fingerprint]['radar'], messages, CanBus.OBSTACLE) - - -class RadarInterface(RadarInterfaceBase): - def __init__(self, CP): - super().__init__(CP) - - self.rcp = None if CP.radarUnavailable else create_radar_can_parser(CP.carFingerprint) - - self.trigger_msg = LAST_RADAR_MSG - self.updated_messages = set() - self.radar_ts = CP.radarTimeStep - - def update(self, can_strings): - if self.rcp is None: - return super().update(None) - - vls = self.rcp.update_strings(can_strings) - self.updated_messages.update(vls) - - if self.trigger_msg not in self.updated_messages: - return None - - ret = car.RadarData.new_message() - header = self.rcp.vl[RADAR_HEADER_MSG] - fault = header['FLRRSnsrBlckd'] or header['FLRRSnstvFltPrsntInt'] or \ - header['FLRRYawRtPlsblityFlt'] or header['FLRRHWFltPrsntInt'] or \ - header['FLRRAntTngFltPrsnt'] or header['FLRRAlgnFltPrsnt'] - errors = [] - if not self.rcp.can_valid: - errors.append("canError") - if fault: - errors.append("fault") - ret.errors = errors - - currentTargets = set() - num_targets = header['FLRRNumValidTargets'] - - # Not all radar messages describe targets, - # no need to monitor all of the self.rcp.msgs_upd - for ii in self.updated_messages: - if ii == RADAR_HEADER_MSG: - continue - - if num_targets == 0: - break - - cpt = self.rcp.vl[ii] - # Zero distance means it's an empty target slot - if cpt['TrkRange'] > 0.0: - targetId = cpt['TrkObjectID'] - currentTargets.add(targetId) - if targetId not in self.pts: - self.pts[targetId] = car.RadarData.RadarPoint.new_message() - self.pts[targetId].trackId = targetId - distance = cpt['TrkRange'] - self.pts[targetId].dRel = distance # from front of car - # From driver's pov, left is positive - self.pts[targetId].yRel = math.sin(cpt['TrkAzimuth'] * CV.DEG_TO_RAD) * distance - self.pts[targetId].vRel = cpt['TrkRangeRate'] - self.pts[targetId].aRel = float('nan') - self.pts[targetId].yvRel = float('nan') - - for oldTarget in list(self.pts.keys()): - if oldTarget not in currentTargets: - del self.pts[oldTarget] - - ret.points = list(self.pts.values()) - self.updated_messages.clear() - return ret diff --git a/car/gm/tests/__init__.py b/car/gm/tests/__init__.py deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/car/gm/tests/test_gm.py b/car/gm/tests/test_gm.py deleted file mode 100644 index a0a4a94ffa..0000000000 --- a/car/gm/tests/test_gm.py +++ /dev/null @@ -1,20 +0,0 @@ -from parameterized import parameterized - -from openpilot.selfdrive.car.gm.fingerprints import FINGERPRINTS -from openpilot.selfdrive.car.gm.values import CAMERA_ACC_CAR, GM_RX_OFFSET - -CAMERA_DIAGNOSTIC_ADDRESS = 0x24b - - -class TestGMFingerprint: - @parameterized.expand(FINGERPRINTS.items()) - def test_can_fingerprints(self, car_model, fingerprints): - assert len(fingerprints) > 0 - - assert all(len(finger) for finger in fingerprints) - - # The camera can sometimes be communicating on startup - if car_model in CAMERA_ACC_CAR: - for finger in fingerprints: - for required_addr in (CAMERA_DIAGNOSTIC_ADDRESS, CAMERA_DIAGNOSTIC_ADDRESS + GM_RX_OFFSET): - assert finger.get(required_addr) == 8, required_addr diff --git a/car/gm/values.py b/car/gm/values.py deleted file mode 100644 index 53a4621d27..0000000000 --- a/car/gm/values.py +++ /dev/null @@ -1,234 +0,0 @@ -from dataclasses import dataclass, field - -from cereal import car -from openpilot.selfdrive.car import dbc_dict, PlatformConfig, DbcDict, Platforms, CarSpecs -from openpilot.selfdrive.car.docs_definitions import CarHarness, CarDocs, CarParts -from openpilot.selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries - -Ecu = car.CarParams.Ecu - - -class CarControllerParams: - STEER_MAX = 300 # GM limit is 3Nm. Used by carcontroller to generate LKA output - STEER_STEP = 3 # Active control frames per command (~33hz) - INACTIVE_STEER_STEP = 10 # Inactive control frames per command (10hz) - STEER_DELTA_UP = 10 # Delta rates require review due to observed EPS weakness - STEER_DELTA_DOWN = 15 - STEER_DRIVER_ALLOWANCE = 65 - STEER_DRIVER_MULTIPLIER = 4 - STEER_DRIVER_FACTOR = 100 - NEAR_STOP_BRAKE_PHASE = 0.5 # m/s - - # Heartbeat for dash "Service Adaptive Cruise" and "Service Front Camera" - ADAS_KEEPALIVE_STEP = 100 - CAMERA_KEEPALIVE_STEP = 100 - - # Allow small margin below -3.5 m/s^2 from ISO 15622:2018 since we - # perform the closed loop control, and might need some - # to apply some more braking if we're on a downhill slope. - # Our controller should still keep the 2 second average above - # -3.5 m/s^2 as per planner limits - ACCEL_MAX = 2. # m/s^2 - ACCEL_MIN = -4. # m/s^2 - - def __init__(self, CP): - # Gas/brake lookups - self.ZERO_GAS = 2048 # Coasting - self.MAX_BRAKE = 400 # ~ -4.0 m/s^2 with regen - - if CP.carFingerprint in CAMERA_ACC_CAR: - self.MAX_GAS = 3400 - self.MAX_ACC_REGEN = 1514 - self.INACTIVE_REGEN = 1554 - # Camera ACC vehicles have no regen while enabled. - # Camera transitions to MAX_ACC_REGEN from ZERO_GAS and uses friction brakes instantly - max_regen_acceleration = 0. - - else: - self.MAX_GAS = 3072 # Safety limit, not ACC max. Stock ACC >4096 from standstill. - self.MAX_ACC_REGEN = 1404 # Max ACC regen is slightly less than max paddle regen - self.INACTIVE_REGEN = 1404 - # ICE has much less engine braking force compared to regen in EVs, - # lower threshold removes some braking deadzone - max_regen_acceleration = -1. if CP.carFingerprint in EV_CAR else -0.1 - - self.GAS_LOOKUP_BP = [max_regen_acceleration, 0., self.ACCEL_MAX] - self.GAS_LOOKUP_V = [self.MAX_ACC_REGEN, self.ZERO_GAS, self.MAX_GAS] - - self.BRAKE_LOOKUP_BP = [self.ACCEL_MIN, max_regen_acceleration] - self.BRAKE_LOOKUP_V = [self.MAX_BRAKE, 0.] - - -@dataclass -class GMCarDocs(CarDocs): - package: str = "Adaptive Cruise Control (ACC)" - - def init_make(self, CP: car.CarParams): - if CP.networkLocation == car.CarParams.NetworkLocation.fwdCamera: - self.car_parts = CarParts.common([CarHarness.gm]) - else: - self.car_parts = CarParts.common([CarHarness.obd_ii]) - - -@dataclass(frozen=True, kw_only=True) -class GMCarSpecs(CarSpecs): - tireStiffnessFactor: float = 0.444 # not optimized yet - - -@dataclass -class GMPlatformConfig(PlatformConfig): - dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict('gm_global_a_powertrain_generated', 'gm_global_a_object', chassis_dbc='gm_global_a_chassis')) - - -@dataclass -class GMASCMPlatformConfig(GMPlatformConfig): - def init(self): - # ASCM is supported, but due to a janky install and hardware configuration, we are not showing in the car docs - self.car_docs = [] - - -class CAR(Platforms): - HOLDEN_ASTRA = GMASCMPlatformConfig( - [GMCarDocs("Holden Astra 2017")], - GMCarSpecs(mass=1363, wheelbase=2.662, steerRatio=15.7, centerToFrontRatio=0.4), - ) - CHEVROLET_VOLT = GMASCMPlatformConfig( - [GMCarDocs("Chevrolet Volt 2017-18", min_enable_speed=0, video_link="https://youtu.be/QeMCN_4TFfQ")], - GMCarSpecs(mass=1607, wheelbase=2.69, steerRatio=17.7, centerToFrontRatio=0.45, tireStiffnessFactor=0.469), - ) - CADILLAC_ATS = GMASCMPlatformConfig( - [GMCarDocs("Cadillac ATS Premium Performance 2018")], - GMCarSpecs(mass=1601, wheelbase=2.78, steerRatio=15.3), - ) - CHEVROLET_MALIBU = GMASCMPlatformConfig( - [GMCarDocs("Chevrolet Malibu Premier 2017")], - GMCarSpecs(mass=1496, wheelbase=2.83, steerRatio=15.8, centerToFrontRatio=0.4), - ) - GMC_ACADIA = GMASCMPlatformConfig( - [GMCarDocs("GMC Acadia 2018", video_link="https://www.youtube.com/watch?v=0ZN6DdsBUZo")], - GMCarSpecs(mass=1975, wheelbase=2.86, steerRatio=14.4, centerToFrontRatio=0.4), - ) - BUICK_LACROSSE = GMASCMPlatformConfig( - [GMCarDocs("Buick LaCrosse 2017-19", "Driver Confidence Package 2")], - GMCarSpecs(mass=1712, wheelbase=2.91, steerRatio=15.8, centerToFrontRatio=0.4), - ) - BUICK_REGAL = GMASCMPlatformConfig( - [GMCarDocs("Buick Regal Essence 2018")], - GMCarSpecs(mass=1714, wheelbase=2.83, steerRatio=14.4, centerToFrontRatio=0.4), - ) - CADILLAC_ESCALADE = GMASCMPlatformConfig( - [GMCarDocs("Cadillac Escalade 2017", "Driver Assist Package")], - GMCarSpecs(mass=2564, wheelbase=2.95, steerRatio=17.3), - ) - CADILLAC_ESCALADE_ESV = GMASCMPlatformConfig( - [GMCarDocs("Cadillac Escalade ESV 2016", "Adaptive Cruise Control (ACC) & LKAS")], - GMCarSpecs(mass=2739, wheelbase=3.302, steerRatio=17.3, tireStiffnessFactor=1.0), - ) - CADILLAC_ESCALADE_ESV_2019 = GMASCMPlatformConfig( - [GMCarDocs("Cadillac Escalade ESV 2019", "Adaptive Cruise Control (ACC) & LKAS")], - CADILLAC_ESCALADE_ESV.specs, - ) - CHEVROLET_BOLT_EUV = GMPlatformConfig( - [ - GMCarDocs("Chevrolet Bolt EUV 2022-23", "Premier or Premier Redline Trim without Super Cruise Package", video_link="https://youtu.be/xvwzGMUA210"), - GMCarDocs("Chevrolet Bolt EV 2022-23", "2LT Trim with Adaptive Cruise Control Package"), - ], - GMCarSpecs(mass=1669, wheelbase=2.63779, steerRatio=16.8, centerToFrontRatio=0.4, tireStiffnessFactor=1.0), - ) - CHEVROLET_SILVERADO = GMPlatformConfig( - [ - GMCarDocs("Chevrolet Silverado 1500 2020-21", "Safety Package II"), - GMCarDocs("GMC Sierra 1500 2020-21", "Driver Alert Package II", video_link="https://youtu.be/5HbNoBLzRwE"), - ], - GMCarSpecs(mass=2450, wheelbase=3.75, steerRatio=16.3, tireStiffnessFactor=1.0), - ) - CHEVROLET_EQUINOX = GMPlatformConfig( - [GMCarDocs("Chevrolet Equinox 2019-22")], - GMCarSpecs(mass=1588, wheelbase=2.72, steerRatio=14.4, centerToFrontRatio=0.4), - ) - CHEVROLET_TRAILBLAZER = GMPlatformConfig( - [GMCarDocs("Chevrolet Trailblazer 2021-22")], - GMCarSpecs(mass=1345, wheelbase=2.64, steerRatio=16.8, centerToFrontRatio=0.4, tireStiffnessFactor=1.0), - ) - - -class CruiseButtons: - INIT = 0 - UNPRESS = 1 - RES_ACCEL = 2 - DECEL_SET = 3 - MAIN = 5 - CANCEL = 6 - -class AccState: - OFF = 0 - ACTIVE = 1 - FAULTED = 3 - STANDSTILL = 4 - -class CanBus: - POWERTRAIN = 0 - OBSTACLE = 1 - CAMERA = 2 - CHASSIS = 2 - LOOPBACK = 128 - DROPPED = 192 - - -# In a Data Module, an identifier is a string used to recognize an object, -# either by itself or together with the identifiers of parent objects. -# Each returns a 4 byte hex representation of the decimal part number. `b"\x02\x8c\xf0'"` -> 42790951 -GM_BOOT_SOFTWARE_PART_NUMER_REQUEST = b'\x1a\xc0' # likely does not contain anything useful -GM_SOFTWARE_MODULE_1_REQUEST = b'\x1a\xc1' -GM_SOFTWARE_MODULE_2_REQUEST = b'\x1a\xc2' -GM_SOFTWARE_MODULE_3_REQUEST = b'\x1a\xc3' - -# Part number of XML data file that is used to configure ECU -GM_XML_DATA_FILE_PART_NUMBER = b'\x1a\x9c' -GM_XML_CONFIG_COMPAT_ID = b'\x1a\x9b' # used to know if XML file is compatible with the ECU software/hardware - -# This DID is for identifying the part number that reflects the mix of hardware, -# software, and calibrations in the ECU when it first arrives at the vehicle assembly plant. -# If there's an Alpha Code, it's associated with this part number and stored in the DID $DB. -GM_END_MODEL_PART_NUMBER_REQUEST = b'\x1a\xcb' -GM_END_MODEL_PART_NUMBER_ALPHA_CODE_REQUEST = b'\x1a\xdb' -GM_BASE_MODEL_PART_NUMBER_REQUEST = b'\x1a\xcc' -GM_BASE_MODEL_PART_NUMBER_ALPHA_CODE_REQUEST = b'\x1a\xdc' -GM_FW_RESPONSE = b'\x5a' - -GM_FW_REQUESTS = [ - GM_BOOT_SOFTWARE_PART_NUMER_REQUEST, - GM_SOFTWARE_MODULE_1_REQUEST, - GM_SOFTWARE_MODULE_2_REQUEST, - GM_SOFTWARE_MODULE_3_REQUEST, - GM_XML_DATA_FILE_PART_NUMBER, - GM_XML_CONFIG_COMPAT_ID, - GM_END_MODEL_PART_NUMBER_REQUEST, - GM_END_MODEL_PART_NUMBER_ALPHA_CODE_REQUEST, - GM_BASE_MODEL_PART_NUMBER_REQUEST, - GM_BASE_MODEL_PART_NUMBER_ALPHA_CODE_REQUEST, -] - -GM_RX_OFFSET = 0x400 - -FW_QUERY_CONFIG = FwQueryConfig( - requests=[request for req in GM_FW_REQUESTS for request in [ - Request( - [StdQueries.SHORT_TESTER_PRESENT_REQUEST, req], - [StdQueries.SHORT_TESTER_PRESENT_RESPONSE, GM_FW_RESPONSE + bytes([req[-1]])], - rx_offset=GM_RX_OFFSET, - bus=0, - logging=True, - ), - ]], - extra_ecus=[(Ecu.fwdCamera, 0x24b, None)], -) - -EV_CAR = {CAR.CHEVROLET_VOLT, CAR.CHEVROLET_BOLT_EUV} - -# We're integrated at the camera with VOACC on these cars (instead of ASCM w/ OBD-II harness) -CAMERA_ACC_CAR = {CAR.CHEVROLET_BOLT_EUV, CAR.CHEVROLET_SILVERADO, CAR.CHEVROLET_EQUINOX, CAR.CHEVROLET_TRAILBLAZER} - -STEER_THRESHOLD = 1.0 - -DBC = CAR.create_dbc_map() diff --git a/car/honda/__init__.py b/car/honda/__init__.py deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/car/honda/carcontroller.py b/car/honda/carcontroller.py deleted file mode 100644 index fe023ea17d..0000000000 --- a/car/honda/carcontroller.py +++ /dev/null @@ -1,256 +0,0 @@ -from collections import namedtuple - -from cereal import car -from openpilot.common.numpy_fast import clip, interp -from openpilot.common.realtime import DT_CTRL -from opendbc.can.packer import CANPacker -from openpilot.selfdrive.car.honda import hondacan -from openpilot.selfdrive.car.honda.values import CruiseButtons, VISUAL_HUD, HONDA_BOSCH, HONDA_BOSCH_RADARLESS, HONDA_NIDEC_ALT_PCM_ACCEL, CarControllerParams -from openpilot.selfdrive.car.interfaces import CarControllerBase -from openpilot.selfdrive.controls.lib.drive_helpers import rate_limit - -VisualAlert = car.CarControl.HUDControl.VisualAlert -LongCtrlState = car.CarControl.Actuators.LongControlState - - -def compute_gb_honda_bosch(accel, speed): - # TODO returns 0s, is unused - return 0.0, 0.0 - - -def compute_gb_honda_nidec(accel, speed): - creep_brake = 0.0 - creep_speed = 2.3 - creep_brake_value = 0.15 - if speed < creep_speed: - creep_brake = (creep_speed - speed) / creep_speed * creep_brake_value - gb = float(accel) / 4.8 - creep_brake - return clip(gb, 0.0, 1.0), clip(-gb, 0.0, 1.0) - - -def compute_gas_brake(accel, speed, fingerprint): - if fingerprint in HONDA_BOSCH: - return compute_gb_honda_bosch(accel, speed) - else: - return compute_gb_honda_nidec(accel, speed) - - -# TODO not clear this does anything useful -def actuator_hysteresis(brake, braking, brake_steady, v_ego, car_fingerprint): - # hyst params - brake_hyst_on = 0.02 # to activate brakes exceed this value - brake_hyst_off = 0.005 # to deactivate brakes below this value - brake_hyst_gap = 0.01 # don't change brake command for small oscillations within this value - - # *** hysteresis logic to avoid brake blinking. go above 0.1 to trigger - if (brake < brake_hyst_on and not braking) or brake < brake_hyst_off: - brake = 0. - braking = brake > 0. - - # for small brake oscillations within brake_hyst_gap, don't change the brake command - if brake == 0.: - brake_steady = 0. - elif brake > brake_steady + brake_hyst_gap: - brake_steady = brake - brake_hyst_gap - elif brake < brake_steady - brake_hyst_gap: - brake_steady = brake + brake_hyst_gap - brake = brake_steady - - return brake, braking, brake_steady - - -def brake_pump_hysteresis(apply_brake, apply_brake_last, last_pump_ts, ts): - pump_on = False - - # reset pump timer if: - # - there is an increment in brake request - # - we are applying steady state brakes and we haven't been running the pump - # for more than 20s (to prevent pressure bleeding) - if apply_brake > apply_brake_last or (ts - last_pump_ts > 20. and apply_brake > 0): - last_pump_ts = ts - - # once the pump is on, run it for at least 0.2s - if ts - last_pump_ts < 0.2 and apply_brake > 0: - pump_on = True - - return pump_on, last_pump_ts - - -def process_hud_alert(hud_alert): - # initialize to no alert - fcw_display = 0 - steer_required = 0 - acc_alert = 0 - - # priority is: FCW, steer required, all others - if hud_alert == VisualAlert.fcw: - fcw_display = VISUAL_HUD[hud_alert.raw] - elif hud_alert in (VisualAlert.steerRequired, VisualAlert.ldw): - steer_required = VISUAL_HUD[hud_alert.raw] - else: - acc_alert = VISUAL_HUD[hud_alert.raw] - - return fcw_display, steer_required, acc_alert - - -HUDData = namedtuple("HUDData", - ["pcm_accel", "v_cruise", "lead_visible", - "lanes_visible", "fcw", "acc_alert", "steer_required", "lead_distance_bars"]) - - -def rate_limit_steer(new_steer, last_steer): - # TODO just hardcoded ramp to min/max in 0.33s for all Honda - MAX_DELTA = 3 * DT_CTRL - return clip(new_steer, last_steer - MAX_DELTA, last_steer + MAX_DELTA) - - -class CarController(CarControllerBase): - def __init__(self, dbc_name, CP, VM): - self.CP = CP - self.packer = CANPacker(dbc_name) - self.params = CarControllerParams(CP) - self.CAN = hondacan.CanBus(CP) - self.frame = 0 - - self.braking = False - self.brake_steady = 0. - self.brake_last = 0. - self.apply_brake_last = 0 - self.last_pump_ts = 0. - self.stopping_counter = 0 - - self.accel = 0.0 - self.speed = 0.0 - self.gas = 0.0 - self.brake = 0.0 - self.last_steer = 0.0 - - def update(self, CC, CS, now_nanos): - actuators = CC.actuators - hud_control = CC.hudControl - conversion = hondacan.get_cruise_speed_conversion(self.CP.carFingerprint, CS.is_metric) - hud_v_cruise = hud_control.setSpeed / conversion if hud_control.speedVisible else 255 - pcm_cancel_cmd = CC.cruiseControl.cancel - - if CC.longActive: - accel = actuators.accel - gas, brake = compute_gas_brake(actuators.accel, CS.out.vEgo, self.CP.carFingerprint) - else: - accel = 0.0 - gas, brake = 0.0, 0.0 - - # *** rate limit steer *** - limited_steer = rate_limit_steer(actuators.steer, self.last_steer) - self.last_steer = limited_steer - - # *** apply brake hysteresis *** - pre_limit_brake, self.braking, self.brake_steady = actuator_hysteresis(brake, self.braking, self.brake_steady, - CS.out.vEgo, self.CP.carFingerprint) - - # *** rate limit after the enable check *** - self.brake_last = rate_limit(pre_limit_brake, self.brake_last, -2., DT_CTRL) - - # vehicle hud display, wait for one update from 10Hz 0x304 msg - fcw_display, steer_required, acc_alert = process_hud_alert(hud_control.visualAlert) - - # **** process the car messages **** - - # steer torque is converted back to CAN reference (positive when steering right) - apply_steer = int(interp(-limited_steer * self.params.STEER_MAX, - self.params.STEER_LOOKUP_BP, self.params.STEER_LOOKUP_V)) - - # Send CAN commands - can_sends = [] - - # tester present - w/ no response (keeps radar disabled) - if self.CP.carFingerprint in (HONDA_BOSCH - HONDA_BOSCH_RADARLESS) and self.CP.openpilotLongitudinalControl: - if self.frame % 10 == 0: - can_sends.append((0x18DAB0F1, 0, b"\x02\x3E\x80\x00\x00\x00\x00\x00", 1)) - - # Send steering command. - can_sends.append(hondacan.create_steering_control(self.packer, self.CAN, apply_steer, CC.latActive, self.CP.carFingerprint, - CS.CP.openpilotLongitudinalControl)) - - # wind brake from air resistance decel at high speed - wind_brake = interp(CS.out.vEgo, [0.0, 2.3, 35.0], [0.001, 0.002, 0.15]) - # all of this is only relevant for HONDA NIDEC - max_accel = interp(CS.out.vEgo, self.params.NIDEC_MAX_ACCEL_BP, self.params.NIDEC_MAX_ACCEL_V) - # TODO this 1.44 is just to maintain previous behavior - pcm_speed_BP = [-wind_brake, - -wind_brake * (3 / 4), - 0.0, - 0.5] - # The Honda ODYSSEY seems to have different PCM_ACCEL - # msgs, is it other cars too? - if not CC.longActive: - pcm_speed = 0.0 - pcm_accel = int(0.0) - elif self.CP.carFingerprint in HONDA_NIDEC_ALT_PCM_ACCEL: - pcm_speed_V = [0.0, - clip(CS.out.vEgo - 3.0, 0.0, 100.0), - clip(CS.out.vEgo + 0.0, 0.0, 100.0), - clip(CS.out.vEgo + 5.0, 0.0, 100.0)] - pcm_speed = interp(gas - brake, pcm_speed_BP, pcm_speed_V) - pcm_accel = int(1.0 * self.params.NIDEC_GAS_MAX) - else: - pcm_speed_V = [0.0, - clip(CS.out.vEgo - 2.0, 0.0, 100.0), - clip(CS.out.vEgo + 2.0, 0.0, 100.0), - clip(CS.out.vEgo + 5.0, 0.0, 100.0)] - pcm_speed = interp(gas - brake, pcm_speed_BP, pcm_speed_V) - pcm_accel = int(clip((accel / 1.44) / max_accel, 0.0, 1.0) * self.params.NIDEC_GAS_MAX) - - if not self.CP.openpilotLongitudinalControl: - if self.frame % 2 == 0 and self.CP.carFingerprint not in HONDA_BOSCH_RADARLESS: # radarless cars don't have supplemental message - can_sends.append(hondacan.create_bosch_supplemental_1(self.packer, self.CAN, self.CP.carFingerprint)) - # If using stock ACC, spam cancel command to kill gas when OP disengages. - if pcm_cancel_cmd: - can_sends.append(hondacan.spam_buttons_command(self.packer, self.CAN, CruiseButtons.CANCEL, self.CP.carFingerprint)) - elif CC.cruiseControl.resume: - can_sends.append(hondacan.spam_buttons_command(self.packer, self.CAN, CruiseButtons.RES_ACCEL, self.CP.carFingerprint)) - - else: - # Send gas and brake commands. - if self.frame % 2 == 0: - ts = self.frame * DT_CTRL - - if self.CP.carFingerprint in HONDA_BOSCH: - self.accel = clip(accel, self.params.BOSCH_ACCEL_MIN, self.params.BOSCH_ACCEL_MAX) - self.gas = interp(accel, self.params.BOSCH_GAS_LOOKUP_BP, self.params.BOSCH_GAS_LOOKUP_V) - - stopping = actuators.longControlState == LongCtrlState.stopping - self.stopping_counter = self.stopping_counter + 1 if stopping else 0 - can_sends.extend(hondacan.create_acc_commands(self.packer, self.CAN, CC.enabled, CC.longActive, self.accel, self.gas, - self.stopping_counter, self.CP.carFingerprint)) - else: - apply_brake = clip(self.brake_last - wind_brake, 0.0, 1.0) - apply_brake = int(clip(apply_brake * self.params.NIDEC_BRAKE_MAX, 0, self.params.NIDEC_BRAKE_MAX - 1)) - pump_on, self.last_pump_ts = brake_pump_hysteresis(apply_brake, self.apply_brake_last, self.last_pump_ts, ts) - - pcm_override = True - can_sends.append(hondacan.create_brake_command(self.packer, self.CAN, apply_brake, pump_on, - pcm_override, pcm_cancel_cmd, fcw_display, - self.CP.carFingerprint, CS.stock_brake)) - self.apply_brake_last = apply_brake - self.brake = apply_brake / self.params.NIDEC_BRAKE_MAX - - # Send dashboard UI commands. - if self.frame % 10 == 0: - hud = HUDData(int(pcm_accel), int(round(hud_v_cruise)), hud_control.leadVisible, - hud_control.lanesVisible, fcw_display, acc_alert, steer_required, hud_control.leadDistanceBars) - can_sends.extend(hondacan.create_ui_commands(self.packer, self.CAN, self.CP, CC.enabled, pcm_speed, hud, CS.is_metric, CS.acc_hud, CS.lkas_hud)) - - if self.CP.openpilotLongitudinalControl and self.CP.carFingerprint not in HONDA_BOSCH: - self.speed = pcm_speed - self.gas = pcm_accel / self.params.NIDEC_GAS_MAX - - new_actuators = actuators.as_builder() - new_actuators.speed = self.speed - new_actuators.accel = self.accel - new_actuators.gas = self.gas - new_actuators.brake = self.brake - new_actuators.steer = self.last_steer - new_actuators.steerOutputCan = apply_steer - - self.frame += 1 - return new_actuators, can_sends diff --git a/car/honda/carstate.py b/car/honda/carstate.py deleted file mode 100644 index c98d1a72d3..0000000000 --- a/car/honda/carstate.py +++ /dev/null @@ -1,297 +0,0 @@ -from collections import defaultdict - -from cereal import car -from openpilot.common.conversions import Conversions as CV -from openpilot.common.numpy_fast import interp -from opendbc.can.can_define import CANDefine -from opendbc.can.parser import CANParser -from openpilot.selfdrive.car.honda.hondacan import CanBus, get_cruise_speed_conversion -from openpilot.selfdrive.car.honda.values import CAR, DBC, STEER_THRESHOLD, HONDA_BOSCH, \ - HONDA_NIDEC_ALT_SCM_MESSAGES, HONDA_BOSCH_RADARLESS, \ - HondaFlags -from openpilot.selfdrive.car.interfaces import CarStateBase - -TransmissionType = car.CarParams.TransmissionType - - -def get_can_messages(CP, gearbox_msg): - messages = [ - ("ENGINE_DATA", 100), - ("WHEEL_SPEEDS", 50), - ("STEERING_SENSORS", 100), - ("SEATBELT_STATUS", 10), - ("CRUISE", 10), - ("POWERTRAIN_DATA", 100), - ("CAR_SPEED", 10), - ("VSA_STATUS", 50), - ("STEER_STATUS", 100), - ("STEER_MOTOR_TORQUE", 0), # TODO: not on every car - ] - - if CP.carFingerprint == CAR.HONDA_ODYSSEY_CHN: - messages += [ - ("SCM_FEEDBACK", 25), - ("SCM_BUTTONS", 50), - ] - else: - messages += [ - ("SCM_FEEDBACK", 10), - ("SCM_BUTTONS", 25), - ] - - if CP.carFingerprint in (CAR.HONDA_CRV_HYBRID, CAR.HONDA_CIVIC_BOSCH_DIESEL, CAR.ACURA_RDX_3G, CAR.HONDA_E): - messages.append((gearbox_msg, 50)) - else: - messages.append((gearbox_msg, 100)) - - if CP.flags & HondaFlags.BOSCH_ALT_BRAKE: - messages.append(("BRAKE_MODULE", 50)) - - if CP.carFingerprint in (HONDA_BOSCH | {CAR.HONDA_CIVIC, CAR.HONDA_ODYSSEY, CAR.HONDA_ODYSSEY_CHN}): - messages.append(("EPB_STATUS", 50)) - - if CP.carFingerprint in HONDA_BOSCH: - # these messages are on camera bus on radarless cars - if not CP.openpilotLongitudinalControl and CP.carFingerprint not in HONDA_BOSCH_RADARLESS: - messages += [ - ("ACC_HUD", 10), - ("ACC_CONTROL", 50), - ] - else: # Nidec signals - if CP.carFingerprint == CAR.HONDA_ODYSSEY_CHN: - messages.append(("CRUISE_PARAMS", 10)) - else: - messages.append(("CRUISE_PARAMS", 50)) - - # TODO: clean this up - if CP.carFingerprint in (CAR.HONDA_ACCORD, CAR.HONDA_CIVIC_BOSCH, CAR.HONDA_CIVIC_BOSCH_DIESEL, CAR.HONDA_CRV_HYBRID, CAR.HONDA_INSIGHT, - CAR.ACURA_RDX_3G, CAR.HONDA_E, CAR.HONDA_CIVIC_2022, CAR.HONDA_HRV_3G): - pass - elif CP.carFingerprint in (CAR.HONDA_ODYSSEY_CHN, CAR.HONDA_FREED, CAR.HONDA_HRV): - pass - else: - messages.append(("DOORS_STATUS", 3)) - - if CP.carFingerprint in HONDA_BOSCH_RADARLESS: - messages.append(("CRUISE_FAULT_STATUS", 50)) - elif CP.openpilotLongitudinalControl: - messages.append(("STANDSTILL", 50)) - - return messages - - -class CarState(CarStateBase): - def __init__(self, CP): - super().__init__(CP) - can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) - self.gearbox_msg = "GEARBOX" - if CP.carFingerprint == CAR.HONDA_ACCORD and CP.transmissionType == TransmissionType.cvt: - self.gearbox_msg = "GEARBOX_15T" - - self.main_on_sig_msg = "SCM_FEEDBACK" - if CP.carFingerprint in HONDA_NIDEC_ALT_SCM_MESSAGES: - self.main_on_sig_msg = "SCM_BUTTONS" - - self.shifter_values = can_define.dv[self.gearbox_msg]["GEAR_SHIFTER"] - self.steer_status_values = defaultdict(lambda: "UNKNOWN", can_define.dv["STEER_STATUS"]["STEER_STATUS"]) - - self.brake_switch_prev = False - self.brake_switch_active = False - self.cruise_setting = 0 - self.v_cruise_pcm_prev = 0 - - # When available we use cp.vl["CAR_SPEED"]["ROUGH_CAR_SPEED_2"] to populate vEgoCluster - # However, on cars without a digital speedometer this is not always present (HRV, FIT, CRV 2016, ILX and RDX) - self.dash_speed_seen = False - - def update(self, cp, cp_cam, cp_body): - ret = car.CarState.new_message() - - # car params - v_weight_v = [0., 1.] # don't trust smooth speed at low values to avoid premature zero snapping - v_weight_bp = [1., 6.] # smooth blending, below ~0.6m/s the smooth speed snaps to zero - - # update prevs, update must run once per loop - self.prev_cruise_buttons = self.cruise_buttons - self.prev_cruise_setting = self.cruise_setting - self.cruise_setting = cp.vl["SCM_BUTTONS"]["CRUISE_SETTING"] - self.cruise_buttons = cp.vl["SCM_BUTTONS"]["CRUISE_BUTTONS"] - - # used for car hud message - self.is_metric = not cp.vl["CAR_SPEED"]["IMPERIAL_UNIT"] - - # ******************* parse out can ******************* - # STANDSTILL->WHEELS_MOVING bit can be noisy around zero, so use XMISSION_SPEED - # panda checks if the signal is non-zero - ret.standstill = cp.vl["ENGINE_DATA"]["XMISSION_SPEED"] < 1e-5 - # TODO: find a common signal across all cars - if self.CP.carFingerprint in (CAR.HONDA_ACCORD, CAR.HONDA_CIVIC_BOSCH, CAR.HONDA_CIVIC_BOSCH_DIESEL, CAR.HONDA_CRV_HYBRID, CAR.HONDA_INSIGHT, - CAR.ACURA_RDX_3G, CAR.HONDA_E, CAR.HONDA_CIVIC_2022, CAR.HONDA_HRV_3G): - ret.doorOpen = bool(cp.vl["SCM_FEEDBACK"]["DRIVERS_DOOR_OPEN"]) - elif self.CP.carFingerprint in (CAR.HONDA_ODYSSEY_CHN, CAR.HONDA_FREED, CAR.HONDA_HRV): - ret.doorOpen = bool(cp.vl["SCM_BUTTONS"]["DRIVERS_DOOR_OPEN"]) - else: - ret.doorOpen = any([cp.vl["DOORS_STATUS"]["DOOR_OPEN_FL"], cp.vl["DOORS_STATUS"]["DOOR_OPEN_FR"], - cp.vl["DOORS_STATUS"]["DOOR_OPEN_RL"], cp.vl["DOORS_STATUS"]["DOOR_OPEN_RR"]]) - ret.seatbeltUnlatched = bool(cp.vl["SEATBELT_STATUS"]["SEATBELT_DRIVER_LAMP"] or not cp.vl["SEATBELT_STATUS"]["SEATBELT_DRIVER_LATCHED"]) - - steer_status = self.steer_status_values[cp.vl["STEER_STATUS"]["STEER_STATUS"]] - ret.steerFaultPermanent = steer_status not in ("NORMAL", "NO_TORQUE_ALERT_1", "NO_TORQUE_ALERT_2", "LOW_SPEED_LOCKOUT", "TMP_FAULT") - # LOW_SPEED_LOCKOUT is not worth a warning - # NO_TORQUE_ALERT_2 can be caused by bump or steering nudge from driver - ret.steerFaultTemporary = steer_status not in ("NORMAL", "LOW_SPEED_LOCKOUT", "NO_TORQUE_ALERT_2") - - if self.CP.carFingerprint in HONDA_BOSCH_RADARLESS: - ret.accFaulted = bool(cp.vl["CRUISE_FAULT_STATUS"]["CRUISE_FAULT"]) - else: - # On some cars, these two signals are always 1, this flag is masking a bug in release - # FIXME: find and set the ACC faulted signals on more platforms - if self.CP.openpilotLongitudinalControl: - ret.accFaulted = bool(cp.vl["STANDSTILL"]["BRAKE_ERROR_1"] or cp.vl["STANDSTILL"]["BRAKE_ERROR_2"]) - - # Log non-critical stock ACC/LKAS faults if Nidec (camera) - if self.CP.carFingerprint not in HONDA_BOSCH: - ret.carFaultedNonCritical = bool(cp_cam.vl["ACC_HUD"]["ACC_PROBLEM"] or cp_cam.vl["LKAS_HUD"]["LKAS_PROBLEM"]) - - ret.espDisabled = cp.vl["VSA_STATUS"]["ESP_DISABLED"] != 0 - - ret.wheelSpeeds = self.get_wheel_speeds( - cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_FL"], - cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_FR"], - cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_RL"], - cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_RR"], - ) - v_wheel = (ret.wheelSpeeds.fl + ret.wheelSpeeds.fr + ret.wheelSpeeds.rl + ret.wheelSpeeds.rr) / 4.0 - - # blend in transmission speed at low speed, since it has more low speed accuracy - v_weight = interp(v_wheel, v_weight_bp, v_weight_v) - ret.vEgoRaw = (1. - v_weight) * cp.vl["ENGINE_DATA"]["XMISSION_SPEED"] * CV.KPH_TO_MS * self.CP.wheelSpeedFactor + v_weight * v_wheel - ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) - - self.dash_speed_seen = self.dash_speed_seen or cp.vl["CAR_SPEED"]["ROUGH_CAR_SPEED_2"] > 1e-3 - if self.dash_speed_seen: - conversion = CV.KPH_TO_MS if self.is_metric else CV.MPH_TO_MS - ret.vEgoCluster = cp.vl["CAR_SPEED"]["ROUGH_CAR_SPEED_2"] * conversion - - ret.steeringAngleDeg = cp.vl["STEERING_SENSORS"]["STEER_ANGLE"] - ret.steeringRateDeg = cp.vl["STEERING_SENSORS"]["STEER_ANGLE_RATE"] - - ret.leftBlinker, ret.rightBlinker = self.update_blinker_from_stalk( - 250, cp.vl["SCM_FEEDBACK"]["LEFT_BLINKER"], cp.vl["SCM_FEEDBACK"]["RIGHT_BLINKER"]) - ret.brakeHoldActive = cp.vl["VSA_STATUS"]["BRAKE_HOLD_ACTIVE"] == 1 - - # TODO: set for all cars - if self.CP.carFingerprint in (HONDA_BOSCH | {CAR.HONDA_CIVIC, CAR.HONDA_ODYSSEY, CAR.HONDA_ODYSSEY_CHN}): - ret.parkingBrake = cp.vl["EPB_STATUS"]["EPB_STATE"] != 0 - - gear = int(cp.vl[self.gearbox_msg]["GEAR_SHIFTER"]) - ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(gear, None)) - - ret.gas = cp.vl["POWERTRAIN_DATA"]["PEDAL_GAS"] - ret.gasPressed = ret.gas > 1e-5 - - ret.steeringTorque = cp.vl["STEER_STATUS"]["STEER_TORQUE_SENSOR"] - ret.steeringTorqueEps = cp.vl["STEER_MOTOR_TORQUE"]["MOTOR_TORQUE"] - ret.steeringPressed = abs(ret.steeringTorque) > STEER_THRESHOLD.get(self.CP.carFingerprint, 1200) - - if self.CP.carFingerprint in HONDA_BOSCH: - # The PCM always manages its own cruise control state, but doesn't publish it - if self.CP.carFingerprint in HONDA_BOSCH_RADARLESS: - ret.cruiseState.nonAdaptive = cp_cam.vl["ACC_HUD"]["CRUISE_CONTROL_LABEL"] != 0 - - if not self.CP.openpilotLongitudinalControl: - # ACC_HUD is on camera bus on radarless cars - acc_hud = cp_cam.vl["ACC_HUD"] if self.CP.carFingerprint in HONDA_BOSCH_RADARLESS else cp.vl["ACC_HUD"] - ret.cruiseState.nonAdaptive = acc_hud["CRUISE_CONTROL_LABEL"] != 0 - ret.cruiseState.standstill = acc_hud["CRUISE_SPEED"] == 252. - - conversion = get_cruise_speed_conversion(self.CP.carFingerprint, self.is_metric) - # On set, cruise set speed pulses between 254~255 and the set speed prev is set to avoid this. - ret.cruiseState.speed = self.v_cruise_pcm_prev if acc_hud["CRUISE_SPEED"] > 160.0 else acc_hud["CRUISE_SPEED"] * conversion - self.v_cruise_pcm_prev = ret.cruiseState.speed - else: - ret.cruiseState.speed = cp.vl["CRUISE"]["CRUISE_SPEED_PCM"] * CV.KPH_TO_MS - - if self.CP.flags & HondaFlags.BOSCH_ALT_BRAKE: - ret.brakePressed = cp.vl["BRAKE_MODULE"]["BRAKE_PRESSED"] != 0 - else: - # brake switch has shown some single time step noise, so only considered when - # switch is on for at least 2 consecutive CAN samples - # brake switch rises earlier than brake pressed but is never 1 when in park - brake_switch_vals = cp.vl_all["POWERTRAIN_DATA"]["BRAKE_SWITCH"] - if len(brake_switch_vals): - brake_switch = cp.vl["POWERTRAIN_DATA"]["BRAKE_SWITCH"] != 0 - if len(brake_switch_vals) > 1: - self.brake_switch_prev = brake_switch_vals[-2] != 0 - self.brake_switch_active = brake_switch and self.brake_switch_prev - self.brake_switch_prev = brake_switch - ret.brakePressed = (cp.vl["POWERTRAIN_DATA"]["BRAKE_PRESSED"] != 0) or self.brake_switch_active - - ret.brake = cp.vl["VSA_STATUS"]["USER_BRAKE"] - ret.cruiseState.enabled = cp.vl["POWERTRAIN_DATA"]["ACC_STATUS"] != 0 - ret.cruiseState.available = bool(cp.vl[self.main_on_sig_msg]["MAIN_ON"]) - - # Gets rid of Pedal Grinding noise when brake is pressed at slow speeds for some models - if self.CP.carFingerprint in (CAR.HONDA_PILOT, CAR.HONDA_RIDGELINE): - if ret.brake > 0.1: - ret.brakePressed = True - - if self.CP.carFingerprint in HONDA_BOSCH: - # TODO: find the radarless AEB_STATUS bit and make sure ACCEL_COMMAND is correct to enable AEB alerts - if self.CP.carFingerprint not in HONDA_BOSCH_RADARLESS: - ret.stockAeb = (not self.CP.openpilotLongitudinalControl) and bool(cp.vl["ACC_CONTROL"]["AEB_STATUS"] and cp.vl["ACC_CONTROL"]["ACCEL_COMMAND"] < -1e-5) - else: - ret.stockAeb = bool(cp_cam.vl["BRAKE_COMMAND"]["AEB_REQ_1"] and cp_cam.vl["BRAKE_COMMAND"]["COMPUTER_BRAKE"] > 1e-5) - - self.acc_hud = False - self.lkas_hud = False - if self.CP.carFingerprint not in HONDA_BOSCH: - ret.stockFcw = cp_cam.vl["BRAKE_COMMAND"]["FCW"] != 0 - self.acc_hud = cp_cam.vl["ACC_HUD"] - self.stock_brake = cp_cam.vl["BRAKE_COMMAND"] - if self.CP.carFingerprint in HONDA_BOSCH_RADARLESS: - self.lkas_hud = cp_cam.vl["LKAS_HUD"] - - if self.CP.enableBsm: - # BSM messages are on B-CAN, requires a panda forwarding B-CAN messages to CAN 0 - # more info here: https://github.com/commaai/openpilot/pull/1867 - ret.leftBlindspot = cp_body.vl["BSM_STATUS_LEFT"]["BSM_ALERT"] == 1 - ret.rightBlindspot = cp_body.vl["BSM_STATUS_RIGHT"]["BSM_ALERT"] == 1 - - return ret - - def get_can_parser(self, CP): - messages = get_can_messages(CP, self.gearbox_msg) - return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus(CP).pt) - - @staticmethod - def get_cam_can_parser(CP): - messages = [ - ("STEERING_CONTROL", 100), - ] - - if CP.carFingerprint in HONDA_BOSCH_RADARLESS: - messages += [ - ("ACC_HUD", 10), - ("LKAS_HUD", 10), - ] - - elif CP.carFingerprint not in HONDA_BOSCH: - messages += [ - ("ACC_HUD", 10), - ("LKAS_HUD", 10), - ("BRAKE_COMMAND", 50), - ] - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus(CP).camera) - - @staticmethod - def get_body_can_parser(CP): - if CP.enableBsm: - messages = [ - ("BSM_STATUS_LEFT", 3), - ("BSM_STATUS_RIGHT", 3), - ] - bus_body = CanBus(CP).radar # B-CAN is forwarded to ACC-CAN radar side (CAN 0 on fake ethernet port) - return CANParser(DBC[CP.carFingerprint]["body"], messages, bus_body) - return None diff --git a/car/honda/fingerprints.py b/car/honda/fingerprints.py deleted file mode 100644 index 8a5b79b41e..0000000000 --- a/car/honda/fingerprints.py +++ /dev/null @@ -1,895 +0,0 @@ -from cereal import car -from openpilot.selfdrive.car.honda.values import CAR - -Ecu = car.CarParams.Ecu - -# Modified FW can be identified by the second dash being replaced by a comma -# For example: `b'39990-TVA,A150\x00\x00'` -# -# TODO: vsa is "essential" for fpv2 but doesn't appear on some CAR.FREED models - - -FW_VERSIONS = { - CAR.HONDA_ACCORD: { - (Ecu.shiftByWire, 0x18da0bf1, None): [ - b'54008-TVC-A910\x00\x00', - b'54008-TWA-A910\x00\x00', - ], - (Ecu.transmission, 0x18da1ef1, None): [ - b'28101-6A7-A220\x00\x00', - b'28101-6A7-A230\x00\x00', - b'28101-6A7-A320\x00\x00', - b'28101-6A7-A330\x00\x00', - b'28101-6A7-A410\x00\x00', - b'28101-6A7-A510\x00\x00', - b'28101-6A7-A610\x00\x00', - b'28101-6A7-A710\x00\x00', - b'28101-6A9-H140\x00\x00', - b'28101-6A9-H420\x00\x00', - b'28102-6B8-A560\x00\x00', - b'28102-6B8-A570\x00\x00', - b'28102-6B8-A700\x00\x00', - b'28102-6B8-A800\x00\x00', - b'28102-6B8-C560\x00\x00', - b'28102-6B8-C570\x00\x00', - b'28102-6B8-M520\x00\x00', - b'28102-6B8-R700\x00\x00', - ], - (Ecu.electricBrakeBooster, 0x18da2bf1, None): [ - b'46114-TVA-A050\x00\x00', - b'46114-TVA-A060\x00\x00', - b'46114-TVA-A080\x00\x00', - b'46114-TVA-A120\x00\x00', - b'46114-TVA-A320\x00\x00', - b'46114-TVE-H550\x00\x00', - b'46114-TVE-H560\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-TVA-B040\x00\x00', - b'57114-TVA-B050\x00\x00', - b'57114-TVA-B060\x00\x00', - b'57114-TVA-B530\x00\x00', - b'57114-TVA-C040\x00\x00', - b'57114-TVA-C050\x00\x00', - b'57114-TVA-C060\x00\x00', - b'57114-TVA-C530\x00\x00', - b'57114-TVA-E520\x00\x00', - b'57114-TVE-H250\x00\x00', - b'57114-TWA-A040\x00\x00', - b'57114-TWA-A050\x00\x00', - b'57114-TWA-A530\x00\x00', - b'57114-TWA-B520\x00\x00', - b'57114-TWA-C510\x00\x00', - b'57114-TWB-H030\x00\x00', - ], - (Ecu.eps, 0x18da30f1, None): [ - b'39990-TBX-H120\x00\x00', - b'39990-TVA,A150\x00\x00', - b'39990-TVA-A140\x00\x00', - b'39990-TVA-A150\x00\x00', - b'39990-TVA-A160\x00\x00', - b'39990-TVA-A340\x00\x00', - b'39990-TVA-X030\x00\x00', - b'39990-TVA-X040\x00\x00', - b'39990-TVE-H130\x00\x00', - b'39990-TWB-H120\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-TBX-H230\x00\x00', - b'77959-TVA-A460\x00\x00', - b'77959-TVA-F330\x00\x00', - b'77959-TVA-H230\x00\x00', - b'77959-TVA-L420\x00\x00', - b'77959-TVA-X330\x00\x00', - b'77959-TWA-A440\x00\x00', - b'77959-TWA-L420\x00\x00', - b'77959-TWB-H220\x00\x00', - ], - (Ecu.hud, 0x18da61f1, None): [ - b'78209-TVA-A010\x00\x00', - b'78209-TVA-A110\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36802-TBX-H140\x00\x00', - b'36802-TVA-A150\x00\x00', - b'36802-TVA-A160\x00\x00', - b'36802-TVA-A170\x00\x00', - b'36802-TVA-A180\x00\x00', - b'36802-TVA-A330\x00\x00', - b'36802-TVC-A330\x00\x00', - b'36802-TVE-H070\x00\x00', - b'36802-TWA-A070\x00\x00', - b'36802-TWA-A080\x00\x00', - b'36802-TWA-A210\x00\x00', - b'36802-TWA-A330\x00\x00', - b'36802-TWB-H060\x00\x00', - ], - (Ecu.fwdCamera, 0x18dab5f1, None): [ - b'36161-TBX-H130\x00\x00', - b'36161-TVA-A060\x00\x00', - b'36161-TVA-A330\x00\x00', - b'36161-TVC-A330\x00\x00', - b'36161-TVE-H050\x00\x00', - b'36161-TWA-A070\x00\x00', - b'36161-TWA-A330\x00\x00', - b'36161-TWB-H040\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-TVA-A010\x00\x00', - b'38897-TVA-A020\x00\x00', - b'38897-TVA-A230\x00\x00', - b'38897-TVA-A240\x00\x00', - b'38897-TWA-A120\x00\x00', - b'38897-TWD-J020\x00\x00', - ], - }, - CAR.HONDA_CIVIC: { - (Ecu.transmission, 0x18da1ef1, None): [ - b'28101-5CG-A040\x00\x00', - b'28101-5CG-A050\x00\x00', - b'28101-5CG-A070\x00\x00', - b'28101-5CG-A080\x00\x00', - b'28101-5CG-A320\x00\x00', - b'28101-5CG-A810\x00\x00', - b'28101-5CG-A820\x00\x00', - b'28101-5DJ-A040\x00\x00', - b'28101-5DJ-A060\x00\x00', - b'28101-5DJ-A510\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-TBA-A540\x00\x00', - b'57114-TBA-A550\x00\x00', - b'57114-TBA-A560\x00\x00', - b'57114-TBA-A570\x00\x00', - b'57114-TEA-Q220\x00\x00', - ], - (Ecu.eps, 0x18da30f1, None): [ - b'39990-TBA,A030\x00\x00', - b'39990-TBA-A030\x00\x00', - b'39990-TBG-A030\x00\x00', - b'39990-TEA-T020\x00\x00', - b'39990-TEG-A010\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-TBA-A030\x00\x00', - b'77959-TBA-A040\x00\x00', - b'77959-TBG-A020\x00\x00', - b'77959-TBG-A030\x00\x00', - b'77959-TEA-Q820\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-TBA-A020\x00\x00', - b'36161-TBA-A030\x00\x00', - b'36161-TBA-A040\x00\x00', - b'36161-TBC-A020\x00\x00', - b'36161-TBC-A030\x00\x00', - b'36161-TED-Q320\x00\x00', - b'36161-TEG-A010\x00\x00', - b'36161-TEG-A020\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-TBA-A010\x00\x00', - b'38897-TBA-A020\x00\x00', - ], - }, - CAR.HONDA_CIVIC_BOSCH: { - (Ecu.transmission, 0x18da1ef1, None): [ - b'28101-5CG-A920\x00\x00', - b'28101-5CG-AB10\x00\x00', - b'28101-5CG-C110\x00\x00', - b'28101-5CG-C220\x00\x00', - b'28101-5CG-C320\x00\x00', - b'28101-5CG-G020\x00\x00', - b'28101-5CG-L020\x00\x00', - b'28101-5CK-A130\x00\x00', - b'28101-5CK-A140\x00\x00', - b'28101-5CK-A150\x00\x00', - b'28101-5CK-C130\x00\x00', - b'28101-5CK-C140\x00\x00', - b'28101-5CK-C150\x00\x00', - b'28101-5CK-G210\x00\x00', - b'28101-5CK-J710\x00\x00', - b'28101-5CK-Q610\x00\x00', - b'28101-5DJ-A610\x00\x00', - b'28101-5DJ-A710\x00\x00', - b'28101-5DV-E330\x00\x00', - b'28101-5DV-E610\x00\x00', - b'28101-5DV-E820\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-TBG-A330\x00\x00', - b'57114-TBG-A340\x00\x00', - b'57114-TBG-A350\x00\x00', - b'57114-TGG-A340\x00\x00', - b'57114-TGG-C320\x00\x00', - b'57114-TGG-G320\x00\x00', - b'57114-TGG-L320\x00\x00', - b'57114-TGG-L330\x00\x00', - b'57114-TGH-L130\x00\x00', - b'57114-TGK-T320\x00\x00', - b'57114-TGL-G330\x00\x00', - ], - (Ecu.eps, 0x18da30f1, None): [ - b'39990-TBA-C020\x00\x00', - b'39990-TBA-C120\x00\x00', - b'39990-TEA-T820\x00\x00', - b'39990-TEZ-T020\x00\x00', - b'39990-TGG,A020\x00\x00', - b'39990-TGG,A120\x00\x00', - b'39990-TGG-A020\x00\x00', - b'39990-TGG-A120\x00\x00', - b'39990-TGG-J510\x00\x00', - b'39990-TGH-J530\x00\x00', - b'39990-TGL-E130\x00\x00', - b'39990-TGN-E120\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-TBA-A060\x00\x00', - b'77959-TBG-A050\x00\x00', - b'77959-TEA-G020\x00\x00', - b'77959-TGG-A020\x00\x00', - b'77959-TGG-A030\x00\x00', - b'77959-TGG-E010\x00\x00', - b'77959-TGG-G010\x00\x00', - b'77959-TGG-G110\x00\x00', - b'77959-TGG-J320\x00\x00', - b'77959-TGG-Z820\x00\x00', - b'77959-TGH-J110\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36802-TBA-A150\x00\x00', - b'36802-TBA-A160\x00\x00', - b'36802-TFJ-G060\x00\x00', - b'36802-TGG-A050\x00\x00', - b'36802-TGG-A060\x00\x00', - b'36802-TGG-A070\x00\x00', - b'36802-TGG-A130\x00\x00', - b'36802-TGG-G040\x00\x00', - b'36802-TGG-G130\x00\x00', - b'36802-TGH-A140\x00\x00', - b'36802-TGK-Q120\x00\x00', - b'36802-TGL-G040\x00\x00', - ], - (Ecu.fwdCamera, 0x18dab5f1, None): [ - b'36161-TBA-A130\x00\x00', - b'36161-TBA-A140\x00\x00', - b'36161-TFJ-G070\x00\x00', - b'36161-TGG-A060\x00\x00', - b'36161-TGG-A080\x00\x00', - b'36161-TGG-A120\x00\x00', - b'36161-TGG-G050\x00\x00', - b'36161-TGG-G070\x00\x00', - b'36161-TGG-G130\x00\x00', - b'36161-TGG-G140\x00\x00', - b'36161-TGH-A140\x00\x00', - b'36161-TGK-Q120\x00\x00', - b'36161-TGL-G050\x00\x00', - b'36161-TGL-G070\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-TBA-A020\x00\x00', - b'38897-TBA-A110\x00\x00', - b'38897-TGH-A010\x00\x00', - ], - (Ecu.electricBrakeBooster, 0x18da2bf1, None): [ - b'39494-TGL-G030\x00\x00', - ], - }, - CAR.HONDA_CIVIC_BOSCH_DIESEL: { - (Ecu.transmission, 0x18da1ef1, None): [ - b'28101-59Y-G220\x00\x00', - b'28101-59Y-G620\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-TGN-E320\x00\x00', - ], - (Ecu.eps, 0x18da30f1, None): [ - b'39990-TFK-G020\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-TFK-G210\x00\x00', - b'77959-TGN-G220\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36802-TFK-G130\x00\x00', - b'36802-TGN-G130\x00\x00', - ], - (Ecu.shiftByWire, 0x18da0bf1, None): [ - b'54008-TGN-E010\x00\x00', - ], - (Ecu.fwdCamera, 0x18dab5f1, None): [ - b'36161-TFK-G130\x00\x00', - b'36161-TGN-G130\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-TBA-A020\x00\x00', - ], - }, - CAR.HONDA_CRV: { - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-T1W-A230\x00\x00', - b'57114-T1W-A240\x00\x00', - b'57114-TFF-A940\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-T0A-A230\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-T1W-A830\x00\x00', - b'36161-T1W-C830\x00\x00', - b'36161-T1X-A830\x00\x00', - ], - }, - CAR.HONDA_CRV_5G: { - (Ecu.transmission, 0x18da1ef1, None): [ - b'28101-5RG-A020\x00\x00', - b'28101-5RG-A030\x00\x00', - b'28101-5RG-A040\x00\x00', - b'28101-5RG-A120\x00\x00', - b'28101-5RG-A220\x00\x00', - b'28101-5RH-A020\x00\x00', - b'28101-5RH-A030\x00\x00', - b'28101-5RH-A040\x00\x00', - b'28101-5RH-A120\x00\x00', - b'28101-5RH-A220\x00\x00', - b'28101-5RL-Q010\x00\x00', - b'28101-5RM-F010\x00\x00', - b'28101-5RM-K010\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-TLA-A040\x00\x00', - b'57114-TLA-A050\x00\x00', - b'57114-TLA-A060\x00\x00', - b'57114-TLB-A830\x00\x00', - b'57114-TMC-Z040\x00\x00', - b'57114-TMC-Z050\x00\x00', - ], - (Ecu.eps, 0x18da30f1, None): [ - b'39990-TLA,A040\x00\x00', - b'39990-TLA-A040\x00\x00', - b'39990-TLA-A110\x00\x00', - b'39990-TLA-A220\x00\x00', - b'39990-TME-T030\x00\x00', - b'39990-TME-T120\x00\x00', - b'39990-TMT-T010\x00\x00', - ], - (Ecu.electricBrakeBooster, 0x18da2bf1, None): [ - b'46114-TLA-A040\x00\x00', - b'46114-TLA-A050\x00\x00', - b'46114-TLA-A930\x00\x00', - b'46114-TMC-U020\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-TLA-A010\x00\x00', - b'38897-TLA-A110\x00\x00', - b'38897-TNY-G010\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36802-TLA-A040\x00\x00', - b'36802-TLA-A050\x00\x00', - b'36802-TLA-A060\x00\x00', - b'36802-TLA-A070\x00\x00', - b'36802-TMC-Q040\x00\x00', - b'36802-TMC-Q070\x00\x00', - b'36802-TNY-A030\x00\x00', - ], - (Ecu.fwdCamera, 0x18dab5f1, None): [ - b'36161-TLA-A060\x00\x00', - b'36161-TLA-A070\x00\x00', - b'36161-TLA-A080\x00\x00', - b'36161-TMC-Q020\x00\x00', - b'36161-TMC-Q030\x00\x00', - b'36161-TMC-Q040\x00\x00', - b'36161-TNY-A020\x00\x00', - b'36161-TNY-A030\x00\x00', - b'36161-TNY-A040\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-TLA-A240\x00\x00', - b'77959-TLA-A250\x00\x00', - b'77959-TLA-A320\x00\x00', - b'77959-TLA-A410\x00\x00', - b'77959-TLA-A420\x00\x00', - b'77959-TLA-Q040\x00\x00', - b'77959-TLA-Z040\x00\x00', - b'77959-TMM-F040\x00\x00', - ], - }, - CAR.HONDA_CRV_EU: { - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-T1V-G920\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-T1V-G520\x00\x00', - ], - (Ecu.shiftByWire, 0x18da0bf1, None): [ - b'54008-T1V-G010\x00\x00', - ], - (Ecu.transmission, 0x18da1ef1, None): [ - b'28101-5LH-E120\x00\x00', - b'28103-5LH-E100\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-T1G-G940\x00\x00', - ], - }, - CAR.HONDA_CRV_HYBRID: { - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-TMB-H030\x00\x00', - b'57114-TPA-G020\x00\x00', - b'57114-TPG-A020\x00\x00', - ], - (Ecu.eps, 0x18da30f1, None): [ - b'39990-TMA-H020\x00\x00', - b'39990-TPA-G030\x00\x00', - b'39990-TPG-A020\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-TMA-H110\x00\x00', - b'38897-TPG-A110\x00\x00', - b'38897-TPG-A210\x00\x00', - ], - (Ecu.shiftByWire, 0x18da0bf1, None): [ - b'54008-TMB-H510\x00\x00', - b'54008-TMB-H610\x00\x00', - ], - (Ecu.fwdCamera, 0x18dab5f1, None): [ - b'36161-TMB-H040\x00\x00', - b'36161-TPA-E050\x00\x00', - b'36161-TPG-A030\x00\x00', - b'36161-TPG-A040\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36802-TMB-H040\x00\x00', - b'36802-TPA-E040\x00\x00', - b'36802-TPG-A020\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-TLA-C320\x00\x00', - b'77959-TLA-C410\x00\x00', - b'77959-TLA-C420\x00\x00', - b'77959-TLA-G220\x00\x00', - b'77959-TLA-H240\x00\x00', - ], - }, - CAR.HONDA_FIT: { - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-T5R-L020\x00\x00', - b'57114-T5R-L220\x00\x00', - ], - (Ecu.eps, 0x18da30f1, None): [ - b'39990-T5R-C020\x00\x00', - b'39990-T5R-C030\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-T5A-J010\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-T5R-A040\x00\x00', - b'36161-T5R-A240\x00\x00', - b'36161-T5R-A520\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-T5R-A230\x00\x00', - ], - }, - CAR.HONDA_FREED: { - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-TDK-J010\x00\x00', - ], - (Ecu.eps, 0x18da30f1, None): [ - b'39990-TDK-J050\x00\x00', - b'39990-TDK-N020\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-TDK-J120\x00\x00', - b'57114-TDK-J330\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-TDK-J070\x00\x00', - b'36161-TDK-J080\x00\x00', - b'36161-TDK-J530\x00\x00', - ], - }, - CAR.HONDA_ODYSSEY: { - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-THR-A010\x00\x00', - b'38897-THR-A020\x00\x00', - ], - (Ecu.eps, 0x18da30f1, None): [ - b'39990-THR-A020\x00\x00', - b'39990-THR-A030\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-THR-A010\x00\x00', - b'77959-THR-A110\x00\x00', - b'77959-THR-X010\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-THR-A020\x00\x00', - b'36161-THR-A030\x00\x00', - b'36161-THR-A110\x00\x00', - b'36161-THR-A720\x00\x00', - b'36161-THR-A730\x00\x00', - b'36161-THR-A810\x00\x00', - b'36161-THR-A910\x00\x00', - b'36161-THR-C010\x00\x00', - b'36161-THR-D110\x00\x00', - b'36161-THR-K020\x00\x00', - ], - (Ecu.transmission, 0x18da1ef1, None): [ - b'28101-5NZ-A110\x00\x00', - b'28101-5NZ-A310\x00\x00', - b'28101-5NZ-C310\x00\x00', - b'28102-5MX-A001\x00\x00', - b'28102-5MX-A600\x00\x00', - b'28102-5MX-A610\x00\x00', - b'28102-5MX-A700\x00\x00', - b'28102-5MX-A710\x00\x00', - b'28102-5MX-A900\x00\x00', - b'28102-5MX-A910\x00\x00', - b'28102-5MX-C001\x00\x00', - b'28102-5MX-C910\x00\x00', - b'28102-5MX-D001\x00\x00', - b'28102-5MX-D710\x00\x00', - b'28102-5MX-K610\x00\x00', - b'28103-5NZ-A100\x00\x00', - b'28103-5NZ-A300\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-THR-A040\x00\x00', - b'57114-THR-A110\x00\x00', - ], - (Ecu.shiftByWire, 0x18da0bf1, None): [ - b'54008-THR-A020\x00\x00', - ], - }, - CAR.HONDA_ODYSSEY_CHN: { - (Ecu.eps, 0x18da30f1, None): [ - b'39990-T6D-H220\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-T6A-J010\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-T6A-P040\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-T6A-P110\x00\x00', - ], - }, - CAR.HONDA_PILOT: { - (Ecu.shiftByWire, 0x18da0bf1, None): [ - b'54008-TG7-A520\x00\x00', - b'54008-TG7-A530\x00\x00', - ], - (Ecu.transmission, 0x18da1ef1, None): [ - b'28101-5EY-A040\x00\x00', - b'28101-5EY-A050\x00\x00', - b'28101-5EY-A100\x00\x00', - b'28101-5EY-A430\x00\x00', - b'28101-5EY-A500\x00\x00', - b'28101-5EZ-A050\x00\x00', - b'28101-5EZ-A060\x00\x00', - b'28101-5EZ-A100\x00\x00', - b'28101-5EZ-A210\x00\x00', - b'28101-5EZ-A330\x00\x00', - b'28101-5EZ-A430\x00\x00', - b'28101-5EZ-A500\x00\x00', - b'28101-5EZ-A600\x00\x00', - b'28101-5EZ-A700\x00\x00', - b'28103-5EY-A110\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-TG7-A030\x00\x00', - b'38897-TG7-A040\x00\x00', - b'38897-TG7-A110\x00\x00', - b'38897-TG7-A210\x00\x00', - ], - (Ecu.eps, 0x18da30f1, None): [ - b'39990-TG7-A030\x00\x00', - b'39990-TG7-A040\x00\x00', - b'39990-TG7-A060\x00\x00', - b'39990-TG7-A070\x00\x00', - b'39990-TGS-A230\x00\x00', - b'39990-TGS-A320\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-TG7-A310\x00\x00', - b'36161-TG7-A520\x00\x00', - b'36161-TG7-A630\x00\x00', - b'36161-TG7-A720\x00\x00', - b'36161-TG7-A820\x00\x00', - b'36161-TG7-A930\x00\x00', - b'36161-TG7-C520\x00\x00', - b'36161-TG7-D520\x00\x00', - b'36161-TG7-D630\x00\x00', - b'36161-TG7-Y630\x00\x00', - b'36161-TG8-A410\x00\x00', - b'36161-TG8-A520\x00\x00', - b'36161-TG8-A630\x00\x00', - b'36161-TG8-A720\x00\x00', - b'36161-TG8-A830\x00\x00', - b'36161-TGS-A030\x00\x00', - b'36161-TGS-A130\x00\x00', - b'36161-TGS-A220\x00\x00', - b'36161-TGS-A320\x00\x00', - b'36161-TGT-A030\x00\x00', - b'36161-TGT-A130\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-TG7-A020\x00\x00', - b'77959-TG7-A110\x00\x00', - b'77959-TG7-A210\x00\x00', - b'77959-TG7-Y210\x00\x00', - b'77959-TGS-A010\x00\x00', - b'77959-TGS-A110\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-TG7-A130\x00\x00', - b'57114-TG7-A140\x00\x00', - b'57114-TG7-A230\x00\x00', - b'57114-TG7-A240\x00\x00', - b'57114-TG7-A630\x00\x00', - b'57114-TG7-A730\x00\x00', - b'57114-TG8-A140\x00\x00', - b'57114-TG8-A230\x00\x00', - b'57114-TG8-A240\x00\x00', - b'57114-TG8-A630\x00\x00', - b'57114-TG8-A730\x00\x00', - b'57114-TGS-A530\x00\x00', - b'57114-TGT-A530\x00\x00', - ], - }, - CAR.ACURA_RDX: { - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-TX4-A220\x00\x00', - b'57114-TX5-A220\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-TX4-A030\x00\x00', - b'36161-TX5-A030\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-TX4-B010\x00\x00', - b'77959-TX4-C010\x00\x00', - b'77959-TX4-C020\x00\x00', - ], - }, - CAR.ACURA_RDX_3G: { - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-TJB-A030\x00\x00', - b'57114-TJB-A040\x00\x00', - b'57114-TJB-A120\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36802-TJB-A040\x00\x00', - b'36802-TJB-A050\x00\x00', - b'36802-TJB-A540\x00\x00', - ], - (Ecu.fwdCamera, 0x18dab5f1, None): [ - b'36161-TJB-A040\x00\x00', - b'36161-TJB-A530\x00\x00', - ], - (Ecu.shiftByWire, 0x18da0bf1, None): [ - b'54008-TJB-A520\x00\x00', - b'54008-TJB-A530\x00\x00', - ], - (Ecu.transmission, 0x18da1ef1, None): [ - b'28102-5YK-A610\x00\x00', - b'28102-5YK-A620\x00\x00', - b'28102-5YK-A630\x00\x00', - b'28102-5YK-A700\x00\x00', - b'28102-5YK-A711\x00\x00', - b'28102-5YK-A800\x00\x00', - b'28102-5YL-A620\x00\x00', - b'28102-5YL-A700\x00\x00', - b'28102-5YL-A711\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-TJB-A040\x00\x00', - b'77959-TJB-A120\x00\x00', - b'77959-TJB-A210\x00\x00', - ], - (Ecu.electricBrakeBooster, 0x18da2bf1, None): [ - b'46114-TJB-A040\x00\x00', - b'46114-TJB-A050\x00\x00', - b'46114-TJB-A060\x00\x00', - b'46114-TJB-A120\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-TJB-A040\x00\x00', - b'38897-TJB-A110\x00\x00', - b'38897-TJB-A120\x00\x00', - b'38897-TJB-A220\x00\x00', - ], - (Ecu.eps, 0x18da30f1, None): [ - b'39990-TJB-A030\x00\x00', - b'39990-TJB-A040\x00\x00', - b'39990-TJB-A070\x00\x00', - b'39990-TJB-A130\x00\x00', - ], - }, - CAR.HONDA_RIDGELINE: { - (Ecu.eps, 0x18da30f1, None): [ - b'39990-T6Z-A020\x00\x00', - b'39990-T6Z-A030\x00\x00', - b'39990-T6Z-A050\x00\x00', - b'39990-T6Z-A110\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-T6Z-A020\x00\x00', - b'36161-T6Z-A310\x00\x00', - b'36161-T6Z-A420\x00\x00', - b'36161-T6Z-A520\x00\x00', - b'36161-T6Z-A620\x00\x00', - b'36161-T6Z-A720\x00\x00', - b'36161-TJZ-A120\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-T6Z-A010\x00\x00', - b'38897-T6Z-A110\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-T6Z-A020\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-T6Z-A120\x00\x00', - b'57114-T6Z-A130\x00\x00', - b'57114-T6Z-A520\x00\x00', - b'57114-T6Z-A610\x00\x00', - b'57114-TJZ-A520\x00\x00', - ], - }, - CAR.HONDA_INSIGHT: { - (Ecu.eps, 0x18da30f1, None): [ - b'39990-TXM-A040\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36802-TXM-A070\x00\x00', - b'36802-TXM-A080\x00\x00', - ], - (Ecu.fwdCamera, 0x18dab5f1, None): [ - b'36161-TXM-A050\x00\x00', - b'36161-TXM-A060\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-TXM-A230\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-TXM-A030\x00\x00', - b'57114-TXM-A040\x00\x00', - ], - (Ecu.shiftByWire, 0x18da0bf1, None): [ - b'54008-TWA-A910\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-TXM-A020\x00\x00', - ], - }, - CAR.HONDA_HRV: { - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-T7A-A010\x00\x00', - b'38897-T7A-A110\x00\x00', - ], - (Ecu.eps, 0x18da30f1, None): [ - b'39990-THX-A020\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-T7A-A040\x00\x00', - b'36161-T7A-A140\x00\x00', - b'36161-T7A-A240\x00\x00', - b'36161-T7A-C440\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-T7A-A230\x00\x00', - ], - }, - CAR.HONDA_HRV_3G: { - (Ecu.eps, 0x18da30f1, None): [ - b'39990-3M0-G110\x00\x00', - b'39990-3W0-A030\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-3M0-M110\x00\x00', - b'38897-3W1-A010\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-3M0-K840\x00\x00', - b'77959-3V0-A820\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'8S102-3M6-P030\x00\x00', - b'8S102-3W0-A060\x00\x00', - b'8S102-3W0-AB10\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-3M6-M010\x00\x00', - b'57114-3W0-A040\x00\x00', - ], - (Ecu.transmission, 0x18da1ef1, None): [ - b'28101-6EH-A010\x00\x00', - b'28101-6JC-M310\x00\x00', - ], - (Ecu.electricBrakeBooster, 0x18da2bf1, None): [ - b'46114-3W0-A020\x00\x00', - ], - }, - CAR.ACURA_ILX: { - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-TX6-A010\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-TV9-A140\x00\x00', - b'36161-TX6-A030\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-TX6-A230\x00\x00', - b'77959-TX6-C210\x00\x00', - ], - }, - CAR.HONDA_E: { - (Ecu.eps, 0x18da30f1, None): [ - b'39990-TYF-N030\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-TYF-E140\x00\x00', - ], - (Ecu.shiftByWire, 0x18da0bf1, None): [ - b'54008-TYF-E010\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-TYF-G430\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36802-TYF-E030\x00\x00', - ], - (Ecu.fwdCamera, 0x18dab5f1, None): [ - b'36161-TYF-E020\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-TYF-E030\x00\x00', - ], - }, - CAR.HONDA_CIVIC_2022: { - (Ecu.eps, 0x18da30f1, None): [ - b'39990-T24-T120\x00\x00', - b'39990-T39-A130\x00\x00', - b'39990-T43-J020\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-T20-A020\x00\x00', - b'38897-T20-A210\x00\x00', - b'38897-T20-A310\x00\x00', - b'38897-T20-A510\x00\x00', - b'38897-T21-A010\x00\x00', - b'38897-T24-Z120\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-T20-A970\x00\x00', - b'77959-T20-A980\x00\x00', - b'77959-T20-M820\x00\x00', - b'77959-T47-A940\x00\x00', - b'77959-T47-A950\x00\x00', - ], - (Ecu.fwdRadar, 0x18dab0f1, None): [ - b'36161-T20-A060\x00\x00', - b'36161-T20-A070\x00\x00', - b'36161-T20-A080\x00\x00', - b'36161-T24-T070\x00\x00', - b'36161-T47-A070\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-T20-AB40\x00\x00', - b'57114-T24-TB30\x00\x00', - b'57114-T43-JB30\x00\x00', - ], - (Ecu.transmission, 0x18da1ef1, None): [ - b'28101-65D-A020\x00\x00', - b'28101-65D-A120\x00\x00', - b'28101-65H-A020\x00\x00', - b'28101-65H-A120\x00\x00', - b'28101-65J-N010\x00\x00', - ], - }, -} diff --git a/car/honda/hondacan.py b/car/honda/hondacan.py deleted file mode 100644 index 1be496d951..0000000000 --- a/car/honda/hondacan.py +++ /dev/null @@ -1,211 +0,0 @@ -from openpilot.common.conversions import Conversions as CV -from openpilot.selfdrive.car import CanBusBase -from openpilot.selfdrive.car.honda.values import HondaFlags, HONDA_BOSCH, HONDA_BOSCH_RADARLESS, CAR, CarControllerParams - -# CAN bus layout with relay -# 0 = ACC-CAN - radar side -# 1 = F-CAN B - powertrain -# 2 = ACC-CAN - camera side -# 3 = F-CAN A - OBDII port - - -class CanBus(CanBusBase): - def __init__(self, CP=None, fingerprint=None) -> None: - # use fingerprint if specified - super().__init__(CP if fingerprint is None else None, fingerprint) - - if CP.carFingerprint in (HONDA_BOSCH - HONDA_BOSCH_RADARLESS): - self._pt, self._radar = self.offset + 1, self.offset - else: - self._pt, self._radar = self.offset, self.offset + 1 - - @property - def pt(self) -> int: - return self._pt - - @property - def radar(self) -> int: - return self._radar - - @property - def camera(self) -> int: - return self.offset + 2 - - -def get_lkas_cmd_bus(CAN, car_fingerprint, radar_disabled=False): - no_radar = car_fingerprint in HONDA_BOSCH_RADARLESS - if radar_disabled or no_radar: - # when radar is disabled, steering commands are sent directly to powertrain bus - return CAN.pt - # normally steering commands are sent to radar, which forwards them to powertrain bus - return 0 - - -def get_cruise_speed_conversion(car_fingerprint: str, is_metric: bool) -> float: - # on certain cars, CRUISE_SPEED changes to imperial with car's unit setting - return CV.MPH_TO_MS if car_fingerprint in HONDA_BOSCH_RADARLESS and not is_metric else CV.KPH_TO_MS - - -def create_brake_command(packer, CAN, apply_brake, pump_on, pcm_override, pcm_cancel_cmd, fcw, car_fingerprint, stock_brake): - # TODO: do we loose pressure if we keep pump off for long? - brakelights = apply_brake > 0 - brake_rq = apply_brake > 0 - pcm_fault_cmd = False - - values = { - "COMPUTER_BRAKE": apply_brake, - "BRAKE_PUMP_REQUEST": pump_on, - "CRUISE_OVERRIDE": pcm_override, - "CRUISE_FAULT_CMD": pcm_fault_cmd, - "CRUISE_CANCEL_CMD": pcm_cancel_cmd, - "COMPUTER_BRAKE_REQUEST": brake_rq, - "SET_ME_1": 1, - "BRAKE_LIGHTS": brakelights, - "CHIME": stock_brake["CHIME"] if fcw else 0, # send the chime for stock fcw - "FCW": fcw << 1, # TODO: Why are there two bits for fcw? - "AEB_REQ_1": 0, - "AEB_REQ_2": 0, - "AEB_STATUS": 0, - } - return packer.make_can_msg("BRAKE_COMMAND", CAN.pt, values) - - -def create_acc_commands(packer, CAN, enabled, active, accel, gas, stopping_counter, car_fingerprint): - commands = [] - min_gas_accel = CarControllerParams.BOSCH_GAS_LOOKUP_BP[0] - - control_on = 5 if enabled else 0 - gas_command = gas if active and accel > min_gas_accel else -30000 - accel_command = accel if active else 0 - braking = 1 if active and accel < min_gas_accel else 0 - standstill = 1 if active and stopping_counter > 0 else 0 - standstill_release = 1 if active and stopping_counter == 0 else 0 - - # common ACC_CONTROL values - acc_control_values = { - 'ACCEL_COMMAND': accel_command, - 'STANDSTILL': standstill, - } - - if car_fingerprint in HONDA_BOSCH_RADARLESS: - acc_control_values.update({ - "CONTROL_ON": enabled, - "IDLESTOP_ALLOW": stopping_counter > 200, # allow idle stop after 4 seconds (50 Hz) - }) - else: - acc_control_values.update({ - # setting CONTROL_ON causes car to set POWERTRAIN_DATA->ACC_STATUS = 1 - "CONTROL_ON": control_on, - "GAS_COMMAND": gas_command, # used for gas - "BRAKE_LIGHTS": braking, - "BRAKE_REQUEST": braking, - "STANDSTILL_RELEASE": standstill_release, - }) - acc_control_on_values = { - "SET_TO_3": 0x03, - "CONTROL_ON": enabled, - "SET_TO_FF": 0xff, - "SET_TO_75": 0x75, - "SET_TO_30": 0x30, - } - commands.append(packer.make_can_msg("ACC_CONTROL_ON", CAN.pt, acc_control_on_values)) - - commands.append(packer.make_can_msg("ACC_CONTROL", CAN.pt, acc_control_values)) - return commands - - -def create_steering_control(packer, CAN, apply_steer, lkas_active, car_fingerprint, radar_disabled): - values = { - "STEER_TORQUE": apply_steer if lkas_active else 0, - "STEER_TORQUE_REQUEST": lkas_active, - } - bus = get_lkas_cmd_bus(CAN, car_fingerprint, radar_disabled) - return packer.make_can_msg("STEERING_CONTROL", bus, values) - - -def create_bosch_supplemental_1(packer, CAN, car_fingerprint): - # non-active params - values = { - "SET_ME_X04": 0x04, - "SET_ME_X80": 0x80, - "SET_ME_X10": 0x10, - } - bus = get_lkas_cmd_bus(CAN, car_fingerprint) - return packer.make_can_msg("BOSCH_SUPPLEMENTAL_1", bus, values) - - -def create_ui_commands(packer, CAN, CP, enabled, pcm_speed, hud, is_metric, acc_hud, lkas_hud): - commands = [] - radar_disabled = CP.carFingerprint in (HONDA_BOSCH - HONDA_BOSCH_RADARLESS) and CP.openpilotLongitudinalControl - bus_lkas = get_lkas_cmd_bus(CAN, CP.carFingerprint, radar_disabled) - - if CP.openpilotLongitudinalControl: - acc_hud_values = { - 'CRUISE_SPEED': hud.v_cruise, - 'ENABLE_MINI_CAR': 1 if enabled else 0, - # only moves the lead car without ACC_ON - 'HUD_DISTANCE': (hud.lead_distance_bars + 1) % 4, # wraps to 0 at 4 bars - 'IMPERIAL_UNIT': int(not is_metric), - 'HUD_LEAD': 2 if enabled and hud.lead_visible else 1 if enabled else 0, - 'SET_ME_X01_2': 1, - } - - if CP.carFingerprint in HONDA_BOSCH: - acc_hud_values['ACC_ON'] = int(enabled) - acc_hud_values['FCM_OFF'] = 1 - acc_hud_values['FCM_OFF_2'] = 1 - else: - # Shows the distance bars, TODO: stock camera shows updates temporarily while disabled - acc_hud_values['ACC_ON'] = int(enabled) - acc_hud_values['PCM_SPEED'] = pcm_speed * CV.MS_TO_KPH - acc_hud_values['PCM_GAS'] = hud.pcm_accel - acc_hud_values['SET_ME_X01'] = 1 - acc_hud_values['FCM_OFF'] = acc_hud['FCM_OFF'] - acc_hud_values['FCM_OFF_2'] = acc_hud['FCM_OFF_2'] - acc_hud_values['FCM_PROBLEM'] = acc_hud['FCM_PROBLEM'] - acc_hud_values['ICONS'] = acc_hud['ICONS'] - commands.append(packer.make_can_msg("ACC_HUD", CAN.pt, acc_hud_values)) - - lkas_hud_values = { - 'SET_ME_X41': 0x41, - 'STEERING_REQUIRED': hud.steer_required, - 'SOLID_LANES': hud.lanes_visible, - 'BEEP': 0, - } - - if CP.carFingerprint in HONDA_BOSCH_RADARLESS: - lkas_hud_values['LANE_LINES'] = 3 - lkas_hud_values['DASHED_LANES'] = hud.lanes_visible - # car likely needs to see LKAS_PROBLEM fall within a specific time frame, so forward from camera - lkas_hud_values['LKAS_PROBLEM'] = lkas_hud['LKAS_PROBLEM'] - - if not (CP.flags & HondaFlags.BOSCH_EXT_HUD): - lkas_hud_values['SET_ME_X48'] = 0x48 - - if CP.flags & HondaFlags.BOSCH_EXT_HUD and not CP.openpilotLongitudinalControl: - commands.append(packer.make_can_msg('LKAS_HUD_A', bus_lkas, lkas_hud_values)) - commands.append(packer.make_can_msg('LKAS_HUD_B', bus_lkas, lkas_hud_values)) - else: - commands.append(packer.make_can_msg('LKAS_HUD', bus_lkas, lkas_hud_values)) - - if radar_disabled: - radar_hud_values = { - 'CMBS_OFF': 0x01, - 'SET_TO_1': 0x01, - } - commands.append(packer.make_can_msg('RADAR_HUD', CAN.pt, radar_hud_values)) - - if CP.carFingerprint == CAR.HONDA_CIVIC_BOSCH: - commands.append(packer.make_can_msg("LEGACY_BRAKE_COMMAND", CAN.pt, {})) - - return commands - - -def spam_buttons_command(packer, CAN, button_val, car_fingerprint): - values = { - 'CRUISE_BUTTONS': button_val, - 'CRUISE_SETTING': 0, - } - # send buttons to camera on radarless cars - bus = CAN.camera if car_fingerprint in HONDA_BOSCH_RADARLESS else CAN.pt - return packer.make_can_msg("SCM_BUTTONS", bus, values) diff --git a/car/honda/interface.py b/car/honda/interface.py deleted file mode 100755 index 2026c385c2..0000000000 --- a/car/honda/interface.py +++ /dev/null @@ -1,259 +0,0 @@ -#!/usr/bin/env python3 -from cereal import car -from panda import Panda -from openpilot.common.conversions import Conversions as CV -from openpilot.common.numpy_fast import interp -from openpilot.selfdrive.car.honda.hondacan import CanBus -from openpilot.selfdrive.car.honda.values import CarControllerParams, CruiseButtons, CruiseSettings, HondaFlags, CAR, HONDA_BOSCH, \ - HONDA_NIDEC_ALT_SCM_MESSAGES, HONDA_BOSCH_RADARLESS -from openpilot.selfdrive.car import create_button_events, get_safety_config -from openpilot.selfdrive.car.interfaces import CarInterfaceBase -from openpilot.selfdrive.car.disable_ecu import disable_ecu - - -ButtonType = car.CarState.ButtonEvent.Type -EventName = car.CarEvent.EventName -TransmissionType = car.CarParams.TransmissionType -BUTTONS_DICT = {CruiseButtons.RES_ACCEL: ButtonType.accelCruise, CruiseButtons.DECEL_SET: ButtonType.decelCruise, - CruiseButtons.MAIN: ButtonType.altButton3, CruiseButtons.CANCEL: ButtonType.cancel} -SETTINGS_BUTTONS_DICT = {CruiseSettings.DISTANCE: ButtonType.gapAdjustCruise, CruiseSettings.LKAS: ButtonType.altButton1} - - -class CarInterface(CarInterfaceBase): - @staticmethod - def get_pid_accel_limits(CP, current_speed, cruise_speed): - if CP.carFingerprint in HONDA_BOSCH: - return CarControllerParams.BOSCH_ACCEL_MIN, CarControllerParams.BOSCH_ACCEL_MAX - else: - # NIDECs don't allow acceleration near cruise_speed, - # so limit limits of pid to prevent windup - ACCEL_MAX_VALS = [CarControllerParams.NIDEC_ACCEL_MAX, 0.2] - ACCEL_MAX_BP = [cruise_speed - 2., cruise_speed - .2] - return CarControllerParams.NIDEC_ACCEL_MIN, interp(current_speed, ACCEL_MAX_BP, ACCEL_MAX_VALS) - - @staticmethod - def _get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs): - ret.carName = "honda" - - CAN = CanBus(ret, fingerprint) - - if candidate in HONDA_BOSCH: - ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.hondaBosch)] - ret.radarUnavailable = True - # Disable the radar and let openpilot control longitudinal - # WARNING: THIS DISABLES AEB! - # If Bosch radarless, this blocks ACC messages from the camera - ret.experimentalLongitudinalAvailable = True - ret.openpilotLongitudinalControl = experimental_long - ret.pcmCruise = not ret.openpilotLongitudinalControl - else: - ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.hondaNidec)] - ret.openpilotLongitudinalControl = True - - ret.pcmCruise = True - - if candidate == CAR.HONDA_CRV_5G: - ret.enableBsm = 0x12f8bfa7 in fingerprint[CAN.radar] - - # Detect Bosch cars with new HUD msgs - if any(0x33DA in f for f in fingerprint.values()): - ret.flags |= HondaFlags.BOSCH_EXT_HUD.value - - # Accord ICE 1.5T CVT has different gearbox message - if candidate == CAR.HONDA_ACCORD and 0x191 in fingerprint[CAN.pt]: - ret.transmissionType = TransmissionType.cvt - - # Certain Hondas have an extra steering sensor at the bottom of the steering rack, - # which improves controls quality as it removes the steering column torsion from feedback. - # Tire stiffness factor fictitiously lower if it includes the steering column torsion effect. - # For modeling details, see p.198-200 in "The Science of Vehicle Dynamics (2014), M. Guiggiani" - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0], [0]] - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] - ret.lateralTuning.pid.kf = 0.00006 # conservative feed-forward - - if candidate in HONDA_BOSCH: - ret.longitudinalTuning.kpV = [0.25] - ret.longitudinalTuning.kiV = [0.05] - ret.longitudinalActuatorDelayUpperBound = 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: - # default longitudinal tuning for all hondas - ret.longitudinalTuning.kpBP = [0., 5., 35.] - ret.longitudinalTuning.kpV = [1.2, 0.8, 0.5] - ret.longitudinalTuning.kiBP = [0., 35.] - ret.longitudinalTuning.kiV = [0.18, 0.12] - - eps_modified = False - for fw in car_fw: - if fw.ecu == "eps" and b"," in fw.fwVersion: - eps_modified = True - - if candidate == CAR.HONDA_CIVIC: - if eps_modified: - # stock request input values: 0x0000, 0x00DE, 0x014D, 0x01EF, 0x0290, 0x0377, 0x0454, 0x0610, 0x06EE - # stock request output values: 0x0000, 0x0917, 0x0DC5, 0x1017, 0x119F, 0x140B, 0x1680, 0x1680, 0x1680 - # modified request output values: 0x0000, 0x0917, 0x0DC5, 0x1017, 0x119F, 0x140B, 0x1680, 0x2880, 0x3180 - # stock filter output values: 0x009F, 0x0108, 0x0108, 0x0108, 0x0108, 0x0108, 0x0108, 0x0108, 0x0108 - # modified filter output values: 0x009F, 0x0108, 0x0108, 0x0108, 0x0108, 0x0108, 0x0108, 0x0400, 0x0480 - # note: max request allowed is 4096, but request is capped at 3840 in firmware, so modifications result in 2x max - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 2560, 8000], [0, 2560, 3840]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.3], [0.1]] - else: - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 2560], [0, 2560]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[1.1], [0.33]] - - elif candidate in (CAR.HONDA_CIVIC_BOSCH, CAR.HONDA_CIVIC_BOSCH_DIESEL, CAR.HONDA_CIVIC_2022): - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.8], [0.24]] - - elif candidate == CAR.HONDA_ACCORD: - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end - - if eps_modified: - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.3], [0.09]] - else: - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.18]] - - elif candidate == CAR.ACURA_ILX: - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 3840], [0, 3840]] # TODO: determine if there is a dead zone at the top end - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.8], [0.24]] - - elif candidate in (CAR.HONDA_CRV, CAR.HONDA_CRV_EU): - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 1000], [0, 1000]] # TODO: determine if there is a dead zone at the top end - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.8], [0.24]] - ret.wheelSpeedFactor = 1.025 - - elif candidate == CAR.HONDA_CRV_5G: - if eps_modified: - # stock request input values: 0x0000, 0x00DB, 0x01BB, 0x0296, 0x0377, 0x0454, 0x0532, 0x0610, 0x067F - # stock request output values: 0x0000, 0x0500, 0x0A15, 0x0E6D, 0x1100, 0x1200, 0x129A, 0x134D, 0x1400 - # modified request output values: 0x0000, 0x0500, 0x0A15, 0x0E6D, 0x1100, 0x1200, 0x1ACD, 0x239A, 0x2800 - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 2560, 10000], [0, 2560, 3840]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.21], [0.07]] - else: - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 3840], [0, 3840]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.64], [0.192]] - ret.wheelSpeedFactor = 1.025 - - elif candidate == CAR.HONDA_CRV_HYBRID: - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.18]] - ret.wheelSpeedFactor = 1.025 - - elif candidate == CAR.HONDA_FIT: - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2], [0.05]] - - elif candidate == CAR.HONDA_FREED: - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2], [0.05]] - - elif candidate in (CAR.HONDA_HRV, CAR.HONDA_HRV_3G): - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] - if candidate == CAR.HONDA_HRV: - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.16], [0.025]] - ret.wheelSpeedFactor = 1.025 - else: - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.8], [0.24]] # TODO: can probably use some tuning - - elif candidate == CAR.ACURA_RDX: - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 1000], [0, 1000]] # TODO: determine if there is a dead zone at the top end - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.8], [0.24]] - - elif candidate == CAR.ACURA_RDX_3G: - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 3840], [0, 3840]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2], [0.06]] - - elif candidate in (CAR.HONDA_ODYSSEY, CAR.HONDA_ODYSSEY_CHN): - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.28], [0.08]] - if candidate == CAR.HONDA_ODYSSEY_CHN: - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 32767], [0, 32767]] # TODO: determine if there is a dead zone at the top end - else: - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end - - elif candidate == CAR.HONDA_PILOT: - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.38], [0.11]] - - elif candidate == CAR.HONDA_RIDGELINE: - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.38], [0.11]] - - elif candidate == CAR.HONDA_INSIGHT: - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.18]] - - elif candidate == CAR.HONDA_E: - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.18]] # TODO: can probably use some tuning - - else: - raise ValueError(f"unsupported car {candidate}") - - # These cars use alternate user brake msg (0x1BE) - # TODO: Only detect feature for Accord/Accord Hybrid, not all Bosch DBCs have BRAKE_MODULE - if 0x1BE in fingerprint[CAN.pt] and candidate in (CAR.HONDA_ACCORD, CAR.HONDA_HRV_3G): - ret.flags |= HondaFlags.BOSCH_ALT_BRAKE.value - - if ret.flags & HondaFlags.BOSCH_ALT_BRAKE: - ret.safetyConfigs[0].safetyParam |= Panda.FLAG_HONDA_ALT_BRAKE - - # These cars use alternate SCM messages (SCM_FEEDBACK AND SCM_BUTTON) - if candidate in HONDA_NIDEC_ALT_SCM_MESSAGES: - ret.safetyConfigs[0].safetyParam |= Panda.FLAG_HONDA_NIDEC_ALT - - if ret.openpilotLongitudinalControl and candidate in HONDA_BOSCH: - ret.safetyConfigs[0].safetyParam |= Panda.FLAG_HONDA_BOSCH_LONG - - if candidate in HONDA_BOSCH_RADARLESS: - ret.safetyConfigs[0].safetyParam |= Panda.FLAG_HONDA_RADARLESS - - # min speed to enable ACC. if car can do stop and go, then set enabling speed - # to a negative value, so it won't matter. Otherwise, add 0.5 mph margin to not - # conflict with PCM acc - ret.autoResumeSng = candidate in (HONDA_BOSCH | {CAR.HONDA_CIVIC}) - ret.minEnableSpeed = -1. if ret.autoResumeSng else 25.5 * CV.MPH_TO_MS - - ret.steerActuatorDelay = 0.1 - ret.steerLimitTimer = 0.8 - - return ret - - @staticmethod - def init(CP, logcan, sendcan): - if CP.carFingerprint in (HONDA_BOSCH - HONDA_BOSCH_RADARLESS) and CP.openpilotLongitudinalControl: - disable_ecu(logcan, sendcan, bus=1, addr=0x18DAB0F1, com_cont_req=b'\x28\x83\x03') - - # returns a car.CarState - def _update(self, c): - ret = self.CS.update(self.cp, self.cp_cam, self.cp_body) - - ret.buttonEvents = [ - *create_button_events(self.CS.cruise_buttons, self.CS.prev_cruise_buttons, BUTTONS_DICT), - *create_button_events(self.CS.cruise_setting, self.CS.prev_cruise_setting, SETTINGS_BUTTONS_DICT), - ] - - # events - events = self.create_common_events(ret, pcm_enable=False) - if self.CP.pcmCruise and ret.vEgo < self.CP.minEnableSpeed: - events.add(EventName.belowEngageSpeed) - - if self.CP.pcmCruise: - # we engage when pcm is active (rising edge) - if ret.cruiseState.enabled and not self.CS.out.cruiseState.enabled: - events.add(EventName.pcmEnable) - elif not ret.cruiseState.enabled and (c.actuators.accel >= 0. or not self.CP.openpilotLongitudinalControl): - # it can happen that car cruise disables while comma system is enabled: need to - # keep braking if needed or if the speed is very low - if ret.vEgo < self.CP.minEnableSpeed + 2.: - # non loud alert if cruise disables below 25mph as expected (+ a little margin) - events.add(EventName.speedTooLow) - else: - events.add(EventName.cruiseDisabled) - if self.CS.CP.minEnableSpeed > 0 and ret.vEgo < 0.001: - events.add(EventName.manualRestart) - - ret.events = events.to_msg() - - return ret diff --git a/car/honda/radar_interface.py b/car/honda/radar_interface.py deleted file mode 100755 index 8090f8e03e..0000000000 --- a/car/honda/radar_interface.py +++ /dev/null @@ -1,84 +0,0 @@ -#!/usr/bin/env python3 -from cereal import car -from opendbc.can.parser import CANParser -from openpilot.selfdrive.car.interfaces import RadarInterfaceBase -from openpilot.selfdrive.car.honda.values import DBC - - -def _create_nidec_can_parser(car_fingerprint): - radar_messages = [0x400] + list(range(0x430, 0x43A)) + list(range(0x440, 0x446)) - messages = [(m, 20) for m in radar_messages] - return CANParser(DBC[car_fingerprint]['radar'], messages, 1) - - -class RadarInterface(RadarInterfaceBase): - def __init__(self, CP): - super().__init__(CP) - self.track_id = 0 - self.radar_fault = False - self.radar_wrong_config = False - self.radar_off_can = CP.radarUnavailable - self.radar_ts = CP.radarTimeStep - - self.delay = int(round(0.1 / CP.radarTimeStep)) # 0.1s delay of radar - - # Nidec - if self.radar_off_can: - self.rcp = None - else: - self.rcp = _create_nidec_can_parser(CP.carFingerprint) - self.trigger_msg = 0x445 - self.updated_messages = set() - - def update(self, can_strings): - # in Bosch radar and we are only steering for now, so sleep 0.05s to keep - # radard at 20Hz and return no points - if self.radar_off_can: - return super().update(None) - - vls = self.rcp.update_strings(can_strings) - self.updated_messages.update(vls) - - if self.trigger_msg not in self.updated_messages: - return None - - rr = self._update(self.updated_messages) - self.updated_messages.clear() - return rr - - def _update(self, updated_messages): - ret = car.RadarData.new_message() - - for ii in sorted(updated_messages): - cpt = self.rcp.vl[ii] - if ii == 0x400: - # check for radar faults - self.radar_fault = cpt['RADAR_STATE'] != 0x79 - self.radar_wrong_config = cpt['RADAR_STATE'] == 0x69 - elif cpt['LONG_DIST'] < 255: - if ii not in self.pts or cpt['NEW_TRACK']: - self.pts[ii] = car.RadarData.RadarPoint.new_message() - self.pts[ii].trackId = self.track_id - self.track_id += 1 - self.pts[ii].dRel = cpt['LONG_DIST'] # from front of car - self.pts[ii].yRel = -cpt['LAT_DIST'] # in car frame's y axis, left is positive - self.pts[ii].vRel = cpt['REL_SPEED'] - self.pts[ii].aRel = float('nan') - self.pts[ii].yvRel = float('nan') - self.pts[ii].measured = True - else: - if ii in self.pts: - del self.pts[ii] - - errors = [] - if not self.rcp.can_valid: - errors.append("canError") - if self.radar_fault: - errors.append("fault") - if self.radar_wrong_config: - errors.append("wrongConfig") - ret.errors = errors - - ret.points = list(self.pts.values()) - - return ret diff --git a/car/honda/tests/__init__.py b/car/honda/tests/__init__.py deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/car/honda/tests/test_honda.py b/car/honda/tests/test_honda.py deleted file mode 100644 index b8ad7872b2..0000000000 --- a/car/honda/tests/test_honda.py +++ /dev/null @@ -1,14 +0,0 @@ -import re - -from openpilot.selfdrive.car.honda.fingerprints import FW_VERSIONS - -HONDA_FW_VERSION_RE = br"[A-Z0-9]{5}-[A-Z0-9]{3}(-|,)[A-Z0-9]{4}(\x00){2}$" - - -class TestHondaFingerprint: - def test_fw_version_format(self): - # Asserts all FW versions follow an expected format - for fw_by_ecu in FW_VERSIONS.values(): - for fws in fw_by_ecu.values(): - for fw in fws: - assert re.match(HONDA_FW_VERSION_RE, fw) is not None, fw diff --git a/car/honda/values.py b/car/honda/values.py deleted file mode 100644 index c3005c667c..0000000000 --- a/car/honda/values.py +++ /dev/null @@ -1,331 +0,0 @@ -from dataclasses import dataclass -from enum import Enum, IntFlag - -from cereal import car -from openpilot.common.conversions import Conversions as CV -from panda.python import uds -from openpilot.selfdrive.car import CarSpecs, PlatformConfig, Platforms, dbc_dict -from openpilot.selfdrive.car.docs_definitions import CarFootnote, CarHarness, CarDocs, CarParts, Column -from openpilot.selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries, p16 - -Ecu = car.CarParams.Ecu -VisualAlert = car.CarControl.HUDControl.VisualAlert - - -class CarControllerParams: - # Allow small margin below -3.5 m/s^2 from ISO 15622:2018 since we - # perform the closed loop control, and might need some - # to apply some more braking if we're on a downhill slope. - # Our controller should still keep the 2 second average above - # -3.5 m/s^2 as per planner limits - NIDEC_ACCEL_MIN = -4.0 # m/s^2 - NIDEC_ACCEL_MAX = 1.6 # m/s^2, lower than 2.0 m/s^2 for tuning reasons - - NIDEC_ACCEL_LOOKUP_BP = [-1., 0., .6] - NIDEC_ACCEL_LOOKUP_V = [-4.8, 0., 2.0] - - NIDEC_MAX_ACCEL_V = [0.5, 2.4, 1.4, 0.6] - NIDEC_MAX_ACCEL_BP = [0.0, 4.0, 10., 20.] - - NIDEC_GAS_MAX = 198 # 0xc6 - NIDEC_BRAKE_MAX = 1024 // 4 - - BOSCH_ACCEL_MIN = -3.5 # m/s^2 - BOSCH_ACCEL_MAX = 2.0 # m/s^2 - - BOSCH_GAS_LOOKUP_BP = [-0.2, 2.0] # 2m/s^2 - BOSCH_GAS_LOOKUP_V = [0, 1600] - - def __init__(self, CP): - self.STEER_MAX = CP.lateralParams.torqueBP[-1] - # mirror of list (assuming first item is zero) for interp of signed request values - assert(CP.lateralParams.torqueBP[0] == 0) - assert(CP.lateralParams.torqueBP[0] == 0) - self.STEER_LOOKUP_BP = [v * -1 for v in CP.lateralParams.torqueBP][1:][::-1] + list(CP.lateralParams.torqueBP) - self.STEER_LOOKUP_V = [v * -1 for v in CP.lateralParams.torqueV][1:][::-1] + list(CP.lateralParams.torqueV) - - -class HondaFlags(IntFlag): - # Detected flags - # Bosch models with alternate set of LKAS_HUD messages - BOSCH_EXT_HUD = 1 - BOSCH_ALT_BRAKE = 2 - - # Static flags - BOSCH = 4 - BOSCH_RADARLESS = 8 - - NIDEC = 16 - NIDEC_ALT_PCM_ACCEL = 32 - NIDEC_ALT_SCM_MESSAGES = 64 - - -# Car button codes -class CruiseButtons: - RES_ACCEL = 4 - DECEL_SET = 3 - CANCEL = 2 - MAIN = 1 - - -class CruiseSettings: - DISTANCE = 3 - LKAS = 1 - - -# See dbc files for info on values -VISUAL_HUD = { - VisualAlert.none: 0, - VisualAlert.fcw: 1, - VisualAlert.steerRequired: 1, - VisualAlert.ldw: 1, - VisualAlert.brakePressed: 10, - VisualAlert.wrongGear: 6, - VisualAlert.seatbeltUnbuckled: 5, - VisualAlert.speedTooHigh: 8 -} - - -@dataclass -class HondaCarDocs(CarDocs): - package: str = "Honda Sensing" - - def init_make(self, CP: car.CarParams): - if CP.flags & HondaFlags.BOSCH: - self.car_parts = CarParts.common([CarHarness.bosch_b]) if CP.flags & HondaFlags.BOSCH_RADARLESS else CarParts.common([CarHarness.bosch_a]) - else: - self.car_parts = CarParts.common([CarHarness.nidec]) - - -class Footnote(Enum): - CIVIC_DIESEL = CarFootnote( - "2019 Honda Civic 1.6L Diesel Sedan does not have ALC below 12mph.", - Column.FSR_STEERING) - - -class HondaBoschPlatformConfig(PlatformConfig): - def init(self): - self.flags |= HondaFlags.BOSCH - - -class HondaNidecPlatformConfig(PlatformConfig): - def init(self): - self.flags |= HondaFlags.NIDEC - - -class CAR(Platforms): - # Bosch Cars - HONDA_ACCORD = HondaBoschPlatformConfig( - [ - HondaCarDocs("Honda Accord 2018-22", "All", video_link="https://www.youtube.com/watch?v=mrUwlj3Mi58", min_steer_speed=3. * CV.MPH_TO_MS), - HondaCarDocs("Honda Inspire 2018", "All", min_steer_speed=3. * CV.MPH_TO_MS), - HondaCarDocs("Honda Accord Hybrid 2018-22", "All", min_steer_speed=3. * CV.MPH_TO_MS), - ], - # steerRatio: 11.82 is spec end-to-end - CarSpecs(mass=3279 * CV.LB_TO_KG, wheelbase=2.83, steerRatio=16.33, centerToFrontRatio=0.39, tireStiffnessFactor=0.8467), - dbc_dict('honda_accord_2018_can_generated', None), - ) - HONDA_CIVIC_BOSCH = HondaBoschPlatformConfig( - [ - HondaCarDocs("Honda Civic 2019-21", "All", video_link="https://www.youtube.com/watch?v=4Iz1Mz5LGF8", - footnotes=[Footnote.CIVIC_DIESEL], min_steer_speed=2. * CV.MPH_TO_MS), - HondaCarDocs("Honda Civic Hatchback 2017-21", min_steer_speed=12. * CV.MPH_TO_MS), - ], - CarSpecs(mass=1326, wheelbase=2.7, steerRatio=15.38, centerToFrontRatio=0.4), # steerRatio: 10.93 is end-to-end spec - dbc_dict('honda_civic_hatchback_ex_2017_can_generated', None), - ) - HONDA_CIVIC_BOSCH_DIESEL = HondaBoschPlatformConfig( - [], # don't show in docs - HONDA_CIVIC_BOSCH.specs, - dbc_dict('honda_accord_2018_can_generated', None), - ) - HONDA_CIVIC_2022 = HondaBoschPlatformConfig( - [ - HondaCarDocs("Honda Civic 2022-23", "All", video_link="https://youtu.be/ytiOT5lcp6Q"), - HondaCarDocs("Honda Civic Hatchback 2022-23", "All", video_link="https://youtu.be/ytiOT5lcp6Q"), - ], - HONDA_CIVIC_BOSCH.specs, - dbc_dict('honda_civic_ex_2022_can_generated', None), - flags=HondaFlags.BOSCH_RADARLESS, - ) - HONDA_CRV_5G = HondaBoschPlatformConfig( - [HondaCarDocs("Honda CR-V 2017-22", min_steer_speed=12. * CV.MPH_TO_MS)], - # steerRatio: 12.3 is spec end-to-end - CarSpecs(mass=3410 * CV.LB_TO_KG, wheelbase=2.66, steerRatio=16.0, centerToFrontRatio=0.41, tireStiffnessFactor=0.677), - dbc_dict('honda_crv_ex_2017_can_generated', None, body_dbc='honda_crv_ex_2017_body_generated'), - flags=HondaFlags.BOSCH_ALT_BRAKE, - ) - HONDA_CRV_HYBRID = HondaBoschPlatformConfig( - [HondaCarDocs("Honda CR-V Hybrid 2017-21", min_steer_speed=12. * CV.MPH_TO_MS)], - # mass: mean of 4 models in kg, steerRatio: 12.3 is spec end-to-end - CarSpecs(mass=1667, wheelbase=2.66, steerRatio=16, centerToFrontRatio=0.41, tireStiffnessFactor=0.677), - dbc_dict('honda_accord_2018_can_generated', None), - ) - HONDA_HRV_3G = HondaBoschPlatformConfig( - [HondaCarDocs("Honda HR-V 2023", "All")], - CarSpecs(mass=3125 * CV.LB_TO_KG, wheelbase=2.61, steerRatio=15.2, centerToFrontRatio=0.41, tireStiffnessFactor=0.5), - dbc_dict('honda_civic_ex_2022_can_generated', None), - flags=HondaFlags.BOSCH_RADARLESS, - ) - ACURA_RDX_3G = HondaBoschPlatformConfig( - [HondaCarDocs("Acura RDX 2019-22", "All", min_steer_speed=3. * CV.MPH_TO_MS)], - CarSpecs(mass=4068 * CV.LB_TO_KG, wheelbase=2.75, steerRatio=11.95, centerToFrontRatio=0.41, tireStiffnessFactor=0.677), # as spec - dbc_dict('acura_rdx_2020_can_generated', None), - flags=HondaFlags.BOSCH_ALT_BRAKE, - ) - HONDA_INSIGHT = HondaBoschPlatformConfig( - [HondaCarDocs("Honda Insight 2019-22", "All", min_steer_speed=3. * CV.MPH_TO_MS)], - CarSpecs(mass=2987 * CV.LB_TO_KG, wheelbase=2.7, steerRatio=15.0, centerToFrontRatio=0.39, tireStiffnessFactor=0.82), # as spec - dbc_dict('honda_insight_ex_2019_can_generated', None), - ) - HONDA_E = HondaBoschPlatformConfig( - [HondaCarDocs("Honda e 2020", "All", min_steer_speed=3. * CV.MPH_TO_MS)], - CarSpecs(mass=3338.8 * CV.LB_TO_KG, wheelbase=2.5, centerToFrontRatio=0.5, steerRatio=16.71, tireStiffnessFactor=0.82), - dbc_dict('acura_rdx_2020_can_generated', None), - ) - - # Nidec Cars - ACURA_ILX = HondaNidecPlatformConfig( - [HondaCarDocs("Acura ILX 2016-19", "AcuraWatch Plus", min_steer_speed=25. * CV.MPH_TO_MS)], - CarSpecs(mass=3095 * CV.LB_TO_KG, wheelbase=2.67, steerRatio=18.61, centerToFrontRatio=0.37, tireStiffnessFactor=0.72), # 15.3 is spec end-to-end - dbc_dict('acura_ilx_2016_can_generated', 'acura_ilx_2016_nidec'), - flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, - ) - HONDA_CRV = HondaNidecPlatformConfig( - [HondaCarDocs("Honda CR-V 2015-16", "Touring Trim", min_steer_speed=12. * CV.MPH_TO_MS)], - CarSpecs(mass=3572 * CV.LB_TO_KG, wheelbase=2.62, steerRatio=16.89, centerToFrontRatio=0.41, tireStiffnessFactor=0.444), # as spec - dbc_dict('honda_crv_touring_2016_can_generated', 'acura_ilx_2016_nidec'), - flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, - ) - HONDA_CRV_EU = HondaNidecPlatformConfig( - [], # Euro version of CRV Touring, don't show in docs - HONDA_CRV.specs, - dbc_dict('honda_crv_executive_2016_can_generated', 'acura_ilx_2016_nidec'), - flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, - ) - HONDA_FIT = HondaNidecPlatformConfig( - [HondaCarDocs("Honda Fit 2018-20", min_steer_speed=12. * CV.MPH_TO_MS)], - CarSpecs(mass=2644 * CV.LB_TO_KG, wheelbase=2.53, steerRatio=13.06, centerToFrontRatio=0.39, tireStiffnessFactor=0.75), - dbc_dict('honda_fit_ex_2018_can_generated', 'acura_ilx_2016_nidec'), - flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, - ) - HONDA_FREED = HondaNidecPlatformConfig( - [HondaCarDocs("Honda Freed 2020", min_steer_speed=12. * CV.MPH_TO_MS)], - CarSpecs(mass=3086. * CV.LB_TO_KG, wheelbase=2.74, steerRatio=13.06, centerToFrontRatio=0.39, tireStiffnessFactor=0.75), # mostly copied from FIT - dbc_dict('honda_fit_ex_2018_can_generated', 'acura_ilx_2016_nidec'), - flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, - ) - HONDA_HRV = HondaNidecPlatformConfig( - [HondaCarDocs("Honda HR-V 2019-22", min_steer_speed=12. * CV.MPH_TO_MS)], - HONDA_HRV_3G.specs, - dbc_dict('honda_fit_ex_2018_can_generated', 'acura_ilx_2016_nidec'), - flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, - ) - HONDA_ODYSSEY = HondaNidecPlatformConfig( - [HondaCarDocs("Honda Odyssey 2018-20")], - CarSpecs(mass=1900, wheelbase=3.0, steerRatio=14.35, centerToFrontRatio=0.41, tireStiffnessFactor=0.82), - dbc_dict('honda_odyssey_exl_2018_generated', 'acura_ilx_2016_nidec'), - flags=HondaFlags.NIDEC_ALT_PCM_ACCEL, - ) - HONDA_ODYSSEY_CHN = HondaNidecPlatformConfig( - [], # Chinese version of Odyssey, don't show in docs - HONDA_ODYSSEY.specs, - dbc_dict('honda_odyssey_extreme_edition_2018_china_can_generated', 'acura_ilx_2016_nidec'), - flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, - ) - ACURA_RDX = HondaNidecPlatformConfig( - [HondaCarDocs("Acura RDX 2016-18", "AcuraWatch Plus", min_steer_speed=12. * CV.MPH_TO_MS)], - CarSpecs(mass=3925 * CV.LB_TO_KG, wheelbase=2.68, steerRatio=15.0, centerToFrontRatio=0.38, tireStiffnessFactor=0.444), # as spec - dbc_dict('acura_rdx_2018_can_generated', 'acura_ilx_2016_nidec'), - flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, - ) - HONDA_PILOT = HondaNidecPlatformConfig( - [ - HondaCarDocs("Honda Pilot 2016-22", min_steer_speed=12. * CV.MPH_TO_MS), - HondaCarDocs("Honda Passport 2019-23", "All", min_steer_speed=12. * CV.MPH_TO_MS), - ], - CarSpecs(mass=4278 * CV.LB_TO_KG, wheelbase=2.86, centerToFrontRatio=0.428, steerRatio=16.0, tireStiffnessFactor=0.444), # as spec - dbc_dict('acura_ilx_2016_can_generated', 'acura_ilx_2016_nidec'), - flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, - ) - HONDA_RIDGELINE = HondaNidecPlatformConfig( - [HondaCarDocs("Honda Ridgeline 2017-24", min_steer_speed=12. * CV.MPH_TO_MS)], - CarSpecs(mass=4515 * CV.LB_TO_KG, wheelbase=3.18, centerToFrontRatio=0.41, steerRatio=15.59, tireStiffnessFactor=0.444), # as spec - dbc_dict('acura_ilx_2016_can_generated', 'acura_ilx_2016_nidec'), - flags=HondaFlags.NIDEC_ALT_SCM_MESSAGES, - ) - HONDA_CIVIC = HondaNidecPlatformConfig( - [HondaCarDocs("Honda Civic 2016-18", min_steer_speed=12. * CV.MPH_TO_MS, video_link="https://youtu.be/-IkImTe1NYE")], - CarSpecs(mass=1326, wheelbase=2.70, centerToFrontRatio=0.4, steerRatio=15.38), # 10.93 is end-to-end spec - dbc_dict('honda_civic_touring_2016_can_generated', 'acura_ilx_2016_nidec'), - ) - - -HONDA_ALT_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ - p16(0xF112) -HONDA_ALT_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ - p16(0xF112) - -FW_QUERY_CONFIG = FwQueryConfig( - requests=[ - # Currently used to fingerprint - Request( - [StdQueries.UDS_VERSION_REQUEST], - [StdQueries.UDS_VERSION_RESPONSE], - bus=1, - ), - - # Data collection requests: - # Log manufacturer-specific identifier for current ECUs - Request( - [HONDA_ALT_VERSION_REQUEST], - [HONDA_ALT_VERSION_RESPONSE], - bus=1, - logging=True, - ), - # Nidec PT bus - Request( - [StdQueries.UDS_VERSION_REQUEST], - [StdQueries.UDS_VERSION_RESPONSE], - bus=0, - ), - # Bosch PT bus - Request( - [StdQueries.UDS_VERSION_REQUEST], - [StdQueries.UDS_VERSION_RESPONSE], - bus=1, - obd_multiplexing=False, - ), - ], - # We lose these ECUs without the comma power on these cars. - # Note that we still attempt to match with them when they are present - # This is or'd with (ALL_ECUS - ESSENTIAL_ECUS) from fw_versions.py - non_essential_ecus={ - Ecu.eps: [CAR.ACURA_RDX_3G, CAR.HONDA_ACCORD, CAR.HONDA_CIVIC_2022, CAR.HONDA_E, CAR.HONDA_HRV_3G], - Ecu.vsa: [CAR.ACURA_RDX_3G, CAR.HONDA_ACCORD, CAR.HONDA_CIVIC, CAR.HONDA_CIVIC_BOSCH, CAR.HONDA_CIVIC_2022, CAR.HONDA_CRV_5G, CAR.HONDA_CRV_HYBRID, - CAR.HONDA_E, CAR.HONDA_HRV_3G, CAR.HONDA_INSIGHT], - }, - extra_ecus=[ - (Ecu.combinationMeter, 0x18da60f1, None), - (Ecu.programmedFuelInjection, 0x18da10f1, None), - # The only other ECU on PT bus accessible by camera on radarless Civic - # This is likely a manufacturer-specific sub-address implementation: the camera responds to this and 0x18dab0f1 - # Unclear what the part number refers to: 8S103 is 'Camera Set Mono', while 36160 is 'Camera Monocular - Honda' - # TODO: add query back, camera does not support querying both in parallel and 0x18dab0f1 often fails to respond - # (Ecu.unknown, 0x18DAB3F1, None), - ], -) - -STEER_THRESHOLD = { - # default is 1200, overrides go here - CAR.ACURA_RDX: 400, - CAR.HONDA_CRV_EU: 400, -} - -HONDA_NIDEC_ALT_PCM_ACCEL = CAR.with_flags(HondaFlags.NIDEC_ALT_PCM_ACCEL) -HONDA_NIDEC_ALT_SCM_MESSAGES = CAR.with_flags(HondaFlags.NIDEC_ALT_SCM_MESSAGES) -HONDA_BOSCH = CAR.with_flags(HondaFlags.BOSCH) -HONDA_BOSCH_RADARLESS = CAR.with_flags(HondaFlags.BOSCH_RADARLESS) - - -DBC = CAR.create_dbc_map() diff --git a/car/hyundai/__init__.py b/car/hyundai/__init__.py deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/car/hyundai/carcontroller.py b/car/hyundai/carcontroller.py deleted file mode 100644 index 4038ddcca9..0000000000 --- a/car/hyundai/carcontroller.py +++ /dev/null @@ -1,208 +0,0 @@ -from cereal import car -from openpilot.common.conversions import Conversions as CV -from openpilot.common.numpy_fast import clip -from openpilot.common.realtime import DT_CTRL -from opendbc.can.packer import CANPacker -from openpilot.selfdrive.car import apply_driver_steer_torque_limits, common_fault_avoidance -from openpilot.selfdrive.car.hyundai import hyundaicanfd, hyundaican -from openpilot.selfdrive.car.hyundai.hyundaicanfd import CanBus -from openpilot.selfdrive.car.hyundai.values import HyundaiFlags, Buttons, CarControllerParams, CANFD_CAR, CAR -from openpilot.selfdrive.car.interfaces import CarControllerBase - -VisualAlert = car.CarControl.HUDControl.VisualAlert -LongCtrlState = car.CarControl.Actuators.LongControlState - -# EPS faults if you apply torque while the steering angle is above 90 degrees for more than 1 second -# All slightly below EPS thresholds to avoid fault -MAX_ANGLE = 85 -MAX_ANGLE_FRAMES = 89 -MAX_ANGLE_CONSECUTIVE_FRAMES = 2 - - -def process_hud_alert(enabled, fingerprint, hud_control): - sys_warning = (hud_control.visualAlert in (VisualAlert.steerRequired, VisualAlert.ldw)) - - # initialize to no line visible - # TODO: this is not accurate for all cars - sys_state = 1 - if hud_control.leftLaneVisible and hud_control.rightLaneVisible or sys_warning: # HUD alert only display when LKAS status is active - sys_state = 3 if enabled or sys_warning else 4 - elif hud_control.leftLaneVisible: - sys_state = 5 - elif hud_control.rightLaneVisible: - sys_state = 6 - - # initialize to no warnings - left_lane_warning = 0 - right_lane_warning = 0 - if hud_control.leftLaneDepart: - left_lane_warning = 1 if fingerprint in (CAR.GENESIS_G90, CAR.GENESIS_G80) else 2 - if hud_control.rightLaneDepart: - right_lane_warning = 1 if fingerprint in (CAR.GENESIS_G90, CAR.GENESIS_G80) else 2 - - return sys_warning, sys_state, left_lane_warning, right_lane_warning - - -class CarController(CarControllerBase): - def __init__(self, dbc_name, CP, VM): - self.CP = CP - self.CAN = CanBus(CP) - self.params = CarControllerParams(CP) - self.packer = CANPacker(dbc_name) - self.angle_limit_counter = 0 - self.frame = 0 - - self.accel_last = 0 - self.apply_steer_last = 0 - self.car_fingerprint = CP.carFingerprint - self.last_button_frame = 0 - - def update(self, CC, CS, now_nanos): - actuators = CC.actuators - hud_control = CC.hudControl - - # steering torque - new_steer = int(round(actuators.steer * self.params.STEER_MAX)) - apply_steer = apply_driver_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.params) - - # >90 degree steering fault prevention - self.angle_limit_counter, apply_steer_req = common_fault_avoidance(abs(CS.out.steeringAngleDeg) >= MAX_ANGLE, CC.latActive, - self.angle_limit_counter, MAX_ANGLE_FRAMES, - MAX_ANGLE_CONSECUTIVE_FRAMES) - - if not CC.latActive: - apply_steer = 0 - - # Hold torque with induced temporary fault when cutting the actuation bit - torque_fault = CC.latActive and not apply_steer_req - - self.apply_steer_last = apply_steer - - # accel + longitudinal - accel = clip(actuators.accel, CarControllerParams.ACCEL_MIN, CarControllerParams.ACCEL_MAX) - stopping = actuators.longControlState == LongCtrlState.stopping - set_speed_in_units = hud_control.setSpeed * (CV.MS_TO_KPH if CS.is_metric else CV.MS_TO_MPH) - - # HUD messages - sys_warning, sys_state, left_lane_warning, right_lane_warning = process_hud_alert(CC.enabled, self.car_fingerprint, - hud_control) - - can_sends = [] - - # *** common hyundai stuff *** - - # tester present - w/ no response (keeps relevant ECU disabled) - if self.frame % 100 == 0 and not (self.CP.flags & HyundaiFlags.CANFD_CAMERA_SCC.value) and self.CP.openpilotLongitudinalControl: - # for longitudinal control, either radar or ADAS driving ECU - addr, bus = 0x7d0, 0 - if self.CP.flags & HyundaiFlags.CANFD_HDA2.value: - addr, bus = 0x730, self.CAN.ECAN - can_sends.append([addr, 0, b"\x02\x3E\x80\x00\x00\x00\x00\x00", bus]) - - # for blinkers - if self.CP.flags & HyundaiFlags.ENABLE_BLINKERS: - can_sends.append([0x7b1, 0, b"\x02\x3E\x80\x00\x00\x00\x00\x00", self.CAN.ECAN]) - - # CAN-FD platforms - if self.CP.carFingerprint in CANFD_CAR: - hda2 = self.CP.flags & HyundaiFlags.CANFD_HDA2 - hda2_long = hda2 and self.CP.openpilotLongitudinalControl - - # steering control - can_sends.extend(hyundaicanfd.create_steering_messages(self.packer, self.CP, self.CAN, CC.enabled, apply_steer_req, apply_steer)) - - # prevent LFA from activating on HDA2 by sending "no lane lines detected" to ADAS ECU - if self.frame % 5 == 0 and hda2: - can_sends.append(hyundaicanfd.create_suppress_lfa(self.packer, self.CAN, CS.hda2_lfa_block_msg, - self.CP.flags & HyundaiFlags.CANFD_HDA2_ALT_STEERING)) - - # LFA and HDA icons - if self.frame % 5 == 0 and (not hda2 or hda2_long): - can_sends.append(hyundaicanfd.create_lfahda_cluster(self.packer, self.CAN, CC.enabled)) - - # blinkers - if hda2 and self.CP.flags & HyundaiFlags.ENABLE_BLINKERS: - can_sends.extend(hyundaicanfd.create_spas_messages(self.packer, self.CAN, self.frame, CC.leftBlinker, CC.rightBlinker)) - - if self.CP.openpilotLongitudinalControl: - if hda2: - can_sends.extend(hyundaicanfd.create_adrv_messages(self.packer, self.CAN, self.frame)) - if self.frame % 2 == 0: - can_sends.append(hyundaicanfd.create_acc_control(self.packer, self.CAN, CC.enabled, self.accel_last, accel, stopping, CC.cruiseControl.override, - set_speed_in_units, hud_control)) - self.accel_last = accel - else: - # button presses - can_sends.extend(self.create_button_messages(CC, CS, use_clu11=False)) - else: - can_sends.append(hyundaican.create_lkas11(self.packer, self.frame, self.CP, apply_steer, apply_steer_req, - torque_fault, CS.lkas11, sys_warning, sys_state, CC.enabled, - hud_control.leftLaneVisible, hud_control.rightLaneVisible, - left_lane_warning, right_lane_warning)) - - if not self.CP.openpilotLongitudinalControl: - can_sends.extend(self.create_button_messages(CC, CS, use_clu11=True)) - - if self.frame % 2 == 0 and self.CP.openpilotLongitudinalControl: - # TODO: unclear if this is needed - jerk = 3.0 if actuators.longControlState == LongCtrlState.pid else 1.0 - use_fca = self.CP.flags & HyundaiFlags.USE_FCA.value - can_sends.extend(hyundaican.create_acc_commands(self.packer, CC.enabled, accel, jerk, int(self.frame / 2), - hud_control, set_speed_in_units, stopping, - CC.cruiseControl.override, use_fca)) - - # 20 Hz LFA MFA message - if self.frame % 5 == 0 and self.CP.flags & HyundaiFlags.SEND_LFA.value: - can_sends.append(hyundaican.create_lfahda_mfc(self.packer, CC.enabled)) - - # 5 Hz ACC options - if self.frame % 20 == 0 and self.CP.openpilotLongitudinalControl: - can_sends.extend(hyundaican.create_acc_opt(self.packer)) - - # 2 Hz front radar options - if self.frame % 50 == 0 and self.CP.openpilotLongitudinalControl: - can_sends.append(hyundaican.create_frt_radar_opt(self.packer)) - - new_actuators = actuators.as_builder() - new_actuators.steer = apply_steer / self.params.STEER_MAX - new_actuators.steerOutputCan = apply_steer - new_actuators.accel = accel - - self.frame += 1 - return new_actuators, can_sends - - def create_button_messages(self, CC: car.CarControl, CS: car.CarState, use_clu11: bool): - can_sends = [] - if use_clu11: - if CC.cruiseControl.cancel: - can_sends.append(hyundaican.create_clu11(self.packer, self.frame, CS.clu11, Buttons.CANCEL, self.CP)) - elif CC.cruiseControl.resume: - # send resume at a max freq of 10Hz - if (self.frame - self.last_button_frame) * DT_CTRL > 0.1: - # send 25 messages at a time to increases the likelihood of resume being accepted - can_sends.extend([hyundaican.create_clu11(self.packer, self.frame, CS.clu11, Buttons.RES_ACCEL, self.CP)] * 25) - if (self.frame - self.last_button_frame) * DT_CTRL >= 0.15: - self.last_button_frame = self.frame - else: - if (self.frame - self.last_button_frame) * DT_CTRL > 0.25: - # cruise cancel - if CC.cruiseControl.cancel: - if self.CP.flags & HyundaiFlags.CANFD_ALT_BUTTONS: - can_sends.append(hyundaicanfd.create_acc_cancel(self.packer, self.CP, self.CAN, CS.cruise_info)) - self.last_button_frame = self.frame - else: - for _ in range(20): - can_sends.append(hyundaicanfd.create_buttons(self.packer, self.CP, self.CAN, CS.buttons_counter+1, Buttons.CANCEL)) - self.last_button_frame = self.frame - - # cruise standstill resume - elif CC.cruiseControl.resume: - if self.CP.flags & HyundaiFlags.CANFD_ALT_BUTTONS: - # TODO: resume for alt button cars - pass - else: - for _ in range(20): - can_sends.append(hyundaicanfd.create_buttons(self.packer, self.CP, self.CAN, CS.buttons_counter+1, Buttons.RES_ACCEL)) - self.last_button_frame = self.frame - - return can_sends diff --git a/car/hyundai/carstate.py b/car/hyundai/carstate.py deleted file mode 100644 index 92c489cf34..0000000000 --- a/car/hyundai/carstate.py +++ /dev/null @@ -1,368 +0,0 @@ -from collections import deque -import copy -import math - -from cereal import car -from openpilot.common.conversions import Conversions as CV -from opendbc.can.parser import CANParser -from opendbc.can.can_define import CANDefine -from openpilot.selfdrive.car.hyundai.hyundaicanfd import CanBus -from openpilot.selfdrive.car.hyundai.values import HyundaiFlags, CAR, DBC, CAN_GEARS, CAMERA_SCC_CAR, \ - CANFD_CAR, Buttons, CarControllerParams -from openpilot.selfdrive.car.interfaces import CarStateBase - -PREV_BUTTON_SAMPLES = 8 -CLUSTER_SAMPLE_RATE = 20 # frames -STANDSTILL_THRESHOLD = 12 * 0.03125 * CV.KPH_TO_MS - - -class CarState(CarStateBase): - def __init__(self, CP): - super().__init__(CP) - can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) - - self.cruise_buttons = deque([Buttons.NONE] * PREV_BUTTON_SAMPLES, maxlen=PREV_BUTTON_SAMPLES) - self.main_buttons = deque([Buttons.NONE] * PREV_BUTTON_SAMPLES, maxlen=PREV_BUTTON_SAMPLES) - - self.gear_msg_canfd = "GEAR_ALT" if CP.flags & HyundaiFlags.CANFD_ALT_GEARS else \ - "GEAR_ALT_2" if CP.flags & HyundaiFlags.CANFD_ALT_GEARS_2 else \ - "GEAR_SHIFTER" - if CP.carFingerprint in CANFD_CAR: - self.shifter_values = can_define.dv[self.gear_msg_canfd]["GEAR"] - elif self.CP.carFingerprint in CAN_GEARS["use_cluster_gears"]: - self.shifter_values = can_define.dv["CLU15"]["CF_Clu_Gear"] - elif self.CP.carFingerprint in CAN_GEARS["use_tcu_gears"]: - self.shifter_values = can_define.dv["TCU12"]["CUR_GR"] - else: # preferred and elect gear methods use same definition - self.shifter_values = can_define.dv["LVR12"]["CF_Lvr_Gear"] - - self.accelerator_msg_canfd = "ACCELERATOR" if CP.flags & HyundaiFlags.EV else \ - "ACCELERATOR_ALT" if CP.flags & HyundaiFlags.HYBRID else \ - "ACCELERATOR_BRAKE_ALT" - self.cruise_btns_msg_canfd = "CRUISE_BUTTONS_ALT" if CP.flags & HyundaiFlags.CANFD_ALT_BUTTONS else \ - "CRUISE_BUTTONS" - self.is_metric = False - self.buttons_counter = 0 - - self.cruise_info = {} - - # On some cars, CLU15->CF_Clu_VehicleSpeed can oscillate faster than the dash updates. Sample at 5 Hz - self.cluster_speed = 0 - self.cluster_speed_counter = CLUSTER_SAMPLE_RATE - - self.params = CarControllerParams(CP) - - def update(self, cp, cp_cam): - if self.CP.carFingerprint in CANFD_CAR: - return self.update_canfd(cp, cp_cam) - - ret = car.CarState.new_message() - cp_cruise = cp_cam if self.CP.carFingerprint in CAMERA_SCC_CAR else cp - self.is_metric = cp.vl["CLU11"]["CF_Clu_SPEED_UNIT"] == 0 - speed_conv = CV.KPH_TO_MS if self.is_metric else CV.MPH_TO_MS - - ret.doorOpen = any([cp.vl["CGW1"]["CF_Gway_DrvDrSw"], cp.vl["CGW1"]["CF_Gway_AstDrSw"], - cp.vl["CGW2"]["CF_Gway_RLDrSw"], cp.vl["CGW2"]["CF_Gway_RRDrSw"]]) - - ret.seatbeltUnlatched = cp.vl["CGW1"]["CF_Gway_DrvSeatBeltSw"] == 0 - - ret.wheelSpeeds = self.get_wheel_speeds( - cp.vl["WHL_SPD11"]["WHL_SPD_FL"], - cp.vl["WHL_SPD11"]["WHL_SPD_FR"], - cp.vl["WHL_SPD11"]["WHL_SPD_RL"], - cp.vl["WHL_SPD11"]["WHL_SPD_RR"], - ) - ret.vEgoRaw = (ret.wheelSpeeds.fl + ret.wheelSpeeds.fr + ret.wheelSpeeds.rl + ret.wheelSpeeds.rr) / 4. - ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) - ret.standstill = ret.wheelSpeeds.fl <= STANDSTILL_THRESHOLD and ret.wheelSpeeds.rr <= STANDSTILL_THRESHOLD - - self.cluster_speed_counter += 1 - if self.cluster_speed_counter > CLUSTER_SAMPLE_RATE: - self.cluster_speed = cp.vl["CLU15"]["CF_Clu_VehicleSpeed"] - self.cluster_speed_counter = 0 - - # Mimic how dash converts to imperial. - # Sorento is the only platform where CF_Clu_VehicleSpeed is already imperial when not is_metric - # TODO: CGW_USM1->CF_Gway_DrLockSoundRValue may describe this - if not self.is_metric and self.CP.carFingerprint not in (CAR.KIA_SORENTO,): - self.cluster_speed = math.floor(self.cluster_speed * CV.KPH_TO_MPH + CV.KPH_TO_MPH) - - ret.vEgoCluster = self.cluster_speed * speed_conv - - ret.steeringAngleDeg = cp.vl["SAS11"]["SAS_Angle"] - ret.steeringRateDeg = cp.vl["SAS11"]["SAS_Speed"] - ret.yawRate = cp.vl["ESP12"]["YAW_RATE"] - ret.leftBlinker, ret.rightBlinker = self.update_blinker_from_lamp( - 50, cp.vl["CGW1"]["CF_Gway_TurnSigLh"], cp.vl["CGW1"]["CF_Gway_TurnSigRh"]) - ret.steeringTorque = cp.vl["MDPS12"]["CR_Mdps_StrColTq"] - ret.steeringTorqueEps = cp.vl["MDPS12"]["CR_Mdps_OutTq"] - ret.steeringPressed = self.update_steering_pressed(abs(ret.steeringTorque) > self.params.STEER_THRESHOLD, 5) - ret.steerFaultTemporary = cp.vl["MDPS12"]["CF_Mdps_ToiUnavail"] != 0 or cp.vl["MDPS12"]["CF_Mdps_ToiFlt"] != 0 - - # cruise state - if self.CP.openpilotLongitudinalControl: - # These are not used for engage/disengage since openpilot keeps track of state using the buttons - ret.cruiseState.available = cp.vl["TCS13"]["ACCEnable"] == 0 - ret.cruiseState.enabled = cp.vl["TCS13"]["ACC_REQ"] == 1 - ret.cruiseState.standstill = False - ret.cruiseState.nonAdaptive = False - else: - ret.cruiseState.available = cp_cruise.vl["SCC11"]["MainMode_ACC"] == 1 - ret.cruiseState.enabled = cp_cruise.vl["SCC12"]["ACCMode"] != 0 - ret.cruiseState.standstill = cp_cruise.vl["SCC11"]["SCCInfoDisplay"] == 4. - ret.cruiseState.nonAdaptive = cp_cruise.vl["SCC11"]["SCCInfoDisplay"] == 2. # Shows 'Cruise Control' on dash - ret.cruiseState.speed = cp_cruise.vl["SCC11"]["VSetDis"] * speed_conv - - # TODO: Find brake pressure - ret.brake = 0 - ret.brakePressed = cp.vl["TCS13"]["DriverOverride"] == 2 # 2 includes regen braking by user on HEV/EV - ret.brakeHoldActive = cp.vl["TCS15"]["AVH_LAMP"] == 2 # 0 OFF, 1 ERROR, 2 ACTIVE, 3 READY - ret.parkingBrake = cp.vl["TCS13"]["PBRAKE_ACT"] == 1 - ret.espDisabled = cp.vl["TCS11"]["TCS_PAS"] == 1 - ret.accFaulted = cp.vl["TCS13"]["ACCEnable"] != 0 # 0 ACC CONTROL ENABLED, 1-3 ACC CONTROL DISABLED - - if self.CP.flags & (HyundaiFlags.HYBRID | HyundaiFlags.EV): - if self.CP.flags & HyundaiFlags.HYBRID: - ret.gas = cp.vl["E_EMS11"]["CR_Vcu_AccPedDep_Pos"] / 254. - else: - ret.gas = cp.vl["E_EMS11"]["Accel_Pedal_Pos"] / 254. - ret.gasPressed = ret.gas > 0 - else: - ret.gas = cp.vl["EMS12"]["PV_AV_CAN"] / 100. - ret.gasPressed = bool(cp.vl["EMS16"]["CF_Ems_AclAct"]) - - # Gear Selection via Cluster - For those Kia/Hyundai which are not fully discovered, we can use the Cluster Indicator for Gear Selection, - # as this seems to be standard over all cars, but is not the preferred method. - if self.CP.flags & (HyundaiFlags.HYBRID | HyundaiFlags.EV): - gear = cp.vl["ELECT_GEAR"]["Elect_Gear_Shifter"] - elif self.CP.carFingerprint in CAN_GEARS["use_cluster_gears"]: - gear = cp.vl["CLU15"]["CF_Clu_Gear"] - elif self.CP.carFingerprint in CAN_GEARS["use_tcu_gears"]: - gear = cp.vl["TCU12"]["CUR_GR"] - else: - gear = cp.vl["LVR12"]["CF_Lvr_Gear"] - - ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(gear)) - - if not self.CP.openpilotLongitudinalControl: - aeb_src = "FCA11" if self.CP.flags & HyundaiFlags.USE_FCA.value else "SCC12" - aeb_sig = "FCA_CmdAct" if self.CP.flags & HyundaiFlags.USE_FCA.value else "AEB_CmdAct" - aeb_warning = cp_cruise.vl[aeb_src]["CF_VSM_Warn"] != 0 - scc_warning = cp_cruise.vl["SCC12"]["TakeOverReq"] == 1 # sometimes only SCC system shows an FCW - aeb_braking = cp_cruise.vl[aeb_src]["CF_VSM_DecCmdAct"] != 0 or cp_cruise.vl[aeb_src][aeb_sig] != 0 - ret.stockFcw = (aeb_warning or scc_warning) and not aeb_braking - ret.stockAeb = aeb_warning and aeb_braking - - if self.CP.enableBsm: - ret.leftBlindspot = cp.vl["LCA11"]["CF_Lca_IndLeft"] != 0 - ret.rightBlindspot = cp.vl["LCA11"]["CF_Lca_IndRight"] != 0 - - # save the entire LKAS11 and CLU11 - self.lkas11 = copy.copy(cp_cam.vl["LKAS11"]) - self.clu11 = copy.copy(cp.vl["CLU11"]) - self.steer_state = cp.vl["MDPS12"]["CF_Mdps_ToiActive"] # 0 NOT ACTIVE, 1 ACTIVE - self.prev_cruise_buttons = self.cruise_buttons[-1] - self.cruise_buttons.extend(cp.vl_all["CLU11"]["CF_Clu_CruiseSwState"]) - self.main_buttons.extend(cp.vl_all["CLU11"]["CF_Clu_CruiseSwMain"]) - - return ret - - def update_canfd(self, cp, cp_cam): - ret = car.CarState.new_message() - - self.is_metric = cp.vl["CRUISE_BUTTONS_ALT"]["DISTANCE_UNIT"] != 1 - speed_factor = CV.KPH_TO_MS if self.is_metric else CV.MPH_TO_MS - - if self.CP.flags & (HyundaiFlags.EV | HyundaiFlags.HYBRID): - offset = 255. if self.CP.flags & HyundaiFlags.EV else 1023. - ret.gas = cp.vl[self.accelerator_msg_canfd]["ACCELERATOR_PEDAL"] / offset - ret.gasPressed = ret.gas > 1e-5 - else: - ret.gasPressed = bool(cp.vl[self.accelerator_msg_canfd]["ACCELERATOR_PEDAL_PRESSED"]) - - ret.brakePressed = cp.vl["TCS"]["DriverBraking"] == 1 - - ret.doorOpen = cp.vl["DOORS_SEATBELTS"]["DRIVER_DOOR"] == 1 - ret.seatbeltUnlatched = cp.vl["DOORS_SEATBELTS"]["DRIVER_SEATBELT"] == 0 - - gear = cp.vl[self.gear_msg_canfd]["GEAR"] - ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(gear)) - - # TODO: figure out positions - ret.wheelSpeeds = self.get_wheel_speeds( - cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_1"], - cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_2"], - cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_3"], - cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_4"], - ) - ret.vEgoRaw = (ret.wheelSpeeds.fl + ret.wheelSpeeds.fr + ret.wheelSpeeds.rl + ret.wheelSpeeds.rr) / 4. - ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) - ret.standstill = ret.wheelSpeeds.fl <= STANDSTILL_THRESHOLD and ret.wheelSpeeds.rr <= STANDSTILL_THRESHOLD - - ret.steeringRateDeg = cp.vl["STEERING_SENSORS"]["STEERING_RATE"] - ret.steeringAngleDeg = cp.vl["STEERING_SENSORS"]["STEERING_ANGLE"] * -1 - ret.steeringTorque = cp.vl["MDPS"]["STEERING_COL_TORQUE"] - ret.steeringTorqueEps = cp.vl["MDPS"]["STEERING_OUT_TORQUE"] - ret.steeringPressed = self.update_steering_pressed(abs(ret.steeringTorque) > self.params.STEER_THRESHOLD, 5) - ret.steerFaultTemporary = cp.vl["MDPS"]["LKA_FAULT"] != 0 - - # TODO: alt signal usage may be described by cp.vl['BLINKERS']['USE_ALT_LAMP'] - left_blinker_sig, right_blinker_sig = "LEFT_LAMP", "RIGHT_LAMP" - if self.CP.carFingerprint == CAR.HYUNDAI_KONA_EV_2ND_GEN: - left_blinker_sig, right_blinker_sig = "LEFT_LAMP_ALT", "RIGHT_LAMP_ALT" - ret.leftBlinker, ret.rightBlinker = self.update_blinker_from_lamp(50, cp.vl["BLINKERS"][left_blinker_sig], - cp.vl["BLINKERS"][right_blinker_sig]) - if self.CP.enableBsm: - ret.leftBlindspot = cp.vl["BLINDSPOTS_REAR_CORNERS"]["FL_INDICATOR"] != 0 - ret.rightBlindspot = cp.vl["BLINDSPOTS_REAR_CORNERS"]["FR_INDICATOR"] != 0 - - # cruise state - # CAN FD cars enable on main button press, set available if no TCS faults preventing engagement - ret.cruiseState.available = cp.vl["TCS"]["ACCEnable"] == 0 - if self.CP.openpilotLongitudinalControl: - # These are not used for engage/disengage since openpilot keeps track of state using the buttons - ret.cruiseState.enabled = cp.vl["TCS"]["ACC_REQ"] == 1 - ret.cruiseState.standstill = False - else: - cp_cruise_info = cp_cam if self.CP.flags & HyundaiFlags.CANFD_CAMERA_SCC else cp - ret.cruiseState.enabled = cp_cruise_info.vl["SCC_CONTROL"]["ACCMode"] in (1, 2) - ret.cruiseState.standstill = cp_cruise_info.vl["SCC_CONTROL"]["CRUISE_STANDSTILL"] == 1 - ret.cruiseState.speed = cp_cruise_info.vl["SCC_CONTROL"]["VSetDis"] * speed_factor - self.cruise_info = copy.copy(cp_cruise_info.vl["SCC_CONTROL"]) - - # Manual Speed Limit Assist is a feature that replaces non-adaptive cruise control on EV CAN FD platforms. - # It limits the vehicle speed, overridable by pressing the accelerator past a certain point. - # The car will brake, but does not respect positive acceleration commands in this mode - # TODO: find this message on ICE & HYBRID cars + cruise control signals (if exists) - if self.CP.flags & HyundaiFlags.EV: - ret.cruiseState.nonAdaptive = cp.vl["MANUAL_SPEED_LIMIT_ASSIST"]["MSLA_ENABLED"] == 1 - - self.prev_cruise_buttons = self.cruise_buttons[-1] - self.cruise_buttons.extend(cp.vl_all[self.cruise_btns_msg_canfd]["CRUISE_BUTTONS"]) - self.main_buttons.extend(cp.vl_all[self.cruise_btns_msg_canfd]["ADAPTIVE_CRUISE_MAIN_BTN"]) - self.buttons_counter = cp.vl[self.cruise_btns_msg_canfd]["COUNTER"] - ret.accFaulted = cp.vl["TCS"]["ACCEnable"] != 0 # 0 ACC CONTROL ENABLED, 1-3 ACC CONTROL DISABLED - - if self.CP.flags & HyundaiFlags.CANFD_HDA2: - self.hda2_lfa_block_msg = copy.copy(cp_cam.vl["CAM_0x362"] if self.CP.flags & HyundaiFlags.CANFD_HDA2_ALT_STEERING - else cp_cam.vl["CAM_0x2a4"]) - - return ret - - def get_can_parser(self, CP): - if CP.carFingerprint in CANFD_CAR: - return self.get_can_parser_canfd(CP) - - messages = [ - # address, frequency - ("MDPS12", 50), - ("TCS11", 100), - ("TCS13", 50), - ("TCS15", 10), - ("CLU11", 50), - ("CLU15", 5), - ("ESP12", 100), - ("CGW1", 10), - ("CGW2", 5), - ("CGW4", 5), - ("WHL_SPD11", 50), - ("SAS11", 100), - ] - - if not CP.openpilotLongitudinalControl and CP.carFingerprint not in CAMERA_SCC_CAR: - messages += [ - ("SCC11", 50), - ("SCC12", 50), - ] - if CP.flags & HyundaiFlags.USE_FCA.value: - messages.append(("FCA11", 50)) - - if CP.enableBsm: - messages.append(("LCA11", 50)) - - if CP.flags & (HyundaiFlags.HYBRID | HyundaiFlags.EV): - messages.append(("E_EMS11", 50)) - else: - messages += [ - ("EMS12", 100), - ("EMS16", 100), - ] - - if CP.flags & (HyundaiFlags.HYBRID | HyundaiFlags.EV): - messages.append(("ELECT_GEAR", 20)) - elif CP.carFingerprint in CAN_GEARS["use_cluster_gears"]: - pass - elif CP.carFingerprint in CAN_GEARS["use_tcu_gears"]: - messages.append(("TCU12", 100)) - else: - messages.append(("LVR12", 100)) - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, 0) - - @staticmethod - def get_cam_can_parser(CP): - if CP.carFingerprint in CANFD_CAR: - return CarState.get_cam_can_parser_canfd(CP) - - messages = [ - ("LKAS11", 100) - ] - - if not CP.openpilotLongitudinalControl and CP.carFingerprint in CAMERA_SCC_CAR: - messages += [ - ("SCC11", 50), - ("SCC12", 50), - ] - - if CP.flags & HyundaiFlags.USE_FCA.value: - messages.append(("FCA11", 50)) - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, 2) - - def get_can_parser_canfd(self, CP): - messages = [ - (self.gear_msg_canfd, 100), - (self.accelerator_msg_canfd, 100), - ("WHEEL_SPEEDS", 100), - ("STEERING_SENSORS", 100), - ("MDPS", 100), - ("TCS", 50), - ("CRUISE_BUTTONS_ALT", 50), - ("BLINKERS", 4), - ("DOORS_SEATBELTS", 4), - ] - - if CP.flags & HyundaiFlags.EV: - messages += [ - ("MANUAL_SPEED_LIMIT_ASSIST", 10), - ] - - if not (CP.flags & HyundaiFlags.CANFD_ALT_BUTTONS): - messages += [ - ("CRUISE_BUTTONS", 50) - ] - - if CP.enableBsm: - messages += [ - ("BLINDSPOTS_REAR_CORNERS", 20), - ] - - if not (CP.flags & HyundaiFlags.CANFD_CAMERA_SCC.value) and not CP.openpilotLongitudinalControl: - messages += [ - ("SCC_CONTROL", 50), - ] - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus(CP).ECAN) - - @staticmethod - def get_cam_can_parser_canfd(CP): - messages = [] - if CP.flags & HyundaiFlags.CANFD_HDA2: - block_lfa_msg = "CAM_0x362" if CP.flags & HyundaiFlags.CANFD_HDA2_ALT_STEERING else "CAM_0x2a4" - messages += [(block_lfa_msg, 20)] - elif CP.flags & HyundaiFlags.CANFD_CAMERA_SCC: - messages += [ - ("SCC_CONTROL", 50), - ] - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus(CP).CAM) diff --git a/car/hyundai/fingerprints.py b/car/hyundai/fingerprints.py deleted file mode 100644 index d115283dd5..0000000000 --- a/car/hyundai/fingerprints.py +++ /dev/null @@ -1,1160 +0,0 @@ -# ruff: noqa: E501 -from cereal import car -from openpilot.selfdrive.car.hyundai.values import CAR - -Ecu = car.CarParams.Ecu - -FINGERPRINTS = { - CAR.HYUNDAI_SANTA_FE: [{ - 67: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 8, 593: 8, 608: 8, 688: 6, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1155: 8, 1156: 8, 1162: 8, 1164: 8, 1168: 7, 1170: 8, 1173: 8, 1183: 8, 1186: 2, 1191: 2, 1227: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1379: 8, 1384: 8, 1407: 8, 1414: 3, 1419: 8, 1427: 6, 1456: 4, 1470: 8 - }, - { - 67: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 8, 593: 8, 608: 8, 688: 6, 764: 8, 809: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1064: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1155: 8, 1162: 8, 1164: 8, 1168: 7, 1170: 8, 1173: 8, 1180: 8, 1183: 8, 1186: 2, 1227: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1371: 8, 1378: 8, 1384: 8, 1407: 8, 1414: 3, 1419: 8, 1427: 6, 1456: 4, 1470: 8, 1988: 8, 2000: 8, 2004: 8, 2008: 8, 2012: 8 - }, - { - 67: 8, 68: 8, 80: 4, 160: 8, 161: 8, 272: 8, 288: 4, 339: 8, 356: 8, 357: 8, 399: 8, 544: 8, 608: 8, 672: 8, 688: 5, 704: 1, 790: 8, 809: 8, 848: 8, 880: 8, 898: 8, 900: 8, 901: 8, 904: 8, 1056: 8, 1064: 8, 1065: 8, 1072: 8, 1075: 8, 1087: 8, 1088: 8, 1151: 8, 1200: 8, 1201: 8, 1232: 4, 1264: 8, 1265: 8, 1266: 8, 1296: 8, 1306: 8, 1312: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1348: 8, 1349: 8, 1369: 8, 1370: 8, 1371: 8, 1407: 8, 1415: 8, 1419: 8, 1440: 8, 1442: 4, 1461: 8, 1470: 8 - }], - CAR.HYUNDAI_SONATA: [{ - 67: 8, 68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 8, 546: 8, 549: 8, 550: 8, 576: 8, 593: 8, 608: 8, 688: 6, 809: 8, 832: 8, 854: 8, 865: 8, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 905: 8, 908: 8, 909: 8, 912: 7, 913: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1089: 5, 1096: 8, 1107: 5, 1108: 8, 1114: 8, 1136: 8, 1145: 8, 1151: 8, 1155: 8, 1156: 8, 1157: 4, 1162: 8, 1164: 8, 1168: 8, 1170: 8, 1173: 8, 1180: 8, 1183: 8, 1184: 8, 1186: 2, 1191: 2, 1193: 8, 1210: 8, 1225: 8, 1227: 8, 1265: 4, 1268: 8, 1280: 8, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1330: 8, 1339: 8, 1342: 6, 1343: 8, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1371: 8, 1378: 8, 1379: 8, 1384: 8, 1394: 8, 1407: 8, 1419: 8, 1427: 6, 1446: 8, 1456: 4, 1460: 8, 1470: 8, 1485: 8, 1504: 3, 1988: 8, 1996: 8, 2000: 8, 2004: 8, 2008: 8, 2012: 8, 2015: 8 - }], - CAR.KIA_STINGER: [{ - 67: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 358: 6, 359: 8, 544: 8, 576: 8, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1064: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1168: 7, 1170: 8, 1173: 8, 1184: 8, 1265: 4, 1280: 1, 1281: 4, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1371: 8, 1378: 4, 1379: 8, 1384: 8, 1407: 8, 1419: 8, 1425: 2, 1427: 6, 1456: 4, 1470: 8 - }], - CAR.GENESIS_G90: [{ - 67: 8, 68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 358: 6, 359: 8, 544: 8, 593: 8, 608: 8, 688: 5, 809: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1162: 4, 1168: 7, 1170: 8, 1173: 8, 1184: 8, 1265: 4, 1280: 1, 1281: 3, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1370: 8, 1371: 8, 1378: 4, 1384: 8, 1407: 8, 1419: 8, 1425: 2, 1427: 6, 1434: 2, 1456: 4, 1470: 8, 1988: 8, 2000: 8, 2003: 8, 2004: 8, 2005: 8, 2008: 8, 2011: 8, 2012: 8, 2013: 8 - }], - CAR.HYUNDAI_KONA_EV: [{ - 127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 544: 8, 549: 8, 593: 8, 688: 5, 832: 8, 881: 8, 882: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1136: 8, 1151: 6, 1168: 7, 1173: 8, 1183: 8, 1186: 2, 1191: 2, 1225: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1294: 8, 1307: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1378: 4, 1407: 8, 1419: 8, 1426: 8, 1427: 6, 1429: 8, 1430: 8, 1456: 4, 1470: 8, 1473: 8, 1507: 8, 1535: 8, 2000: 8, 2004: 8, 2008: 8, 2012: 8, 1157: 4, 1193: 8, 1379: 8, 1988: 8, 1996: 8 - }], - CAR.HYUNDAI_KONA_EV_2022: [{ - 127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 544: 8, 593: 8, 688: 5, 832: 8, 881: 8, 882: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 913: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1069: 8, 1078: 4, 1136: 8, 1145: 8, 1151: 8, 1155: 8, 1156: 8, 1157: 4, 1162: 8, 1164: 8, 1168: 8, 1173: 8, 1183: 8, 1188: 8, 1191: 2, 1193: 8, 1225: 8, 1227: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1339: 8, 1342: 8, 1343: 8, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1379: 8, 1407: 8, 1419: 8, 1426: 8, 1427: 6, 1429: 8, 1430: 8, 1446: 8, 1456: 4, 1470: 8, 1473: 8, 1485: 8, 1507: 8, 1535: 8, 1990: 8, 1998: 8 - }], - CAR.KIA_NIRO_EV: [{ - 127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 516: 8, 544: 8, 593: 8, 688: 5, 832: 8, 881: 8, 882: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1136: 8, 1151: 6, 1156: 8, 1157: 4, 1168: 7, 1173: 8, 1183: 8, 1186: 2, 1191: 2, 1193: 8, 1225: 8, 1260: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1407: 8, 1419: 8, 1426: 8, 1427: 6, 1429: 8, 1430: 8, 1456: 4, 1470: 8, 1473: 8, 1507: 8, 1535: 8, 1990: 8, 1998: 8, 1996: 8, 2000: 8, 2004: 8, 2008: 8, 2012: 8, 2015: 8 - }], - CAR.KIA_OPTIMA_H: [{ - 68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 544: 8, 593: 8, 688: 5, 832: 8, 881: 8, 882: 8, 897: 8, 902: 8, 903: 6, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1136: 6, 1151: 6, 1168: 7, 1173: 8, 1236: 2, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1322: 8, 1331: 8, 1332: 8, 1333: 8, 1342: 6, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1371: 8, 1407: 8, 1419: 8, 1427: 6, 1429: 8, 1430: 8, 1448: 8, 1456: 4, 1470: 8, 1476: 8, 1535: 8 - }, - { - 68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 544: 8, 576: 8, 593: 8, 688: 5, 881: 8, 882: 8, 897: 8, 902: 8, 903: 8, 909: 8, 912: 7, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1136: 6, 1151: 6, 1168: 7, 1173: 8, 1180: 8, 1186: 2, 1191: 2, 1265: 4, 1268: 8, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1371: 8, 1407: 8, 1419: 8, 1420: 8, 1425: 2, 1427: 6, 1429: 8, 1430: 8, 1448: 8, 1456: 4, 1470: 8, 1476: 8, 1535: 8 - }], -} - -FW_VERSIONS = { - CAR.HYUNDAI_AZERA_6TH_GEN: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00IG__ SCC F-CU- 1.00 1.00 99110-G8100 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00IG MDPS C 1.00 1.02 56310G8510\x00 4IGSC103', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00IG MFC AT MES LHD 1.00 1.04 99211-G8100 200511', - ], - }, - CAR.HYUNDAI_AZERA_HEV_6TH_GEN: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00IGH MFC AT KOR LHD 1.00 1.00 99211-G8000 180903', - b'\xf1\x00IGH MFC AT KOR LHD 1.00 1.01 99211-G8000 181109', - b'\xf1\x00IGH MFC AT KOR LHD 1.00 1.02 99211-G8100 191029', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00IG MDPS C 1.00 1.00 56310M9600\x00 4IHSC100', - b'\xf1\x00IG MDPS C 1.00 1.01 56310M9350\x00 4IH8C101', - b'\xf1\x00IG MDPS C 1.00 1.02 56310M9350\x00 4IH8C102', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00IGhe SCC FHCUP 1.00 1.00 99110-M9100 ', - b'\xf1\x00IGhe SCC FHCUP 1.00 1.01 99110-M9000 ', - b'\xf1\x00IGhe SCC FHCUP 1.00 1.02 99110-M9000 ', - ], - }, - CAR.HYUNDAI_GENESIS: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00DH LKAS 1.1 -150210', - b'\xf1\x00DH LKAS 1.4 -140110', - b'\xf1\x00DH LKAS 1.5 -140425', - ], - }, - CAR.HYUNDAI_IONIQ: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00AEhe SCC H-CUP 1.01 1.01 96400-G2000 ', - b'\xf1\x00AEhe SCC H-CUP 1.01 1.01 96400-G2100 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00AE MDPS C 1.00 1.05 56310/G2501 4AEHC105', - b'\xf1\x00AE MDPS C 1.00 1.07 56310/G2301 4AEHC107', - b'\xf1\x00AE MDPS C 1.00 1.07 56310/G2501 4AEHC107', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00AEH MFC AT EUR LHD 1.00 1.00 95740-G2400 180222', - b'\xf1\x00AEH MFC AT USA LHD 1.00 1.00 95740-G2400 180222', - ], - }, - CAR.HYUNDAI_IONIQ_PHEV_2019: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00AEhe SCC H-CUP 1.01 1.01 96400-G2000 ', - b'\xf1\x00AEhe SCC H-CUP 1.01 1.01 96400-G2100 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00AE MDPS C 1.00 1.07 56310/G2501 4AEHC107', - b'\xf1\x00AE MDPS C 1.00 1.07 56310/G2551 4AEHC107', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00AEP MFC AT AUS RHD 1.00 1.00 95740-G2400 180222', - b'\xf1\x00AEP MFC AT USA LHD 1.00 1.00 95740-G2400 180222', - ], - }, - CAR.HYUNDAI_IONIQ_PHEV: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00AEhe SCC F-CUP 1.00 1.00 99110-G2200 ', - b'\xf1\x00AEhe SCC F-CUP 1.00 1.00 99110-G2600 ', - b'\xf1\x00AEhe SCC F-CUP 1.00 1.02 99110-G2100 ', - b'\xf1\x00AEhe SCC FHCUP 1.00 1.00 99110-G2600 ', - b'\xf1\x00AEhe SCC FHCUP 1.00 1.02 99110-G2100 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00AE MDPS C 1.00 1.01 56310/G2210 4APHC101', - b'\xf1\x00AE MDPS C 1.00 1.01 56310/G2310 4APHC101', - b'\xf1\x00AE MDPS C 1.00 1.01 56310/G2510 4APHC101', - b'\xf1\x00AE MDPS C 1.00 1.01 56310/G2560 4APHC101', - b'\xf1\x00AE MDPS C 1.00 1.01 56310G2510\x00 4APHC101', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00AEP MFC AT EUR LHD 1.00 1.01 95740-G2600 190819', - b'\xf1\x00AEP MFC AT EUR RHD 1.00 1.01 95740-G2600 190819', - b'\xf1\x00AEP MFC AT USA LHD 1.00 1.00 95740-G2700 201027', - b'\xf1\x00AEP MFC AT USA LHD 1.00 1.01 95740-G2600 190819', - ], - }, - CAR.HYUNDAI_IONIQ_EV_2020: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00AEev SCC F-CUP 1.00 1.00 99110-G7200 ', - b'\xf1\x00AEev SCC F-CUP 1.00 1.00 99110-G7500 ', - b'\xf1\x00AEev SCC F-CUP 1.00 1.01 99110-G7000 ', - b'\xf1\x00AEev SCC F-CUP 1.00 1.01 99110-G7100 ', - b'\xf1\x00AEev SCC FHCUP 1.00 1.01 99110-G7100 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00AE MDPS C 1.00 1.01 56310/G7310 4APEC101', - b'\xf1\x00AE MDPS C 1.00 1.01 56310/G7510 4APEC101', - b'\xf1\x00AE MDPS C 1.00 1.01 56310/G7560 4APEC101', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.00 95740-G2600 190730', - b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.00 95740-G2700 201027', - b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.01 95740-G2600 190819', - b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.03 95740-G2500 190516', - b'\xf1\x00AEE MFC AT EUR RHD 1.00 1.01 95740-G2600 190819', - b'\xf1\x00AEE MFC AT USA LHD 1.00 1.01 95740-G2600 190819', - ], - }, - CAR.HYUNDAI_IONIQ_EV_LTD: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00AEev SCC F-CUP 1.00 1.00 96400-G7000 ', - b'\xf1\x00AEev SCC F-CUP 1.00 1.00 96400-G7100 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00AE MDPS C 1.00 1.02 56310G7300\x00 4AEEC102', - b'\xf1\x00AE MDPS C 1.00 1.03 56310/G7300 4AEEC103', - b'\xf1\x00AE MDPS C 1.00 1.03 56310G7300\x00 4AEEC103', - b'\xf1\x00AE MDPS C 1.00 1.04 56310/G7301 4AEEC104', - b'\xf1\x00AE MDPS C 1.00 1.04 56310/G7501 4AEEC104', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.00 95740-G2300 170703', - b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.00 95740-G2400 180222', - b'\xf1\x00AEE MFC AT EUR LHD 1.00 1.00 95740-G7200 160418', - b'\xf1\x00AEE MFC AT USA LHD 1.00 1.00 95740-G2400 180222', - ], - }, - CAR.HYUNDAI_IONIQ_HEV_2022: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00AEhe SCC F-CUP 1.00 1.00 99110-G2600 ', - b'\xf1\x00AEhe SCC FHCUP 1.00 1.00 99110-G2600 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00AE MDPS C 1.00 1.01 56310G2510\x00 4APHC101', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00AEH MFC AT USA LHD 1.00 1.00 95740-G2700 201027', - ], - }, - CAR.HYUNDAI_SONATA: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00DN8_ SCC F-CU- 1.00 1.00 99110-L0000 ', - b'\xf1\x00DN8_ SCC F-CUP 1.00 1.00 99110-L0000 ', - b'\xf1\x00DN8_ SCC F-CUP 1.00 1.02 99110-L1000 ', - b'\xf1\x00DN8_ SCC FHCUP 1.00 1.00 99110-L0000 ', - b'\xf1\x00DN8_ SCC FHCUP 1.00 1.01 99110-L1000 ', - b'\xf1\x00DN8_ SCC FHCUP 1.00 1.02 99110-L1000 ', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00DN ESC \x01 102\x19\x04\x13 58910-L1300', - b'\xf1\x00DN ESC \x03 100 \x08\x01 58910-L0300', - b'\xf1\x00DN ESC \x06 104\x19\x08\x01 58910-L0100', - b'\xf1\x00DN ESC \x06 106 \x07\x01 58910-L0100', - b'\xf1\x00DN ESC \x06 107 \x07\x03 58910-L1300', - b'\xf1\x00DN ESC \x06 107"\x08\x07 58910-L0100', - b'\xf1\x00DN ESC \x07 104\x19\x08\x01 58910-L0100', - b'\xf1\x00DN ESC \x07 106 \x07\x01 58910-L0100', - b'\xf1\x00DN ESC \x07 107"\x08\x07 58910-L0100', - b'\xf1\x00DN ESC \x08 103\x19\x06\x01 58910-L1300', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00DN8 MDPS C 1,00 1,01 56310L0010\x00 4DNAC101', - b'\xf1\x00DN8 MDPS C 1.00 1.01 56310-L0010 4DNAC101', - b'\xf1\x00DN8 MDPS C 1.00 1.01 56310-L0210 4DNAC101', - b'\xf1\x00DN8 MDPS C 1.00 1.01 56310-L0210 4DNAC102', - b'\xf1\x00DN8 MDPS C 1.00 1.01 56310L0010\x00 4DNAC101', - b'\xf1\x00DN8 MDPS C 1.00 1.01 56310L0200\x00 4DNAC102', - b'\xf1\x00DN8 MDPS C 1.00 1.01 56310L0210\x00 4DNAC101', - b'\xf1\x00DN8 MDPS C 1.00 1.01 56310L0210\x00 4DNAC102', - b'\xf1\x00DN8 MDPS C 1.00 1.03 56310-L1010 4DNDC103', - b'\xf1\x00DN8 MDPS C 1.00 1.03 56310-L1030 4DNDC103', - b'\xf1\x00DN8 MDPS R 1.00 1.00 57700-L0000 4DNAP100', - b'\xf1\x00DN8 MDPS R 1.00 1.00 57700-L0000 4DNAP101', - b'\xf1\x00DN8 MDPS R 1.00 1.02 57700-L1000 4DNDP105', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00DN8 MFC AT KOR LHD 1.00 1.02 99211-L1000 190422', - b'\xf1\x00DN8 MFC AT KOR LHD 1.00 1.04 99211-L1000 191016', - b'\xf1\x00DN8 MFC AT RUS LHD 1.00 1.03 99211-L1000 190705', - b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.00 99211-L0000 190716', - b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.01 99211-L0000 191016', - b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.03 99211-L0000 210603', - b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.05 99211-L1000 201109', - b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.06 99211-L1000 210325', - b'\xf1\x00DN8 MFC AT USA LHD 1.00 1.07 99211-L1000 211223', - ], - }, - CAR.HYUNDAI_SONATA_LF: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00LF__ SCC F-CUP 1.00 1.00 96401-C2200 ', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00LF ESC \t 11 \x17\x01\x13 58920-C2610', - b'\xf1\x00LF ESC \x0c 11 \x17\x01\x13 58920-C2610', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00LFF LKAS AT USA LHD 1.00 1.01 95740-C1000 E51', - b'\xf1\x00LFF LKAS AT USA LHD 1.01 1.02 95740-C1000 E52', - ], - }, - CAR.HYUNDAI_TUCSON: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00TL__ FCA F-CUP 1.00 1.01 99110-D3500 ', - b'\xf1\x00TL__ FCA F-CUP 1.00 1.02 99110-D3510 ', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00TL MFC AT KOR LHD 1.00 1.02 95895-D3800 180719', - b'\xf1\x00TL MFC AT USA LHD 1.00 1.06 95895-D3800 190107', - ], - }, - CAR.HYUNDAI_SANTA_FE: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00TM__ SCC F-CUP 1.00 1.00 99110-S1210 ', - b'\xf1\x00TM__ SCC F-CUP 1.00 1.01 99110-S2000 ', - b'\xf1\x00TM__ SCC F-CUP 1.00 1.02 99110-S2000 ', - b'\xf1\x00TM__ SCC F-CUP 1.00 1.03 99110-S2000 ', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00TM ESC \x02 100\x18\x030 58910-S2600', - b'\xf1\x00TM ESC \x02 102\x18\x07\x01 58910-S2600', - b'\xf1\x00TM ESC \x02 103\x18\x11\x07 58910-S2600', - b'\xf1\x00TM ESC \x02 104\x19\x07\x07 58910-S2600', - b'\xf1\x00TM ESC \x03 103\x18\x11\x07 58910-S2600', - b'\xf1\x00TM ESC \x0c 103\x18\x11\x08 58910-S2650', - b'\xf1\x00TM ESC \r 100\x18\x031 58910-S2650', - b'\xf1\x00TM ESC \r 103\x18\x11\x08 58910-S2650', - b'\xf1\x00TM ESC \r 104\x19\x07\x08 58910-S2650', - b'\xf1\x00TM ESC \r 105\x19\x05# 58910-S1500', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00TM MDPS C 1.00 1.00 56340-S2000 8409', - b'\xf1\x00TM MDPS C 1.00 1.00 56340-S2000 8A12', - b'\xf1\x00TM MDPS C 1.00 1.01 56340-S2000 9129', - b'\xf1\x00TM MDPS R 1.00 1.02 57700-S1100 4TMDP102', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00TM MFC AT EUR LHD 1.00 1.01 99211-S1010 181207', - b'\xf1\x00TM MFC AT USA LHD 1.00 1.00 99211-S2000 180409', - ], - }, - CAR.HYUNDAI_SANTA_FE_2022: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00TM__ SCC F-CUP 1.00 1.00 99110-S1500 ', - b'\xf1\x00TM__ SCC F-CUP 1.00 1.01 99110-S1500 ', - b'\xf1\x00TM__ SCC FHCUP 1.00 1.00 99110-S1500 ', - b'\xf1\x00TM__ SCC FHCUP 1.00 1.01 99110-S1500 ', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00TM ESC \x01 102!\x04\x03 58910-S2DA0', - b'\xf1\x00TM ESC \x01 104"\x10\x07 58910-S2DA0', - b'\xf1\x00TM ESC \x02 101 \x08\x04 58910-S2GA0', - b'\xf1\x00TM ESC \x02 103"\x07\x08 58910-S2GA0', - b'\xf1\x00TM ESC \x03 101 \x08\x02 58910-S2DA0', - b'\xf1\x00TM ESC \x03 102!\x04\x03 58910-S2DA0', - b'\xf1\x00TM ESC \x04 101 \x08\x04 58910-S2GA0', - b'\xf1\x00TM ESC \x04 102!\x04\x05 58910-S2GA0', - b'\xf1\x00TM ESC \x04 103"\x07\x08 58910-S2GA0', - b'\xf1\x00TM ESC \x1e 102 \x08\x08 58910-S1DA0', - b'\xf1\x00TM ESC 103!\x030 58910-S1MA0', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00TM MDPS C 1.00 1.01 56310-S1AB0 4TSDC101', - b'\xf1\x00TM MDPS C 1.00 1.01 56310-S1EB0 4TSDC101', - b'\xf1\x00TM MDPS C 1.00 1.02 56370-S2AA0 0B19', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00TM MFC AT EUR LHD 1.00 1.03 99211-S1500 210224', - b'\xf1\x00TM MFC AT MES LHD 1.00 1.05 99211-S1500 220126', - b'\xf1\x00TMA MFC AT MEX LHD 1.00 1.01 99211-S2500 210205', - b'\xf1\x00TMA MFC AT USA LHD 1.00 1.00 99211-S2500 200720', - b'\xf1\x00TMA MFC AT USA LHD 1.00 1.01 99211-S2500 210205', - b'\xf1\x00TMA MFC AT USA LHD 1.00 1.03 99211-S2500 220414', - ], - }, - CAR.HYUNDAI_SANTA_FE_HEV_2022: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00TMhe SCC FHCUP 1.00 1.00 99110-CL500 ', - b'\xf1\x00TMhe SCC FHCUP 1.00 1.01 99110-CL500 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00TM MDPS C 1.00 1.02 56310-CLAC0 4TSHC102', - b'\xf1\x00TM MDPS C 1.00 1.02 56310-CLEC0 4TSHC102', - b'\xf1\x00TM MDPS C 1.00 1.02 56310-GA000 4TSHA100', - b'\xf1\x00TM MDPS R 1.00 1.05 57700-CL000 4TSHP105', - b'\xf1\x00TM MDPS R 1.00 1.06 57700-CL000 4TSHP106', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00TMA MFC AT USA LHD 1.00 1.03 99211-S2500 220414', - b'\xf1\x00TMH MFC AT EUR LHD 1.00 1.06 99211-S1500 220727', - b'\xf1\x00TMH MFC AT KOR LHD 1.00 1.06 99211-S1500 220727', - b'\xf1\x00TMH MFC AT USA LHD 1.00 1.03 99211-S1500 210224', - b'\xf1\x00TMH MFC AT USA LHD 1.00 1.05 99211-S1500 220126', - b'\xf1\x00TMH MFC AT USA LHD 1.00 1.06 99211-S1500 220727', - ], - }, - CAR.HYUNDAI_SANTA_FE_PHEV_2022: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00TMhe SCC F-CUP 1.00 1.00 99110-CL500 ', - b'\xf1\x00TMhe SCC FHCUP 1.00 1.00 99110-CL500 ', - b'\xf1\x00TMhe SCC FHCUP 1.00 1.01 99110-CL500 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00TM MDPS C 1.00 1.02 56310-CLAC0 4TSHC102', - b'\xf1\x00TM MDPS C 1.00 1.02 56310-CLEC0 4TSHC102', - b'\xf1\x00TM MDPS C 1.00 1.02 56310CLEC0\x00 4TSHC102', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00TMP MFC AT USA LHD 1.00 1.03 99211-S1500 210224', - b'\xf1\x00TMP MFC AT USA LHD 1.00 1.05 99211-S1500 220126', - b'\xf1\x00TMP MFC AT USA LHD 1.00 1.06 99211-S1500 220727', - ], - }, - CAR.HYUNDAI_CUSTIN_1ST_GEN: { - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00KU ESC \x01 101!\x02\x03 58910-O3200', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00KU__ SCC F-CUP 1.00 1.01 99110-O3000 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00KU MDPS C 1.00 1.01 56310/O3100 4KUCC101', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00KU2 MFC AT CHN LHD 1.00 1.02 99211-O3000 220923', - ], - }, - CAR.KIA_STINGER: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00CK__ SCC F_CUP 1.00 1.01 96400-J5000 ', - b'\xf1\x00CK__ SCC F_CUP 1.00 1.01 96400-J5100 ', - b'\xf1\x00CK__ SCC F_CUP 1.00 1.02 96400-J5100 ', - b'\xf1\x00CK__ SCC F_CUP 1.00 1.03 96400-J5100 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00CK MDPS R 1.00 1.04 57700-J5200 4C2CL104', - b'\xf1\x00CK MDPS R 1.00 1.04 57700-J5220 4C2VL104', - b'\xf1\x00CK MDPS R 1.00 1.04 57700-J5420 4C4VL104', - b'\xf1\x00CK MDPS R 1.00 1.06 57700-J5220 4C2VL106', - b'\xf1\x00CK MDPS R 1.00 1.06 57700-J5420 4C4VL106', - b'\xf1\x00CK MDPS R 1.00 1.07 57700-J5220 4C2VL107', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00CK MFC AT EUR LHD 1.00 1.03 95740-J5000 170822', - b'\xf1\x00CK MFC AT USA LHD 1.00 1.03 95740-J5000 170822', - b'\xf1\x00CK MFC AT USA LHD 1.00 1.04 95740-J5000 180504', - ], - }, - CAR.KIA_STINGER_2022: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00CK__ SCC F-CUP 1.00 1.00 99110-J5500 ', - b'\xf1\x00CK__ SCC FHCUP 1.00 1.00 99110-J5500 ', - b'\xf1\x00CK__ SCC FHCUP 1.00 1.00 99110-J5600 ', - b'\xf1\x00CK__ SCC FHCUP 1.00 1.01 99110-J5100 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00CK MDPS R 1.00 5.03 57700-J5300 4C2CL503', - b'\xf1\x00CK MDPS R 1.00 5.03 57700-J5320 4C2VL503', - b'\xf1\x00CK MDPS R 1.00 5.03 57700-J5380 4C2VR503', - b'\xf1\x00CK MDPS R 1.00 5.03 57700-J5520 4C4VL503', - b'\xf1\x00CK MDPS R 1.00 5.04 57700-J5520 4C4VL504', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00CK MFC AT AUS RHD 1.00 1.00 99211-J5500 210622', - b'\xf1\x00CK MFC AT KOR LHD 1.00 1.00 99211-J5500 210622', - b'\xf1\x00CK MFC AT USA LHD 1.00 1.00 99211-J5500 210622', - b'\xf1\x00CK MFC AT USA LHD 1.00 1.03 99211-J5000 201209', - ], - }, - CAR.HYUNDAI_PALISADE: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00LX2 SCC FHCUP 1.00 1.04 99110-S8100 ', - b'\xf1\x00LX2_ SCC F-CUP 1.00 1.04 99110-S8100 ', - b'\xf1\x00LX2_ SCC F-CUP 1.00 1.05 99110-S8100 ', - b'\xf1\x00LX2_ SCC FHCU- 1.00 1.05 99110-S8100 ', - b'\xf1\x00LX2_ SCC FHCUP 1.00 1.00 99110-S8110 ', - b'\xf1\x00LX2_ SCC FHCUP 1.00 1.03 99110-S8100 ', - b'\xf1\x00LX2_ SCC FHCUP 1.00 1.04 99110-S8100 ', - b'\xf1\x00LX2_ SCC FHCUP 1.00 1.05 99110-S8100 ', - b'\xf1\x00ON__ FCA FHCUP 1.00 1.00 99110-S9110 ', - b'\xf1\x00ON__ FCA FHCUP 1.00 1.01 99110-S9110 ', - b'\xf1\x00ON__ FCA FHCUP 1.00 1.02 99110-S9100 ', - b'\xf1\x00ON__ FCA FHCUP 1.00 1.03 99110-S9100 ', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00LX ESC \x01 103\x19\t\x10 58910-S8360', - b'\xf1\x00LX ESC \x01 1031\t\x10 58910-S8360', - b'\xf1\x00LX ESC \x01 104 \x10\x15 58910-S8350', - b'\xf1\x00LX ESC \x01 104 \x10\x16 58910-S8360', - b'\xf1\x00LX ESC \x0b 101\x19\x03\x17 58910-S8330', - b'\xf1\x00LX ESC \x0b 101\x19\x03 58910-S8360', - b'\xf1\x00LX ESC \x0b 102\x19\x05\x07 58910-S8330', - b'\xf1\x00LX ESC \x0b 103\x19\t\x07 58910-S8330', - b'\xf1\x00LX ESC \x0b 103\x19\t\t 58910-S8350', - b'\xf1\x00LX ESC \x0b 103\x19\t\x10 58910-S8360', - b'\xf1\x00LX ESC \x0b 104 \x10\x16 58910-S8360', - b'\xf1\x00ON ESC \x01 101\x19\t\x08 58910-S9360', - b'\xf1\x00ON ESC \x0b 100\x18\x12\x18 58910-S9360', - b'\xf1\x00ON ESC \x0b 101\x19\t\x05 58910-S9320', - b'\xf1\x00ON ESC \x0b 101\x19\t\x08 58910-S9360', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00LX2 MDPS C 1,00 1,03 56310-S8020 4LXDC103', - b'\xf1\x00LX2 MDPS C 1.00 1.03 56310-S8000 4LXDC103', - b'\xf1\x00LX2 MDPS C 1.00 1.03 56310-S8020 4LXDC103', - b'\xf1\x00LX2 MDPS C 1.00 1.03 56310-XX000 4LXDC103', - b'\xf1\x00LX2 MDPS C 1.00 1.04 56310-S8020 4LXDC104', - b'\xf1\x00LX2 MDPS C 1.00 1.04 56310-S8420 4LXDC104', - b'\xf1\x00LX2 MDPS R 1.00 1.02 56370-S8300 9318', - b'\xf1\x00ON MDPS C 1.00 1.00 56340-S9000 8B13', - b'\xf1\x00ON MDPS C 1.00 1.01 56340-S9000 9201', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00LX2 MFC AT KOR LHD 1.00 1.08 99211-S8100 200903', - b'\xf1\x00LX2 MFC AT USA LHD 1.00 1.00 99211-S8110 210226', - b'\xf1\x00LX2 MFC AT USA LHD 1.00 1.03 99211-S8100 190125', - b'\xf1\x00LX2 MFC AT USA LHD 1.00 1.05 99211-S8100 190909', - b'\xf1\x00LX2 MFC AT USA LHD 1.00 1.07 99211-S8100 200422', - b'\xf1\x00LX2 MFC AT USA LHD 1.00 1.08 99211-S8100 200903', - b'\xf1\x00ON MFC AT USA LHD 1.00 1.01 99211-S9100 181105', - b'\xf1\x00ON MFC AT USA LHD 1.00 1.03 99211-S9100 200720', - b'\xf1\x00ON MFC AT USA LHD 1.00 1.04 99211-S9100 211227', - ], - }, - CAR.HYUNDAI_VELOSTER: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00JS__ SCC H-CUP 1.00 1.02 95650-J3200 ', - b'\xf1\x00JS__ SCC HNCUP 1.00 1.02 95650-J3100 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00JSL MDPS C 1.00 1.03 56340-J3000 8308', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00JS LKAS AT KOR LHD 1.00 1.03 95740-J3000 K33', - b'\xf1\x00JS LKAS AT USA LHD 1.00 1.02 95740-J3000 K32', - ], - }, - CAR.GENESIS_G70: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00IK__ SCC F-CUP 1.00 1.01 96400-G9100 ', - b'\xf1\x00IK__ SCC F-CUP 1.00 1.02 96400-G9100 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00IK MDPS R 1.00 1.06 57700-G9420 4I4VL106', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00IK MFC AT USA LHD 1.00 1.01 95740-G9000 170920', - ], - }, - CAR.GENESIS_G70_2020: { - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00IK MDPS R 1.00 1.06 57700-G9220 4I2VL106', - b'\xf1\x00IK MDPS R 1.00 1.07 57700-G9220 4I2VL107', - b'\xf1\x00IK MDPS R 1.00 1.07 57700-G9420 4I4VL107', - b'\xf1\x00IK MDPS R 1.00 1.08 57700-G9200 4I2CL108', - b'\xf1\x00IK MDPS R 1.00 1.08 57700-G9420 4I4VL108', - b'\xf1\x00IK MDPS R 1.00 5.09 57700-G9520 4I4VL509', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00IK__ SCC F-CUP 1.00 1.01 96400-G9100 ', - b'\xf1\x00IK__ SCC F-CUP 1.00 1.02 96400-G9100 ', - b'\xf1\x00IK__ SCC F-CUP 1.00 1.02 96400-G9100 \xf1\xa01.02', - b'\xf1\x00IK__ SCC FHCUP 1.00 1.00 99110-G9300 ', - b'\xf1\x00IK__ SCC FHCUP 1.00 1.02 96400-G9000 ', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00IK MFC AT KOR LHD 1.00 1.01 95740-G9000 170920', - b'\xf1\x00IK MFC AT USA LHD 1.00 1.01 95740-G9000 170920', - b'\xf1\x00IK MFC AT USA LHD 1.00 1.04 99211-G9000 220401', - ], - }, - CAR.GENESIS_G80: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00DH__ SCC F-CUP 1.00 1.01 96400-B1120 ', - b'\xf1\x00DH__ SCC F-CUP 1.00 1.02 96400-B1120 ', - b'\xf1\x00DH__ SCC FHCUP 1.00 1.01 96400-B1110 ', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00DH LKAS AT KOR LHD 1.01 1.01 95895-B1500 161014', - b'\xf1\x00DH LKAS AT KOR LHD 1.01 1.02 95895-B1500 170810', - b'\xf1\x00DH LKAS AT USA LHD 1.01 1.01 95895-B1500 161014', - b'\xf1\x00DH LKAS AT USA LHD 1.01 1.02 95895-B1500 170810', - b'\xf1\x00DH LKAS AT USA LHD 1.01 1.03 95895-B1500 180713', - b'\xf1\x00DH LKAS AT USA LHD 1.01 1.04 95895-B1500 181213', - ], - }, - CAR.GENESIS_G90: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00HI__ SCC F-CUP 1.00 1.01 96400-D2100 ', - b'\xf1\x00HI__ SCC FHCUP 1.00 1.02 99110-D2100 ', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00HI LKAS AT USA LHD 1.00 1.00 95895-D2020 160302', - b'\xf1\x00HI LKAS AT USA LHD 1.00 1.00 95895-D2030 170208', - b'\xf1\x00HI MFC AT USA LHD 1.00 1.03 99211-D2000 190831', - ], - }, - CAR.HYUNDAI_KONA: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00OS__ SCC F-CUP 1.00 1.00 95655-J9200 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00OS MDPS C 1.00 1.05 56310J9030\x00 4OSDC105', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00OS9 LKAS AT USA LHD 1.00 1.00 95740-J9300 g21', - ], - }, - CAR.KIA_CEED: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00CD__ SCC F-CUP 1.00 1.02 99110-J7000 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00CD MDPS C 1.00 1.06 56310-XX000 4CDEC106', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00CD LKAS AT EUR LHD 1.00 1.01 99211-J7000 B40', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00CD ESC \x03 102\x18\x08\x05 58920-J7350', - ], - }, - CAR.KIA_FORTE: { - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00BD MDPS C 1.00 1.02 56310-XX000 4BD2C102', - b'\xf1\x00BD MDPS C 1.00 1.08 56310/M6300 4BDDC108', - b'\xf1\x00BD MDPS C 1.00 1.08 56310M6300\x00 4BDDC108', - b'\xf1\x00BDm MDPS C A.01 1.01 56310M7800\x00 4BPMC101', - b'\xf1\x00BDm MDPS C A.01 1.03 56310M7800\x00 4BPMC103', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00BD LKAS AT USA LHD 1.00 1.04 95740-M6000 J33', - b'\xf1\x00BDP LKAS AT USA LHD 1.00 1.05 99211-M6500 744', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00BDPE_SCC FHCUPC 1.00 1.04 99110-M6500\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'\xf1\x00BD__ SCC H-CUP 1.00 1.02 99110-M6000 ', - ], - }, - CAR.KIA_K5_2021: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00DL3_ SCC F-CUP 1.00 1.03 99110-L2100 ', - b'\xf1\x00DL3_ SCC FHCUP 1.00 1.03 99110-L2000 ', - b'\xf1\x00DL3_ SCC FHCUP 1.00 1.03 99110-L2100 ', - b'\xf1\x00DL3_ SCC FHCUP 1.00 1.04 99110-L2100 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00DL3 MDPS C 1.00 1.01 56310-L3110 4DLAC101', - b'\xf1\x00DL3 MDPS C 1.00 1.01 56310-L3220 4DLAC101', - b'\xf1\x00DL3 MDPS C 1.00 1.02 56310-L2220 4DLDC102', - b'\xf1\x00DL3 MDPS C 1.00 1.02 56310L3220\x00 4DLAC102', - b'\xf1\x00DL3 MDPS R 1.00 1.02 57700-L3000 4DLAP102', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00DL3 MFC AT KOR LHD 1.00 1.04 99210-L2000 210527', - b'\xf1\x00DL3 MFC AT USA LHD 1.00 1.03 99210-L3000 200915', - b'\xf1\x00DL3 MFC AT USA LHD 1.00 1.04 99210-L3000 210208', - b'\xf1\x00DL3 MFC AT USA LHD 1.00 1.05 99210-L3000 211222', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00DL ESC \x01 104 \x07\x12 58910-L2200', - b'\xf1\x00DL ESC \x03 100 \x08\x02 58910-L3600', - b'\xf1\x00DL ESC \x06 101 \x04\x02 58910-L3200', - b'\xf1\x00DL ESC \x06 103"\x08\x06 58910-L3200', - b'\xf1\x00DL ESC \t 100 \x06\x02 58910-L3800', - b'\xf1\x00DL ESC \t 101 \x07\x02 58910-L3800', - b'\xf1\x00DL ESC \t 102"\x08\x10 58910-L3800', - ], - }, - CAR.KIA_K5_HEV_2020: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00DLhe SCC FHCUP 1.00 1.02 99110-L7000 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00DL3 MDPS C 1.00 1.02 56310-L7000 4DLHC102', - b'\xf1\x00DL3 MDPS C 1.00 1.02 56310-L7220 4DLHC102', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00DL3HMFC AT KOR LHD 1.00 1.02 99210-L2000 200309', - b'\xf1\x00DL3HMFC AT KOR LHD 1.00 1.04 99210-L2000 210527', - ], - }, - CAR.HYUNDAI_KONA_EV: { - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00OS IEB \x01 212 \x11\x13 58520-K4000', - b'\xf1\x00OS IEB \x02 210 \x02\x14 58520-K4000', - b'\xf1\x00OS IEB \x02 212 \x11\x13 58520-K4000', - b'\xf1\x00OS IEB \x03 210 \x02\x14 58520-K4000', - b'\xf1\x00OS IEB \x03 212 \x11\x13 58520-K4000', - b'\xf1\x00OS IEB \r 105\x18\t\x18 58520-K4000', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00OE2 LKAS AT EUR LHD 1.00 1.00 95740-K4200 200', - b'\xf1\x00OSE LKAS AT EUR LHD 1.00 1.00 95740-K4100 W40', - b'\xf1\x00OSE LKAS AT EUR RHD 1.00 1.00 95740-K4100 W40', - b'\xf1\x00OSE LKAS AT KOR LHD 1.00 1.00 95740-K4100 W40', - b'\xf1\x00OSE LKAS AT USA LHD 1.00 1.00 95740-K4100 W40', - b'\xf1\x00OSE LKAS AT USA LHD 1.00 1.00 95740-K4300 W50', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00OS MDPS C 1.00 1.03 56310/K4550 4OEDC103', - b'\xf1\x00OS MDPS C 1.00 1.04 56310-XX000 4OEDC104', - b'\xf1\x00OS MDPS C 1.00 1.04 56310K4000\x00 4OEDC104', - b'\xf1\x00OS MDPS C 1.00 1.04 56310K4050\x00 4OEDC104', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00OSev SCC F-CUP 1.00 1.00 99110-K4000 ', - b'\xf1\x00OSev SCC F-CUP 1.00 1.00 99110-K4100 ', - b'\xf1\x00OSev SCC F-CUP 1.00 1.01 99110-K4000 ', - b'\xf1\x00OSev SCC FNCUP 1.00 1.01 99110-K4000 ', - ], - }, - CAR.HYUNDAI_KONA_EV_2022: { - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00OS IEB \x02 102"\x05\x16 58520-K4010', - b'\xf1\x00OS IEB \x03 101 \x11\x13 58520-K4010', - b'\xf1\x00OS IEB \x03 102"\x05\x16 58520-K4010', - b'\xf1\x00OS IEB \r 102"\x05\x16 58520-K4010', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00OSP LKA AT AUS RHD 1.00 1.04 99211-J9200 904', - b'\xf1\x00OSP LKA AT CND LHD 1.00 1.02 99211-J9110 802', - b'\xf1\x00OSP LKA AT EUR LHD 1.00 1.04 99211-J9200 904', - b'\xf1\x00OSP LKA AT EUR RHD 1.00 1.02 99211-J9110 802', - b'\xf1\x00OSP LKA AT EUR RHD 1.00 1.04 99211-J9200 904', - b'\xf1\x00OSP LKA AT USA LHD 1.00 1.04 99211-J9200 904', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00OSP MDPS C 1.00 1.02 56310-K4271 4OEPC102', - b'\xf1\x00OSP MDPS C 1.00 1.02 56310/K4271 4OEPC102', - b'\xf1\x00OSP MDPS C 1.00 1.02 56310/K4970 4OEPC102', - b'\xf1\x00OSP MDPS C 1.00 1.02 56310K4260\x00 4OEPC102', - b'\xf1\x00OSP MDPS C 1.00 1.02 56310K4261\x00 4OEPC102', - b'\xf1\x00OSP MDPS C 1.00 1.02 56310K4971\x00 4OEPC102', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00YB__ FCA ----- 1.00 1.01 99110-K4500 \x00\x00\x00', - ], - }, - CAR.HYUNDAI_KONA_EV_2ND_GEN: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00SXev RDR ----- 1.00 1.00 99110-BF000 ', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00SX2EMFC AT KOR LHD 1.00 1.00 99211-BF000 230410', - ], - }, - CAR.KIA_NIRO_EV: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00DEev SCC F-CUP 1.00 1.00 99110-Q4000 ', - b'\xf1\x00DEev SCC F-CUP 1.00 1.00 99110-Q4100 ', - b'\xf1\x00DEev SCC F-CUP 1.00 1.00 99110-Q4500 ', - b'\xf1\x00DEev SCC F-CUP 1.00 1.00 99110-Q4600 ', - b'\xf1\x00DEev SCC F-CUP 1.00 1.02 96400-Q4000 ', - b'\xf1\x00DEev SCC F-CUP 1.00 1.02 96400-Q4100 ', - b'\xf1\x00DEev SCC F-CUP 1.00 1.03 96400-Q4100 ', - b'\xf1\x00DEev SCC FHCUP 1.00 1.00 99110-Q4600 ', - b'\xf1\x00DEev SCC FHCUP 1.00 1.03 96400-Q4000 ', - b'\xf1\x00DEev SCC FNCUP 1.00 1.00 99110-Q4600 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00DE MDPS C 1.00 1.04 56310Q4100\x00 4DEEC104', - b'\xf1\x00DE MDPS C 1.00 1.05 56310Q4000\x00 4DEEC105', - b'\xf1\x00DE MDPS C 1.00 1.05 56310Q4100\x00 4DEEC105', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00DEE MFC AT EUR LHD 1.00 1.00 99211-Q4000 191211', - b'\xf1\x00DEE MFC AT EUR LHD 1.00 1.00 99211-Q4100 200706', - b'\xf1\x00DEE MFC AT EUR LHD 1.00 1.03 95740-Q4000 180821', - b'\xf1\x00DEE MFC AT KOR LHD 1.00 1.03 95740-Q4000 180821', - b'\xf1\x00DEE MFC AT USA LHD 1.00 1.00 99211-Q4000 191211', - b'\xf1\x00DEE MFC AT USA LHD 1.00 1.01 99211-Q4500 210428', - b'\xf1\x00DEE MFC AT USA LHD 1.00 1.03 95740-Q4000 180821', - ], - }, - CAR.KIA_NIRO_EV_2ND_GEN: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00SG2_ RDR ----- 1.00 1.01 99110-AT000 ', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00SG2EMFC AT EUR LHD 1.01 1.09 99211-AT000 220801', - b'\xf1\x00SG2EMFC AT USA LHD 1.01 1.09 99211-AT000 220801', - ], - }, - CAR.KIA_NIRO_PHEV: { - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00DE MDPS C 1.00 1.01 56310G5520\x00 4DEPC101', - b'\xf1\x00DE MDPS C 1.00 1.09 56310G5301\x00 4DEHC109', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00DEH MFC AT USA LHD 1.00 1.00 95740-G5010 170117', - b'\xf1\x00DEP MFC AT USA LHD 1.00 1.00 95740-G5010 170117', - b'\xf1\x00DEP MFC AT USA LHD 1.00 1.01 95740-G5010 170424', - b'\xf1\x00DEP MFC AT USA LHD 1.00 1.05 99211-G5000 190826', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00DEhe SCC F-CUP 1.00 1.02 99110-G5100 ', - b'\xf1\x00DEhe SCC H-CUP 1.01 1.02 96400-G5100 ', - ], - }, - CAR.KIA_NIRO_PHEV_2022: { - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00DE MDPS C 1.00 1.01 56310G5520\x00 4DEPC101', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00DEP MFC AT USA LHD 1.00 1.00 99211-G5500 210428', - b'\xf1\x00DEP MFC AT USA LHD 1.00 1.06 99211-G5000 201028', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00DEhe SCC F-CUP 1.00 1.00 99110-G5600 ', - b'\xf1\x00DEhe SCC FHCUP 1.00 1.00 99110-G5600 ', - ], - }, - CAR.KIA_NIRO_HEV_2021: { - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00DE MDPS C 1.00 1.01 56310G5520\x00 4DEPC101', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00DEH MFC AT KOR LHD 1.00 1.04 99211-G5000 190516', - b'\xf1\x00DEH MFC AT USA LHD 1.00 1.00 99211-G5500 210428', - b'\xf1\x00DEH MFC AT USA LHD 1.00 1.07 99211-G5000 201221', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00DEhe SCC FHCUP 1.00 1.00 99110-G5600 ', - b'\xf1\x00DEhe SCC FHCUP 1.00 1.01 99110-G5000 ', - ], - }, - CAR.KIA_SELTOS: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00SP2_ SCC FHCUP 1.01 1.05 99110-Q5100 ', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00SP ESC \x07 101\x19\t\x05 58910-Q5450', - b'\xf1\x00SP ESC \t 101\x19\t\x05 58910-Q5450', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00SP2 MDPS C 1.00 1.04 56300Q5200 ', - b'\xf1\x00SP2 MDPS C 1.01 1.05 56300Q5200 ', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00SP2 MFC AT USA LHD 1.00 1.04 99210-Q5000 191114', - b'\xf1\x00SP2 MFC AT USA LHD 1.00 1.05 99210-Q5000 201012', - ], - }, - CAR.KIA_OPTIMA_G4: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00JF__ SCC F-CUP 1.00 1.00 96400-D4100 ', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00JF ESC \x0f 16 \x16\x06\x17 58920-D5080', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00JFWGN LDWS AT USA LHD 1.00 1.02 95895-D4100 G21', - ], - }, - CAR.KIA_OPTIMA_G4_FL: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00JF__ SCC F-CUP 1.00 1.00 96400-D4110 ', - ], - (Ecu.abs, 0x7d1, None): [ - b"\xf1\x00JF ESC \t 11 \x18\x03' 58920-D5260", - b'\xf1\x00JF ESC \x0b 11 \x18\x030 58920-D5180', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00JFA LKAS AT USA LHD 1.00 1.00 95895-D5001 h32', - b'\xf1\x00JFA LKAS AT USA LHD 1.00 1.00 95895-D5100 h32', - ], - }, - CAR.KIA_OPTIMA_H: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00JFhe SCC FNCUP 1.00 1.00 96400-A8000 ', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00JFP LKAS AT EUR LHD 1.00 1.03 95895-A8100 160711', - ], - }, - CAR.KIA_OPTIMA_H_G4_FL: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00JFhe SCC FHCUP 1.00 1.01 99110-A8500 ', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00JFH MFC AT KOR LHD 1.00 1.01 95895-A8200 180323', - ], - }, - CAR.HYUNDAI_ELANTRA: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00AD LKAS AT USA LHD 1.01 1.01 95895-F2000 251', - b'\xf1\x00ADP LKAS AT USA LHD 1.00 1.03 99211-F2000 X31', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00AD ESC \x11 11 \x18\x05\x06 58910-F2840', - b'\xf1\x00AD ESC \x11 12 \x15\t\t 58920-F2810', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00AD__ SCC H-CUP 1.00 1.00 99110-F2100 ', - b'\xf1\x00AD__ SCC H-CUP 1.00 1.01 96400-F2100 ', - ], - }, - CAR.HYUNDAI_ELANTRA_GT_I30: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00PD LKAS AT KOR LHD 1.00 1.02 95740-G3000 A51', - b'\xf1\x00PD LKAS AT USA LHD 1.00 1.02 95740-G3000 A51', - b'\xf1\x00PD LKAS AT USA LHD 1.01 1.01 95740-G3100 A54', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00PD MDPS C 1.00 1.00 56310G3300\x00 4PDDC100', - b'\xf1\x00PD MDPS C 1.00 1.03 56310/G3300 4PDDC103', - b'\xf1\x00PD MDPS C 1.00 1.04 56310/G3300 4PDDC104', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00PD ESC \t 104\x18\t\x03 58920-G3350', - b'\xf1\x00PD ESC \x0b 103\x17\x110 58920-G3350', - b'\xf1\x00PD ESC \x0b 104\x18\t\x03 58920-G3350', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00PD__ SCC F-CUP 1.00 1.00 96400-G3300 ', - b'\xf1\x00PD__ SCC F-CUP 1.01 1.00 96400-G3100 ', - b'\xf1\x00PD__ SCC FNCUP 1.01 1.00 96400-G3000 ', - ], - }, - CAR.HYUNDAI_ELANTRA_2021: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00CN7_ SCC F-CUP 1.00 1.01 99110-AA000 ', - b'\xf1\x00CN7_ SCC FHCUP 1.00 1.01 99110-AA000 ', - b'\xf1\x00CN7_ SCC FNCUP 1.00 1.01 99110-AA000 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00CN7 MDPS C 1.00 1.06 56310/AA050 4CNDC106', - b'\xf1\x00CN7 MDPS C 1.00 1.06 56310/AA070 4CNDC106', - b'\xf1\x00CN7 MDPS C 1.00 1.06 56310AA050\x00 4CNDC106', - b'\xf1\x00CN7 MDPS C 1.00 1.07 56310AA050\x00 4CNDC107', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.00 99210-AB000 200819', - b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.01 99210-AB000 210205', - b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.02 99210-AB000 220111', - b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.03 99210-AA000 200819', - b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.03 99210-AB000 220426', - b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.06 99210-AA000 220111', - b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.07 99210-AA000 220426', - b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.08 99210-AA000 220728', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00CN ESC \t 101 \x10\x03 58910-AB800', - b'\xf1\x00CN ESC \t 104 \x08\x03 58910-AA800', - b'\xf1\x00CN ESC \t 105 \x10\x03 58910-AA800', - ], - }, - CAR.HYUNDAI_ELANTRA_HEV_2021: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00CN7HMFC AT USA LHD 1.00 1.03 99210-AA000 200819', - b'\xf1\x00CN7HMFC AT USA LHD 1.00 1.05 99210-AA000 210930', - b'\xf1\x00CN7HMFC AT USA LHD 1.00 1.07 99210-AA000 220426', - b'\xf1\x00CN7HMFC AT USA LHD 1.00 1.08 99210-AA000 220728', - b'\xf1\x00CN7HMFC AT USA LHD 1.00 1.09 99210-AA000 221108', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00CNhe SCC FHCUP 1.00 1.01 99110-BY000 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00CN7 MDPS C 1.00 1.02 56310/BY050 4CNHC102', - b'\xf1\x00CN7 MDPS C 1.00 1.03 56310/BY050 4CNHC103', - b'\xf1\x00CN7 MDPS C 1.00 1.03 56310BY050\x00 4CNHC103', - b'\xf1\x00CN7 MDPS C 1.00 1.03 56310BY0500 4CNHC103', - b'\xf1\x00CN7 MDPS C 1.00 1.04 56310BY050\x00 4CNHC104', - ], - }, - CAR.HYUNDAI_KONA_HEV: { - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00OS IEB \x01 104 \x11 58520-CM000', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00OShe SCC FNCUP 1.00 1.01 99110-CM000 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00OS MDPS C 1.00 1.00 56310CM030\x00 4OHDC100', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00OSH LKAS AT KOR LHD 1.00 1.01 95740-CM000 l31', - ], - }, - CAR.HYUNDAI_SONATA_HYBRID: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00DNhe SCC F-CUP 1.00 1.02 99110-L5000 ', - b'\xf1\x00DNhe SCC FHCUP 1.00 1.00 99110-L5000 ', - b'\xf1\x00DNhe SCC FHCUP 1.00 1.02 99110-L5000 ', - ], - (Ecu.eps, 0x7d4, None): [ - b'\xf1\x00DN8 MDPS C 1.00 1.01 56310-L5000 4DNHC101', - b'\xf1\x00DN8 MDPS C 1.00 1.02 56310-L5450 4DNHC102', - b'\xf1\x00DN8 MDPS C 1.00 1.02 56310-L5500 4DNHC102', - b'\xf1\x00DN8 MDPS C 1.00 1.03 56310-L5450 4DNHC103', - b'\xf1\x00DN8 MDPS C 1.00 1.03 56310L5450\x00 4DNHC104', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00DN8HMFC AT KOR LHD 1.00 1.03 99211-L1000 190705', - b'\xf1\x00DN8HMFC AT USA LHD 1.00 1.04 99211-L1000 191016', - b'\xf1\x00DN8HMFC AT USA LHD 1.00 1.05 99211-L1000 201109', - b'\xf1\x00DN8HMFC AT USA LHD 1.00 1.06 99211-L1000 210325', - b'\xf1\x00DN8HMFC AT USA LHD 1.00 1.07 99211-L1000 211223', - ], - }, - CAR.KIA_SORENTO: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00UMP LKAS AT KOR LHD 1.00 1.00 95740-C5550 S30', - b'\xf1\x00UMP LKAS AT USA LHD 1.00 1.00 95740-C6550 d00', - b'\xf1\x00UMP LKAS AT USA LHD 1.01 1.01 95740-C6550 d01', - ], - (Ecu.abs, 0x7d1, None): [ - b'\xf1\x00UM ESC \x02 12 \x18\x05\x05 58910-C6300', - b'\xf1\x00UM ESC \x0c 12 \x18\x05\x06 58910-C6330', - b'\xf1\x00UM ESC \x13 12 \x17\x07\x05 58910-C5320', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00UM__ SCC F-CUP 1.00 1.00 96400-C5500 ', - b'\xf1\x00UM__ SCC F-CUP 1.00 1.00 96400-C6500 ', - ], - }, - CAR.KIA_EV6: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00CV1_ RDR ----- 1.00 1.01 99110-CV000 ', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00CV1 MFC AT EUR LHD 1.00 1.05 99210-CV000 211027', - b'\xf1\x00CV1 MFC AT EUR LHD 1.00 1.06 99210-CV000 220328', - b'\xf1\x00CV1 MFC AT EUR RHD 1.00 1.00 99210-CV100 220630', - b'\xf1\x00CV1 MFC AT KOR LHD 1.00 1.04 99210-CV000 210823', - b'\xf1\x00CV1 MFC AT KOR LHD 1.00 1.05 99210-CV000 211027', - b'\xf1\x00CV1 MFC AT KOR LHD 1.00 1.06 99210-CV000 220328', - b'\xf1\x00CV1 MFC AT USA LHD 1.00 1.00 99210-CV100 220630', - b'\xf1\x00CV1 MFC AT USA LHD 1.00 1.00 99210-CV200 230510', - b'\xf1\x00CV1 MFC AT USA LHD 1.00 1.05 99210-CV000 211027', - b'\xf1\x00CV1 MFC AT USA LHD 1.00 1.06 99210-CV000 220328', - ], - }, - CAR.HYUNDAI_IONIQ_5: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00NE1_ RDR ----- 1.00 1.00 99110-GI000 ', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00NE1 MFC AT CAN LHD 1.00 1.01 99211-GI010 211007', - b'\xf1\x00NE1 MFC AT CAN LHD 1.00 1.05 99211-GI010 220614', - b'\xf1\x00NE1 MFC AT EUR LHD 1.00 1.01 99211-GI010 211007', - b'\xf1\x00NE1 MFC AT EUR LHD 1.00 1.06 99211-GI000 210813', - b'\xf1\x00NE1 MFC AT EUR LHD 1.00 1.06 99211-GI010 230110', - b'\xf1\x00NE1 MFC AT EUR RHD 1.00 1.01 99211-GI010 211007', - b'\xf1\x00NE1 MFC AT EUR RHD 1.00 1.02 99211-GI010 211206', - b'\xf1\x00NE1 MFC AT KOR LHD 1.00 1.00 99211-GI020 230719', - b'\xf1\x00NE1 MFC AT KOR LHD 1.00 1.05 99211-GI010 220614', - b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.00 99211-GI020 230719', - b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.01 99211-GI010 211007', - b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.02 99211-GI010 211206', - b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.03 99211-GI010 220401', - b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.05 99211-GI010 220614', - b'\xf1\x00NE1 MFC AT USA LHD 1.00 1.06 99211-GI010 230110', - ], - }, - CAR.HYUNDAI_IONIQ_6: { - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00CE__ RDR ----- 1.00 1.01 99110-KL000 ', - ], - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00CE MFC AT CAN LHD 1.00 1.04 99211-KL000 221213', - b'\xf1\x00CE MFC AT EUR LHD 1.00 1.03 99211-KL000 221011', - b'\xf1\x00CE MFC AT EUR LHD 1.00 1.04 99211-KL000 221213', - b'\xf1\x00CE MFC AT USA LHD 1.00 1.04 99211-KL000 221213', - ], - }, - CAR.HYUNDAI_TUCSON_4TH_GEN: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00NX4 FR_CMR AT CAN LHD 1.00 1.00 99211-N9260 14Y', - b'\xf1\x00NX4 FR_CMR AT CAN LHD 1.00 1.01 99211-N9100 14A', - b'\xf1\x00NX4 FR_CMR AT EUR LHD 1.00 1.00 99211-N9220 14K', - b'\xf1\x00NX4 FR_CMR AT EUR LHD 1.00 2.02 99211-N9000 14E', - b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-N9210 14G', - b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-N9220 14K', - b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-N9240 14Q', - b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-N9250 14W', - b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-N9260 14Y', - b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.01 99211-N9100 14A', - b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.01 99211-N9240 14T', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00NX4__ 1.00 1.00 99110-N9100 ', - b'\xf1\x00NX4__ 1.00 1.01 99110-N9000 ', - b'\xf1\x00NX4__ 1.00 1.02 99110-N9000 ', - b'\xf1\x00NX4__ 1.01 1.00 99110-N9100 ', - ], - }, - CAR.HYUNDAI_SANTA_CRUZ_1ST_GEN: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-CW000 14M', - b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-CW010 14X', - b'\xf1\x00NX4 FR_CMR AT USA LHD 1.00 1.00 99211-CW020 14Z', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00NX4__ 1.00 1.00 99110-K5000 ', - b'\xf1\x00NX4__ 1.01 1.00 99110-K5000 ', - ], - }, - CAR.KIA_SPORTAGE_5TH_GEN: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00NQ5 FR_CMR AT AUS RHD 1.00 1.00 99211-P1040 663', - b'\xf1\x00NQ5 FR_CMR AT EUR LHD 1.00 1.00 99211-P1040 663', - b'\xf1\x00NQ5 FR_CMR AT GEN LHD 1.00 1.00 99211-P1060 665', - b'\xf1\x00NQ5 FR_CMR AT USA LHD 1.00 1.00 99211-P1030 662', - b'\xf1\x00NQ5 FR_CMR AT USA LHD 1.00 1.00 99211-P1040 663', - b'\xf1\x00NQ5 FR_CMR AT USA LHD 1.00 1.00 99211-P1060 665', - b'\xf1\x00NQ5 FR_CMR AT USA LHD 1.00 1.00 99211-P1070 690', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00NQ5__ 1.00 1.02 99110-P1000 ', - b'\xf1\x00NQ5__ 1.00 1.03 99110-CH000 ', - b'\xf1\x00NQ5__ 1.00 1.03 99110-P1000 ', - b'\xf1\x00NQ5__ 1.01 1.03 99110-CH000 ', - b'\xf1\x00NQ5__ 1.01 1.03 99110-P1000 ', - ], - }, - CAR.GENESIS_GV70_1ST_GEN: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00JK1 MFC AT USA LHD 1.00 1.01 99211-AR200 220125', - b'\xf1\x00JK1 MFC AT USA LHD 1.00 1.01 99211-AR300 220125', - b'\xf1\x00JK1 MFC AT USA LHD 1.00 1.04 99211-AR000 210204', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00JK1_ SCC FHCUP 1.00 1.00 99110-AR200 ', - b'\xf1\x00JK1_ SCC FHCUP 1.00 1.00 99110-AR300 ', - b'\xf1\x00JK1_ SCC FHCUP 1.00 1.02 99110-AR000 ', - ], - }, - CAR.GENESIS_GV60_EV_1ST_GEN: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00JW1 MFC AT USA LHD 1.00 1.02 99211-CU000 211215', - b'\xf1\x00JW1 MFC AT USA LHD 1.00 1.02 99211-CU100 211215', - b'\xf1\x00JW1 MFC AT USA LHD 1.00 1.03 99211-CU000 221118', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00JW1_ RDR ----- 1.00 1.00 99110-CU000 ', - ], - }, - CAR.KIA_SORENTO_4TH_GEN: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00MQ4 MFC AT USA LHD 1.00 1.00 99210-R5100 221019', - b'\xf1\x00MQ4 MFC AT USA LHD 1.00 1.03 99210-R5000 200903', - b'\xf1\x00MQ4 MFC AT USA LHD 1.00 1.05 99210-R5000 210623', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00MQ4_ SCC F-CUP 1.00 1.06 99110-P2000 ', - b'\xf1\x00MQ4_ SCC FHCUP 1.00 1.00 99110-R5000 ', - b'\xf1\x00MQ4_ SCC FHCUP 1.00 1.06 99110-P2000 ', - b'\xf1\x00MQ4_ SCC FHCUP 1.00 1.08 99110-P2000 ', - ], - }, - CAR.KIA_SORENTO_HEV_4TH_GEN: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00MQ4HMFC AT KOR LHD 1.00 1.04 99210-P2000 200330', - b'\xf1\x00MQ4HMFC AT KOR LHD 1.00 1.12 99210-P2000 230331', - b'\xf1\x00MQ4HMFC AT USA LHD 1.00 1.10 99210-P2000 210406', - b'\xf1\x00MQ4HMFC AT USA LHD 1.00 1.11 99210-P2000 211217', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00MQhe SCC FHCUP 1.00 1.04 99110-P4000 ', - b'\xf1\x00MQhe SCC FHCUP 1.00 1.06 99110-P4000 ', - b'\xf1\x00MQhe SCC FHCUP 1.00 1.07 99110-P4000 ', - ], - }, - CAR.KIA_NIRO_HEV_2ND_GEN: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00SG2HMFC AT USA LHD 1.01 1.08 99211-AT000 220531', - b'\xf1\x00SG2HMFC AT USA LHD 1.01 1.09 99211-AT000 220801', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00SG2_ RDR ----- 1.00 1.01 99110-AT000 ', - ], - }, - CAR.GENESIS_GV80: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00JX1 MFC AT USA LHD 1.00 1.02 99211-T6110 220513', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00JX1_ SCC FHCUP 1.00 1.01 99110-T6100 ', - ], - }, - CAR.KIA_CARNIVAL_4TH_GEN: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00KA4 MFC AT EUR LHD 1.00 1.06 99210-R0000 220221', - b'\xf1\x00KA4 MFC AT KOR LHD 1.00 1.06 99210-R0000 220221', - b'\xf1\x00KA4 MFC AT USA LHD 1.00 1.00 99210-R0100 230105', - b'\xf1\x00KA4 MFC AT USA LHD 1.00 1.01 99210-R0100 230710', - b'\xf1\x00KA4 MFC AT USA LHD 1.00 1.05 99210-R0000 201221', - b'\xf1\x00KA4 MFC AT USA LHD 1.00 1.06 99210-R0000 220221', - b'\xf1\x00KA4CMFC AT CHN LHD 1.00 1.01 99211-I4000 210525', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00KA4_ SCC F-CUP 1.00 1.03 99110-R0000 ', - b'\xf1\x00KA4_ SCC FHCUP 1.00 1.00 99110-R0100 ', - b'\xf1\x00KA4_ SCC FHCUP 1.00 1.03 99110-R0000 ', - b'\xf1\x00KA4c SCC FHCUP 1.00 1.01 99110-I4000 ', - ], - }, - CAR.KIA_K8_HEV_1ST_GEN: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00GL3HMFC AT KOR LHD 1.00 1.03 99211-L8000 210907', - b'\xf1\x00GL3HMFC AT KOR LHD 1.00 1.04 99211-L8000 230207', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00GL3_ RDR ----- 1.00 1.02 99110-L8000 ', - ], - }, - CAR.HYUNDAI_STARIA_4TH_GEN: { - (Ecu.fwdCamera, 0x7c4, None): [ - b'\xf1\x00US4 MFC AT KOR LHD 1.00 1.06 99211-CG000 230524', - ], - (Ecu.fwdRadar, 0x7d0, None): [ - b'\xf1\x00US4_ RDR ----- 1.00 1.00 99110-CG000 ', - ], - }, -} diff --git a/car/hyundai/hyundaican.py b/car/hyundai/hyundaican.py deleted file mode 100644 index b4b951f89e..0000000000 --- a/car/hyundai/hyundaican.py +++ /dev/null @@ -1,213 +0,0 @@ -import crcmod -from openpilot.selfdrive.car.hyundai.values import CAR, HyundaiFlags - -hyundai_checksum = crcmod.mkCrcFun(0x11D, initCrc=0xFD, rev=False, xorOut=0xdf) - -def create_lkas11(packer, frame, CP, apply_steer, steer_req, - torque_fault, lkas11, sys_warning, sys_state, enabled, - left_lane, right_lane, - left_lane_depart, right_lane_depart): - values = {s: lkas11[s] for s in [ - "CF_Lkas_LdwsActivemode", - "CF_Lkas_LdwsSysState", - "CF_Lkas_SysWarning", - "CF_Lkas_LdwsLHWarning", - "CF_Lkas_LdwsRHWarning", - "CF_Lkas_HbaLamp", - "CF_Lkas_FcwBasReq", - "CF_Lkas_HbaSysState", - "CF_Lkas_FcwOpt", - "CF_Lkas_HbaOpt", - "CF_Lkas_FcwSysState", - "CF_Lkas_FcwCollisionWarning", - "CF_Lkas_FusionState", - "CF_Lkas_FcwOpt_USM", - "CF_Lkas_LdwsOpt_USM", - ]} - values["CF_Lkas_LdwsSysState"] = sys_state - values["CF_Lkas_SysWarning"] = 3 if sys_warning else 0 - values["CF_Lkas_LdwsLHWarning"] = left_lane_depart - values["CF_Lkas_LdwsRHWarning"] = right_lane_depart - values["CR_Lkas_StrToqReq"] = apply_steer - values["CF_Lkas_ActToi"] = steer_req - values["CF_Lkas_ToiFlt"] = torque_fault # seems to allow actuation on CR_Lkas_StrToqReq - values["CF_Lkas_MsgCount"] = frame % 0x10 - - if CP.carFingerprint in (CAR.HYUNDAI_SONATA, CAR.HYUNDAI_PALISADE, CAR.KIA_NIRO_EV, CAR.KIA_NIRO_HEV_2021, CAR.HYUNDAI_SANTA_FE, - CAR.HYUNDAI_IONIQ_EV_2020, CAR.HYUNDAI_IONIQ_PHEV, CAR.KIA_SELTOS, CAR.HYUNDAI_ELANTRA_2021, CAR.GENESIS_G70_2020, - CAR.HYUNDAI_ELANTRA_HEV_2021, CAR.HYUNDAI_SONATA_HYBRID, CAR.HYUNDAI_KONA_EV, CAR.HYUNDAI_KONA_HEV, CAR.HYUNDAI_KONA_EV_2022, - CAR.HYUNDAI_SANTA_FE_2022, CAR.KIA_K5_2021, CAR.HYUNDAI_IONIQ_HEV_2022, CAR.HYUNDAI_SANTA_FE_HEV_2022, - CAR.HYUNDAI_SANTA_FE_PHEV_2022, CAR.KIA_STINGER_2022, CAR.KIA_K5_HEV_2020, CAR.KIA_CEED, - CAR.HYUNDAI_AZERA_6TH_GEN, CAR.HYUNDAI_AZERA_HEV_6TH_GEN, CAR.HYUNDAI_CUSTIN_1ST_GEN): - values["CF_Lkas_LdwsActivemode"] = int(left_lane) + (int(right_lane) << 1) - values["CF_Lkas_LdwsOpt_USM"] = 2 - - # FcwOpt_USM 5 = Orange blinking car + lanes - # FcwOpt_USM 4 = Orange car + lanes - # FcwOpt_USM 3 = Green blinking car + lanes - # FcwOpt_USM 2 = Green car + lanes - # FcwOpt_USM 1 = White car + lanes - # FcwOpt_USM 0 = No car + lanes - values["CF_Lkas_FcwOpt_USM"] = 2 if enabled else 1 - - # SysWarning 4 = keep hands on wheel - # SysWarning 5 = keep hands on wheel (red) - # SysWarning 6 = keep hands on wheel (red) + beep - # Note: the warning is hidden while the blinkers are on - values["CF_Lkas_SysWarning"] = 4 if sys_warning else 0 - - # Likely cars lacking the ability to show individual lane lines in the dash - elif CP.carFingerprint in (CAR.KIA_OPTIMA_G4, CAR.KIA_OPTIMA_G4_FL): - # SysWarning 4 = keep hands on wheel + beep - values["CF_Lkas_SysWarning"] = 4 if sys_warning else 0 - - # SysState 0 = no icons - # SysState 1-2 = white car + lanes - # SysState 3 = green car + lanes, green steering wheel - # SysState 4 = green car + lanes - values["CF_Lkas_LdwsSysState"] = 3 if enabled else 1 - values["CF_Lkas_LdwsOpt_USM"] = 2 # non-2 changes above SysState definition - - # these have no effect - values["CF_Lkas_LdwsActivemode"] = 0 - values["CF_Lkas_FcwOpt_USM"] = 0 - - elif CP.carFingerprint == CAR.HYUNDAI_GENESIS: - # This field is actually LdwsActivemode - # Genesis and Optima fault when forwarding while engaged - values["CF_Lkas_LdwsActivemode"] = 2 - - dat = packer.make_can_msg("LKAS11", 0, values)[2] - - if CP.flags & HyundaiFlags.CHECKSUM_CRC8: - # CRC Checksum as seen on 2019 Hyundai Santa Fe - dat = dat[:6] + dat[7:8] - checksum = hyundai_checksum(dat) - elif CP.flags & HyundaiFlags.CHECKSUM_6B: - # Checksum of first 6 Bytes, as seen on 2018 Kia Sorento - checksum = sum(dat[:6]) % 256 - else: - # Checksum of first 6 Bytes and last Byte as seen on 2018 Kia Stinger - checksum = (sum(dat[:6]) + dat[7]) % 256 - - values["CF_Lkas_Chksum"] = checksum - - return packer.make_can_msg("LKAS11", 0, values) - - -def create_clu11(packer, frame, clu11, button, CP): - values = {s: clu11[s] for s in [ - "CF_Clu_CruiseSwState", - "CF_Clu_CruiseSwMain", - "CF_Clu_SldMainSW", - "CF_Clu_ParityBit1", - "CF_Clu_VanzDecimal", - "CF_Clu_Vanz", - "CF_Clu_SPEED_UNIT", - "CF_Clu_DetentOut", - "CF_Clu_RheostatLevel", - "CF_Clu_CluInfo", - "CF_Clu_AmpInfo", - "CF_Clu_AliveCnt1", - ]} - values["CF_Clu_CruiseSwState"] = button - values["CF_Clu_AliveCnt1"] = frame % 0x10 - # send buttons to camera on camera-scc based cars - bus = 2 if CP.flags & HyundaiFlags.CAMERA_SCC else 0 - return packer.make_can_msg("CLU11", bus, values) - - -def create_lfahda_mfc(packer, enabled, hda_set_speed=0): - values = { - "LFA_Icon_State": 2 if enabled else 0, - "HDA_Active": 1 if hda_set_speed else 0, - "HDA_Icon_State": 2 if hda_set_speed else 0, - "HDA_VSetReq": hda_set_speed, - } - return packer.make_can_msg("LFAHDA_MFC", 0, values) - -def create_acc_commands(packer, enabled, accel, upper_jerk, idx, hud_control, set_speed, stopping, long_override, use_fca): - commands = [] - - scc11_values = { - "MainMode_ACC": 1, - "TauGapSet": hud_control.leadDistanceBars, - "VSetDis": set_speed if enabled else 0, - "AliveCounterACC": idx % 0x10, - "ObjValid": 1, # close lead makes controls tighter - "ACC_ObjStatus": 1, # close lead makes controls tighter - "ACC_ObjLatPos": 0, - "ACC_ObjRelSpd": 0, - "ACC_ObjDist": 1, # close lead makes controls tighter - } - commands.append(packer.make_can_msg("SCC11", 0, scc11_values)) - - scc12_values = { - "ACCMode": 2 if enabled and long_override else 1 if enabled else 0, - "StopReq": 1 if stopping else 0, - "aReqRaw": accel, - "aReqValue": accel, # stock ramps up and down respecting jerk limit until it reaches aReqRaw - "CR_VSM_Alive": idx % 0xF, - } - - # show AEB disabled indicator on dash with SCC12 if not sending FCA messages. - # these signals also prevent a TCS fault on non-FCA cars with alpha longitudinal - if not use_fca: - scc12_values["CF_VSM_ConfMode"] = 1 - scc12_values["AEB_Status"] = 1 # AEB disabled - - scc12_dat = packer.make_can_msg("SCC12", 0, scc12_values)[2] - scc12_values["CR_VSM_ChkSum"] = 0x10 - sum(sum(divmod(i, 16)) for i in scc12_dat) % 0x10 - - commands.append(packer.make_can_msg("SCC12", 0, scc12_values)) - - scc14_values = { - "ComfortBandUpper": 0.0, # stock usually is 0 but sometimes uses higher values - "ComfortBandLower": 0.0, # stock usually is 0 but sometimes uses higher values - "JerkUpperLimit": upper_jerk, # stock usually is 1.0 but sometimes uses higher values - "JerkLowerLimit": 5.0, # stock usually is 0.5 but sometimes uses higher values - "ACCMode": 2 if enabled and long_override else 1 if enabled else 4, # stock will always be 4 instead of 0 after first disengage - "ObjGap": 2 if hud_control.leadVisible else 0, # 5: >30, m, 4: 25-30 m, 3: 20-25 m, 2: < 20 m, 0: no lead - } - commands.append(packer.make_can_msg("SCC14", 0, scc14_values)) - - # Only send FCA11 on cars where it exists on the bus - if use_fca: - # note that some vehicles most likely have an alternate checksum/counter definition - # https://github.com/commaai/opendbc/commit/9ddcdb22c4929baf310295e832668e6e7fcfa602 - fca11_values = { - "CR_FCA_Alive": idx % 0xF, - "PAINT1_Status": 1, - "FCA_DrvSetStatus": 1, - "FCA_Status": 1, # AEB disabled - } - fca11_dat = packer.make_can_msg("FCA11", 0, fca11_values)[2] - fca11_values["CR_FCA_ChkSum"] = hyundai_checksum(fca11_dat[:7]) - commands.append(packer.make_can_msg("FCA11", 0, fca11_values)) - - return commands - -def create_acc_opt(packer): - commands = [] - - scc13_values = { - "SCCDrvModeRValue": 2, - "SCC_Equip": 1, - "Lead_Veh_Dep_Alert_USM": 2, - } - commands.append(packer.make_can_msg("SCC13", 0, scc13_values)) - - # TODO: this needs to be detected and conditionally sent on unsupported long cars - fca12_values = { - "FCA_DrvSetState": 2, - "FCA_USM": 1, # AEB disabled - } - commands.append(packer.make_can_msg("FCA12", 0, fca12_values)) - - return commands - -def create_frt_radar_opt(packer): - frt_radar11_values = { - "CF_FCA_Equip_Front_Radar": 1, - } - return packer.make_can_msg("FRT_RADAR11", 0, frt_radar11_values) diff --git a/car/hyundai/hyundaicanfd.py b/car/hyundai/hyundaicanfd.py deleted file mode 100644 index 54804f94fd..0000000000 --- a/car/hyundai/hyundaicanfd.py +++ /dev/null @@ -1,223 +0,0 @@ -from openpilot.common.numpy_fast import clip -from openpilot.selfdrive.car import CanBusBase -from openpilot.selfdrive.car.hyundai.values import HyundaiFlags - - -class CanBus(CanBusBase): - def __init__(self, CP, hda2=None, fingerprint=None) -> None: - super().__init__(CP, fingerprint) - - if hda2 is None: - assert CP is not None - hda2 = CP.flags & HyundaiFlags.CANFD_HDA2.value - - # On the CAN-FD platforms, the LKAS camera is on both A-CAN and E-CAN. HDA2 cars - # have a different harness than the HDA1 and non-HDA variants in order to split - # a different bus, since the steering is done by different ECUs. - self._a, self._e = 1, 0 - if hda2: - self._a, self._e = 0, 1 - - self._a += self.offset - self._e += self.offset - self._cam = 2 + self.offset - - @property - def ECAN(self): - return self._e - - @property - def ACAN(self): - return self._a - - @property - def CAM(self): - return self._cam - - -def create_steering_messages(packer, CP, CAN, enabled, lat_active, apply_steer): - - ret = [] - - values = { - "LKA_MODE": 2, - "LKA_ICON": 2 if enabled else 1, - "TORQUE_REQUEST": apply_steer, - "LKA_ASSIST": 0, - "STEER_REQ": 1 if lat_active else 0, - "STEER_MODE": 0, - "HAS_LANE_SAFETY": 0, # hide LKAS settings - "NEW_SIGNAL_1": 0, - "NEW_SIGNAL_2": 0, - } - - if CP.flags & HyundaiFlags.CANFD_HDA2: - hda2_lkas_msg = "LKAS_ALT" if CP.flags & HyundaiFlags.CANFD_HDA2_ALT_STEERING else "LKAS" - if CP.openpilotLongitudinalControl: - ret.append(packer.make_can_msg("LFA", CAN.ECAN, values)) - ret.append(packer.make_can_msg(hda2_lkas_msg, CAN.ACAN, values)) - else: - ret.append(packer.make_can_msg("LFA", CAN.ECAN, values)) - - return ret - -def create_suppress_lfa(packer, CAN, hda2_lfa_block_msg, hda2_alt_steering): - suppress_msg = "CAM_0x362" if hda2_alt_steering else "CAM_0x2a4" - msg_bytes = 32 if hda2_alt_steering else 24 - - values = {f"BYTE{i}": hda2_lfa_block_msg[f"BYTE{i}"] for i in range(3, msg_bytes) if i != 7} - values["COUNTER"] = hda2_lfa_block_msg["COUNTER"] - values["SET_ME_0"] = 0 - values["SET_ME_0_2"] = 0 - values["LEFT_LANE_LINE"] = 0 - values["RIGHT_LANE_LINE"] = 0 - return packer.make_can_msg(suppress_msg, CAN.ACAN, values) - -def create_buttons(packer, CP, CAN, cnt, btn): - values = { - "COUNTER": cnt, - "SET_ME_1": 1, - "CRUISE_BUTTONS": btn, - } - - bus = CAN.ECAN if CP.flags & HyundaiFlags.CANFD_HDA2 else CAN.CAM - return packer.make_can_msg("CRUISE_BUTTONS", bus, values) - -def create_acc_cancel(packer, CP, CAN, cruise_info_copy): - # TODO: why do we copy different values here? - if CP.flags & HyundaiFlags.CANFD_CAMERA_SCC.value: - values = {s: cruise_info_copy[s] for s in [ - "COUNTER", - "CHECKSUM", - "NEW_SIGNAL_1", - "MainMode_ACC", - "ACCMode", - "ZEROS_9", - "CRUISE_STANDSTILL", - "ZEROS_5", - "DISTANCE_SETTING", - "VSetDis", - ]} - else: - values = {s: cruise_info_copy[s] for s in [ - "COUNTER", - "CHECKSUM", - "ACCMode", - "VSetDis", - "CRUISE_STANDSTILL", - ]} - values.update({ - "ACCMode": 4, - "aReqRaw": 0.0, - "aReqValue": 0.0, - }) - return packer.make_can_msg("SCC_CONTROL", CAN.ECAN, values) - -def create_lfahda_cluster(packer, CAN, enabled): - values = { - "HDA_ICON": 1 if enabled else 0, - "LFA_ICON": 2 if enabled else 0, - } - return packer.make_can_msg("LFAHDA_CLUSTER", CAN.ECAN, values) - - -def create_acc_control(packer, CAN, enabled, accel_last, accel, stopping, gas_override, set_speed, hud_control): - jerk = 5 - jn = jerk / 50 - if not enabled or gas_override: - a_val, a_raw = 0, 0 - else: - a_raw = accel - a_val = clip(accel, accel_last - jn, accel_last + jn) - - values = { - "ACCMode": 0 if not enabled else (2 if gas_override else 1), - "MainMode_ACC": 1, - "StopReq": 1 if stopping else 0, - "aReqValue": a_val, - "aReqRaw": a_raw, - "VSetDis": set_speed, - "JerkLowerLimit": jerk if enabled else 1, - "JerkUpperLimit": 3.0, - - "ACC_ObjDist": 1, - "ObjValid": 0, - "OBJ_STATUS": 2, - "SET_ME_2": 0x4, - "SET_ME_3": 0x3, - "SET_ME_TMP_64": 0x64, - "DISTANCE_SETTING": hud_control.leadDistanceBars, - } - - return packer.make_can_msg("SCC_CONTROL", CAN.ECAN, values) - - -def create_spas_messages(packer, CAN, frame, left_blink, right_blink): - ret = [] - - values = { - } - ret.append(packer.make_can_msg("SPAS1", CAN.ECAN, values)) - - blink = 0 - if left_blink: - blink = 3 - elif right_blink: - blink = 4 - values = { - "BLINKER_CONTROL": blink, - } - ret.append(packer.make_can_msg("SPAS2", CAN.ECAN, values)) - - return ret - - -def create_adrv_messages(packer, CAN, frame): - # messages needed to car happy after disabling - # the ADAS Driving ECU to do longitudinal control - - ret = [] - - values = { - } - ret.append(packer.make_can_msg("ADRV_0x51", CAN.ACAN, values)) - - if frame % 2 == 0: - values = { - 'AEB_SETTING': 0x1, # show AEB disabled icon - 'SET_ME_2': 0x2, - 'SET_ME_FF': 0xff, - 'SET_ME_FC': 0xfc, - 'SET_ME_9': 0x9, - } - ret.append(packer.make_can_msg("ADRV_0x160", CAN.ECAN, values)) - - if frame % 5 == 0: - values = { - 'SET_ME_1C': 0x1c, - 'SET_ME_FF': 0xff, - 'SET_ME_TMP_F': 0xf, - 'SET_ME_TMP_F_2': 0xf, - } - ret.append(packer.make_can_msg("ADRV_0x1ea", CAN.ECAN, values)) - - values = { - 'SET_ME_E1': 0xe1, - 'SET_ME_3A': 0x3a, - } - ret.append(packer.make_can_msg("ADRV_0x200", CAN.ECAN, values)) - - if frame % 20 == 0: - values = { - 'SET_ME_15': 0x15, - } - ret.append(packer.make_can_msg("ADRV_0x345", CAN.ECAN, values)) - - if frame % 100 == 0: - values = { - 'SET_ME_22': 0x22, - 'SET_ME_41': 0x41, - } - ret.append(packer.make_can_msg("ADRV_0x1da", CAN.ECAN, values)) - - return ret diff --git a/car/hyundai/interface.py b/car/hyundai/interface.py deleted file mode 100644 index 22c54bce6b..0000000000 --- a/car/hyundai/interface.py +++ /dev/null @@ -1,180 +0,0 @@ -from cereal import car -from panda import Panda -from openpilot.selfdrive.car.hyundai.hyundaicanfd import CanBus -from openpilot.selfdrive.car.hyundai.values import HyundaiFlags, CAR, DBC, CANFD_CAR, CAMERA_SCC_CAR, CANFD_RADAR_SCC_CAR, \ - CANFD_UNSUPPORTED_LONGITUDINAL_CAR, EV_CAR, HYBRID_CAR, LEGACY_SAFETY_MODE_CAR, \ - UNSUPPORTED_LONGITUDINAL_CAR, Buttons -from openpilot.selfdrive.car.hyundai.radar_interface import RADAR_START_ADDR -from openpilot.selfdrive.car import create_button_events, get_safety_config -from openpilot.selfdrive.car.interfaces import CarInterfaceBase -from openpilot.selfdrive.car.disable_ecu import disable_ecu - -Ecu = car.CarParams.Ecu -ButtonType = car.CarState.ButtonEvent.Type -EventName = car.CarEvent.EventName -ENABLE_BUTTONS = (Buttons.RES_ACCEL, Buttons.SET_DECEL, Buttons.CANCEL) -BUTTONS_DICT = {Buttons.RES_ACCEL: ButtonType.accelCruise, Buttons.SET_DECEL: ButtonType.decelCruise, - Buttons.GAP_DIST: ButtonType.gapAdjustCruise, Buttons.CANCEL: ButtonType.cancel} - - -class CarInterface(CarInterfaceBase): - @staticmethod - def _get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs): - ret.carName = "hyundai" - ret.radarUnavailable = RADAR_START_ADDR not in fingerprint[1] or DBC[ret.carFingerprint]["radar"] is None - - # These cars have been put into dashcam only due to both a lack of users and test coverage. - # These cars likely still work fine. Once a user confirms each car works and a test route is - # added to selfdrive/car/tests/routes.py, we can remove it from this list. - # FIXME: the Optima Hybrid 2017 uses a different SCC12 checksum - ret.dashcamOnly = candidate in {CAR.KIA_OPTIMA_H, } - - hda2 = Ecu.adas in [fw.ecu for fw in car_fw] - CAN = CanBus(None, hda2, fingerprint) - - if candidate in CANFD_CAR: - # detect if car is hybrid - if 0x105 in fingerprint[CAN.ECAN]: - ret.flags |= HyundaiFlags.HYBRID.value - elif candidate in EV_CAR: - ret.flags |= HyundaiFlags.EV.value - - # detect HDA2 with ADAS Driving ECU - if hda2: - ret.flags |= HyundaiFlags.CANFD_HDA2.value - if 0x110 in fingerprint[CAN.CAM]: - ret.flags |= HyundaiFlags.CANFD_HDA2_ALT_STEERING.value - else: - # non-HDA2 - if 0x1cf not in fingerprint[CAN.ECAN]: - ret.flags |= HyundaiFlags.CANFD_ALT_BUTTONS.value - # ICE cars do not have 0x130; GEARS message on 0x40 or 0x70 instead - if 0x130 not in fingerprint[CAN.ECAN]: - if 0x40 not in fingerprint[CAN.ECAN]: - ret.flags |= HyundaiFlags.CANFD_ALT_GEARS_2.value - else: - ret.flags |= HyundaiFlags.CANFD_ALT_GEARS.value - if candidate not in CANFD_RADAR_SCC_CAR: - ret.flags |= HyundaiFlags.CANFD_CAMERA_SCC.value - else: - # TODO: detect EV and hybrid - if candidate in HYBRID_CAR: - ret.flags |= HyundaiFlags.HYBRID.value - elif candidate in EV_CAR: - ret.flags |= HyundaiFlags.EV.value - - # Send LFA message on cars with HDA - if 0x485 in fingerprint[2]: - ret.flags |= HyundaiFlags.SEND_LFA.value - - # These cars use the FCA11 message for the AEB and FCW signals, all others use SCC12 - if 0x38d in fingerprint[0] or 0x38d in fingerprint[2]: - ret.flags |= HyundaiFlags.USE_FCA.value - - ret.steerActuatorDelay = 0.1 # Default delay - ret.steerLimitTimer = 0.4 - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) - - if candidate == CAR.KIA_OPTIMA_G4_FL: - ret.steerActuatorDelay = 0.2 - - # *** longitudinal control *** - if candidate in CANFD_CAR: - ret.longitudinalTuning.kpV = [0.1] - ret.longitudinalTuning.kiV = [0.0] - ret.experimentalLongitudinalAvailable = candidate not in (CANFD_UNSUPPORTED_LONGITUDINAL_CAR | CANFD_RADAR_SCC_CAR) - else: - ret.longitudinalTuning.kpV = [0.5] - ret.longitudinalTuning.kiV = [0.0] - ret.experimentalLongitudinalAvailable = candidate not in (UNSUPPORTED_LONGITUDINAL_CAR | CAMERA_SCC_CAR) - ret.openpilotLongitudinalControl = experimental_long and ret.experimentalLongitudinalAvailable - ret.pcmCruise = not ret.openpilotLongitudinalControl - - ret.stoppingControl = True - ret.startingState = True - ret.vEgoStarting = 0.1 - ret.startAccel = 1.0 - ret.longitudinalActuatorDelayLowerBound = 0.5 - ret.longitudinalActuatorDelayUpperBound = 0.5 - - # *** feature detection *** - if candidate in CANFD_CAR: - ret.enableBsm = 0x1e5 in fingerprint[CAN.ECAN] - else: - ret.enableBsm = 0x58b in fingerprint[0] - - # *** panda safety config *** - if candidate in CANFD_CAR: - cfgs = [get_safety_config(car.CarParams.SafetyModel.hyundaiCanfd), ] - if CAN.ECAN >= 4: - cfgs.insert(0, get_safety_config(car.CarParams.SafetyModel.noOutput)) - ret.safetyConfigs = cfgs - - if ret.flags & HyundaiFlags.CANFD_HDA2: - ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_HYUNDAI_CANFD_HDA2 - if ret.flags & HyundaiFlags.CANFD_HDA2_ALT_STEERING: - ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_HYUNDAI_CANFD_HDA2_ALT_STEERING - if ret.flags & HyundaiFlags.CANFD_ALT_BUTTONS: - ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_HYUNDAI_CANFD_ALT_BUTTONS - if ret.flags & HyundaiFlags.CANFD_CAMERA_SCC: - ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_HYUNDAI_CAMERA_SCC - else: - if candidate in LEGACY_SAFETY_MODE_CAR: - # these cars require a special panda safety mode due to missing counters and checksums in the messages - ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.hyundaiLegacy)] - else: - ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.hyundai, 0)] - - if candidate in CAMERA_SCC_CAR: - ret.safetyConfigs[0].safetyParam |= Panda.FLAG_HYUNDAI_CAMERA_SCC - - if ret.openpilotLongitudinalControl: - ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_HYUNDAI_LONG - if ret.flags & HyundaiFlags.HYBRID: - ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_HYUNDAI_HYBRID_GAS - elif ret.flags & HyundaiFlags.EV: - ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_HYUNDAI_EV_GAS - - if candidate in (CAR.HYUNDAI_KONA, CAR.HYUNDAI_KONA_EV, CAR.HYUNDAI_KONA_HEV, CAR.HYUNDAI_KONA_EV_2022): - ret.flags |= HyundaiFlags.ALT_LIMITS.value - ret.safetyConfigs[-1].safetyParam |= Panda.FLAG_HYUNDAI_ALT_LIMITS - - ret.centerToFront = ret.wheelbase * 0.4 - - return ret - - @staticmethod - def init(CP, logcan, sendcan): - if CP.openpilotLongitudinalControl and not (CP.flags & HyundaiFlags.CANFD_CAMERA_SCC.value): - addr, bus = 0x7d0, 0 - if CP.flags & HyundaiFlags.CANFD_HDA2.value: - addr, bus = 0x730, CanBus(CP).ECAN - disable_ecu(logcan, sendcan, bus=bus, addr=addr, com_cont_req=b'\x28\x83\x01') - - # for blinkers - if CP.flags & HyundaiFlags.ENABLE_BLINKERS: - disable_ecu(logcan, sendcan, bus=CanBus(CP).ECAN, addr=0x7B1, com_cont_req=b'\x28\x83\x01') - - def _update(self, c): - ret = self.CS.update(self.cp, self.cp_cam) - - if self.CS.CP.openpilotLongitudinalControl: - ret.buttonEvents = create_button_events(self.CS.cruise_buttons[-1], self.CS.prev_cruise_buttons, BUTTONS_DICT) - - # On some newer model years, the CANCEL button acts as a pause/resume button based on the PCM state - # To avoid re-engaging when openpilot cancels, check user engagement intention via buttons - # Main button also can trigger an engagement on these cars - allow_enable = any(btn in ENABLE_BUTTONS for btn in self.CS.cruise_buttons) or any(self.CS.main_buttons) - events = self.create_common_events(ret, pcm_enable=self.CS.CP.pcmCruise, allow_enable=allow_enable) - - # low speed steer alert hysteresis logic (only for cars with steer cut off above 10 m/s) - if ret.vEgo < (self.CP.minSteerSpeed + 2.) and self.CP.minSteerSpeed > 10.: - self.low_speed_alert = True - if ret.vEgo > (self.CP.minSteerSpeed + 4.): - self.low_speed_alert = False - if self.low_speed_alert: - events.add(car.CarEvent.EventName.belowSteerSpeed) - - ret.events = events.to_msg() - - return ret diff --git a/car/hyundai/radar_interface.py b/car/hyundai/radar_interface.py deleted file mode 100644 index 5260050986..0000000000 --- a/car/hyundai/radar_interface.py +++ /dev/null @@ -1,79 +0,0 @@ -import math - -from cereal import car -from opendbc.can.parser import CANParser -from openpilot.selfdrive.car.interfaces import RadarInterfaceBase -from openpilot.selfdrive.car.hyundai.values import DBC - -RADAR_START_ADDR = 0x500 -RADAR_MSG_COUNT = 32 - -# POC for parsing corner radars: https://github.com/commaai/openpilot/pull/24221/ - -def get_radar_can_parser(CP): - if DBC[CP.carFingerprint]['radar'] is None: - return None - - messages = [(f"RADAR_TRACK_{addr:x}", 50) for addr in range(RADAR_START_ADDR, RADAR_START_ADDR + RADAR_MSG_COUNT)] - return CANParser(DBC[CP.carFingerprint]['radar'], messages, 1) - - -class RadarInterface(RadarInterfaceBase): - def __init__(self, CP): - super().__init__(CP) - self.updated_messages = set() - self.trigger_msg = RADAR_START_ADDR + RADAR_MSG_COUNT - 1 - self.track_id = 0 - - self.radar_off_can = CP.radarUnavailable - self.rcp = get_radar_can_parser(CP) - - def update(self, can_strings): - if self.radar_off_can or (self.rcp is None): - return super().update(None) - - vls = self.rcp.update_strings(can_strings) - self.updated_messages.update(vls) - - if self.trigger_msg not in self.updated_messages: - return None - - rr = self._update(self.updated_messages) - self.updated_messages.clear() - - return rr - - def _update(self, updated_messages): - ret = car.RadarData.new_message() - if self.rcp is None: - return ret - - errors = [] - - if not self.rcp.can_valid: - errors.append("canError") - ret.errors = errors - - for addr in range(RADAR_START_ADDR, RADAR_START_ADDR + RADAR_MSG_COUNT): - msg = self.rcp.vl[f"RADAR_TRACK_{addr:x}"] - - if addr not in self.pts: - self.pts[addr] = car.RadarData.RadarPoint.new_message() - self.pts[addr].trackId = self.track_id - self.track_id += 1 - - valid = msg['STATE'] in (3, 4) - if valid: - azimuth = math.radians(msg['AZIMUTH']) - self.pts[addr].measured = True - self.pts[addr].dRel = math.cos(azimuth) * msg['LONG_DIST'] - self.pts[addr].yRel = 0.5 * -math.sin(azimuth) * msg['LONG_DIST'] - self.pts[addr].vRel = msg['REL_SPEED'] - self.pts[addr].aRel = msg['REL_ACCEL'] - self.pts[addr].yvRel = float('nan') - - else: - del self.pts[addr] - - ret.points = list(self.pts.values()) - return ret diff --git a/car/hyundai/tests/__init__.py b/car/hyundai/tests/__init__.py deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/car/hyundai/tests/print_platform_codes.py b/car/hyundai/tests/print_platform_codes.py deleted file mode 100755 index f641535678..0000000000 --- a/car/hyundai/tests/print_platform_codes.py +++ /dev/null @@ -1,22 +0,0 @@ -#!/usr/bin/env python3 -from cereal import car -from openpilot.selfdrive.car.hyundai.values import PLATFORM_CODE_ECUS, get_platform_codes -from openpilot.selfdrive.car.hyundai.fingerprints import FW_VERSIONS - -Ecu = car.CarParams.Ecu -ECU_NAME = {v: k for k, v in Ecu.schema.enumerants.items()} - -if __name__ == "__main__": - for car_model, ecus in FW_VERSIONS.items(): - print() - print(car_model) - for ecu in sorted(ecus, key=lambda x: int(x[0])): - if ecu[0] not in PLATFORM_CODE_ECUS: - continue - - platform_codes = get_platform_codes(ecus[ecu]) - codes = {code for code, _ in platform_codes} - dates = {date for _, date in platform_codes if date is not None} - print(f' (Ecu.{ECU_NAME[ecu[0]]}, {hex(ecu[1])}, {ecu[2]}):') - print(f' Codes: {codes}') - print(f' Dates: {dates}') diff --git a/car/hyundai/tests/test_hyundai.py b/car/hyundai/tests/test_hyundai.py deleted file mode 100644 index 4d31d7d15e..0000000000 --- a/car/hyundai/tests/test_hyundai.py +++ /dev/null @@ -1,218 +0,0 @@ -from hypothesis import settings, given, strategies as st - -import pytest - -from cereal import car -from openpilot.selfdrive.car.fw_versions import build_fw_dict -from openpilot.selfdrive.car.hyundai.values import CAMERA_SCC_CAR, CANFD_CAR, CAN_GEARS, CAR, CHECKSUM, DATE_FW_ECUS, \ - HYBRID_CAR, EV_CAR, FW_QUERY_CONFIG, LEGACY_SAFETY_MODE_CAR, CANFD_FUZZY_WHITELIST, \ - UNSUPPORTED_LONGITUDINAL_CAR, PLATFORM_CODE_ECUS, HYUNDAI_VERSION_REQUEST_LONG, \ - get_platform_codes -from openpilot.selfdrive.car.hyundai.fingerprints import FW_VERSIONS - -Ecu = car.CarParams.Ecu -ECU_NAME = {v: k for k, v in Ecu.schema.enumerants.items()} - -# Some platforms have date codes in a different format we don't yet parse (or are missing). -# For now, assert list of expected missing date cars -NO_DATES_PLATFORMS = { - # CAN FD - CAR.KIA_SPORTAGE_5TH_GEN, - CAR.HYUNDAI_SANTA_CRUZ_1ST_GEN, - CAR.HYUNDAI_TUCSON_4TH_GEN, - # CAN - CAR.HYUNDAI_ELANTRA, - CAR.HYUNDAI_ELANTRA_GT_I30, - CAR.KIA_CEED, - CAR.KIA_FORTE, - CAR.KIA_OPTIMA_G4, - CAR.KIA_OPTIMA_G4_FL, - CAR.KIA_SORENTO, - CAR.HYUNDAI_KONA, - CAR.HYUNDAI_KONA_EV, - CAR.HYUNDAI_KONA_EV_2022, - CAR.HYUNDAI_KONA_HEV, - CAR.HYUNDAI_SONATA_LF, - CAR.HYUNDAI_VELOSTER, -} - -CANFD_EXPECTED_ECUS = {Ecu.fwdCamera, Ecu.fwdRadar} - - -class TestHyundaiFingerprint: - def test_can_features(self): - # Test no EV/HEV in any gear lists (should all use ELECT_GEAR) - assert set.union(*CAN_GEARS.values()) & (HYBRID_CAR | EV_CAR) == set() - - # Test CAN FD car not in CAN feature lists - can_specific_feature_list = set.union(*CAN_GEARS.values(), *CHECKSUM.values(), LEGACY_SAFETY_MODE_CAR, UNSUPPORTED_LONGITUDINAL_CAR, CAMERA_SCC_CAR) - for car_model in CANFD_CAR: - assert car_model not in can_specific_feature_list, "CAN FD car unexpectedly found in a CAN feature list" - - def test_hybrid_ev_sets(self): - assert HYBRID_CAR & EV_CAR == set(), "Shared cars between hybrid and EV" - assert CANFD_CAR & HYBRID_CAR == set(), "Hard coding CAN FD cars as hybrid is no longer supported" - - def test_canfd_ecu_whitelist(self): - # Asserts only expected Ecus can exist in database for CAN-FD cars - for car_model in CANFD_CAR: - ecus = {fw[0] for fw in FW_VERSIONS[car_model].keys()} - ecus_not_in_whitelist = ecus - CANFD_EXPECTED_ECUS - ecu_strings = ", ".join([f"Ecu.{ECU_NAME[ecu]}" for ecu in ecus_not_in_whitelist]) - assert len(ecus_not_in_whitelist) == 0, \ - f"{car_model}: Car model has unexpected ECUs: {ecu_strings}" - - def test_blacklisted_parts(self, subtests): - # Asserts no ECUs known to be shared across platforms exist in the database. - # Tucson having Santa Cruz camera and EPS for example - for car_model, ecus in FW_VERSIONS.items(): - with subtests.test(car_model=car_model.value): - if car_model == CAR.HYUNDAI_SANTA_CRUZ_1ST_GEN: - pytest.skip("Skip checking Santa Cruz for its parts") - - for code, _ in get_platform_codes(ecus[(Ecu.fwdCamera, 0x7c4, None)]): - if b"-" not in code: - continue - part = code.split(b"-")[1] - assert not part.startswith(b'CW'), "Car has bad part number" - - def test_correct_ecu_response_database(self, subtests): - """ - Assert standard responses for certain ECUs, since they can - respond to multiple queries with different data - """ - expected_fw_prefix = HYUNDAI_VERSION_REQUEST_LONG[1:] - for car_model, ecus in FW_VERSIONS.items(): - with subtests.test(car_model=car_model.value): - for ecu, fws in ecus.items(): - assert all(fw.startswith(expected_fw_prefix) for fw in fws), \ - f"FW from unexpected request in database: {(ecu, fws)}" - - @settings(max_examples=100) - @given(data=st.data()) - def test_platform_codes_fuzzy_fw(self, data): - """Ensure function doesn't raise an exception""" - fw_strategy = st.lists(st.binary()) - fws = data.draw(fw_strategy) - get_platform_codes(fws) - - def test_expected_platform_codes(self, subtests): - # Ensures we don't accidentally add multiple platform codes for a car unless it is intentional - for car_model, ecus in FW_VERSIONS.items(): - with subtests.test(car_model=car_model.value): - for ecu, fws in ecus.items(): - if ecu[0] not in PLATFORM_CODE_ECUS: - continue - - # Third and fourth character are usually EV/hybrid identifiers - codes = {code.split(b"-")[0][:2] for code, _ in get_platform_codes(fws)} - if car_model == CAR.HYUNDAI_PALISADE: - assert codes == {b"LX", b"ON"}, f"Car has unexpected platform codes: {car_model} {codes}" - elif car_model == CAR.HYUNDAI_KONA_EV and ecu[0] == Ecu.fwdCamera: - assert codes == {b"OE", b"OS"}, f"Car has unexpected platform codes: {car_model} {codes}" - else: - assert len(codes) == 1, f"Car has multiple platform codes: {car_model} {codes}" - - # Tests for platform codes, part numbers, and FW dates which Hyundai will use to fuzzy - # fingerprint in the absence of full FW matches: - def test_platform_code_ecus_available(self, subtests): - # TODO: add queries for these non-CAN FD cars to get EPS - no_eps_platforms = CANFD_CAR | {CAR.KIA_SORENTO, CAR.KIA_OPTIMA_G4, CAR.KIA_OPTIMA_G4_FL, CAR.KIA_OPTIMA_H, - CAR.KIA_OPTIMA_H_G4_FL, CAR.HYUNDAI_SONATA_LF, CAR.HYUNDAI_TUCSON, CAR.GENESIS_G90, CAR.GENESIS_G80, CAR.HYUNDAI_ELANTRA} - - # Asserts ECU keys essential for fuzzy fingerprinting are available on all platforms - for car_model, ecus in FW_VERSIONS.items(): - with subtests.test(car_model=car_model.value): - for platform_code_ecu in PLATFORM_CODE_ECUS: - if platform_code_ecu in (Ecu.fwdRadar, Ecu.eps) and car_model == CAR.HYUNDAI_GENESIS: - continue - if platform_code_ecu == Ecu.eps and car_model in no_eps_platforms: - continue - assert platform_code_ecu in [e[0] for e in ecus] - - def test_fw_format(self, subtests): - # Asserts: - # - every supported ECU FW version returns one platform code - # - every supported ECU FW version has a part number - # - expected parsing of ECU FW dates - - for car_model, ecus in FW_VERSIONS.items(): - with subtests.test(car_model=car_model.value): - for ecu, fws in ecus.items(): - if ecu[0] not in PLATFORM_CODE_ECUS: - continue - - codes = set() - for fw in fws: - result = get_platform_codes([fw]) - assert 1 == len(result), f"Unable to parse FW: {fw}" - codes |= result - - if ecu[0] not in DATE_FW_ECUS or car_model in NO_DATES_PLATFORMS: - assert all(date is None for _, date in codes) - else: - assert all(date is not None for _, date in codes) - - if car_model == CAR.HYUNDAI_GENESIS: - pytest.skip("No part numbers for car model") - - # Hyundai places the ECU part number in their FW versions, assert all parsable - # Some examples of valid formats: b"56310-L0010", b"56310L0010", b"56310/M6300" - assert all(b"-" in code for code, _ in codes), \ - f"FW does not have part number: {fw}" - - def test_platform_codes_spot_check(self): - # Asserts basic platform code parsing behavior for a few cases - results = get_platform_codes([b"\xf1\x00DH LKAS 1.1 -150210"]) - assert results == {(b"DH", b"150210")} - - # Some cameras and all radars do not have dates - results = get_platform_codes([b"\xf1\x00AEhe SCC H-CUP 1.01 1.01 96400-G2000 "]) - assert results == {(b"AEhe-G2000", None)} - - results = get_platform_codes([b"\xf1\x00CV1_ RDR ----- 1.00 1.01 99110-CV000 "]) - assert results == {(b"CV1-CV000", None)} - - results = get_platform_codes([ - b"\xf1\x00DH LKAS 1.1 -150210", - b"\xf1\x00AEhe SCC H-CUP 1.01 1.01 96400-G2000 ", - b"\xf1\x00CV1_ RDR ----- 1.00 1.01 99110-CV000 ", - ]) - assert results == {(b"DH", b"150210"), (b"AEhe-G2000", None), (b"CV1-CV000", None)} - - results = get_platform_codes([ - b"\xf1\x00LX2 MFC AT USA LHD 1.00 1.07 99211-S8100 220222", - b"\xf1\x00LX2 MFC AT USA LHD 1.00 1.08 99211-S8100 211103", - b"\xf1\x00ON MFC AT USA LHD 1.00 1.01 99211-S9100 190405", - b"\xf1\x00ON MFC AT USA LHD 1.00 1.03 99211-S9100 190720", - ]) - assert results == {(b"LX2-S8100", b"220222"), (b"LX2-S8100", b"211103"), - (b"ON-S9100", b"190405"), (b"ON-S9100", b"190720")} - - def test_fuzzy_excluded_platforms(self): - # Asserts a list of platforms that will not fuzzy fingerprint with platform codes due to them being shared. - # This list can be shrunk as we combine platforms and detect features - excluded_platforms = { - CAR.GENESIS_G70, # shared platform code, part number, and date - CAR.GENESIS_G70_2020, - } - excluded_platforms |= CANFD_CAR - EV_CAR - CANFD_FUZZY_WHITELIST # shared platform codes - excluded_platforms |= NO_DATES_PLATFORMS # date codes are required to match - - platforms_with_shared_codes = set() - for platform, fw_by_addr in FW_VERSIONS.items(): - car_fw = [] - for ecu, fw_versions in fw_by_addr.items(): - ecu_name, addr, sub_addr = ecu - for fw in fw_versions: - car_fw.append({"ecu": ecu_name, "fwVersion": fw, "address": addr, - "subAddress": 0 if sub_addr is None else sub_addr}) - - CP = car.CarParams.new_message(carFw=car_fw) - matches = FW_QUERY_CONFIG.match_fw_to_car_fuzzy(build_fw_dict(CP.carFw), CP.carVin, FW_VERSIONS) - if len(matches) == 1: - assert list(matches)[0] == platform - else: - platforms_with_shared_codes.add(platform) - - assert platforms_with_shared_codes == excluded_platforms diff --git a/car/hyundai/values.py b/car/hyundai/values.py deleted file mode 100644 index c489ea0042..0000000000 --- a/car/hyundai/values.py +++ /dev/null @@ -1,751 +0,0 @@ -import re -from dataclasses import dataclass, field -from enum import Enum, IntFlag - -from cereal import car -from panda.python import uds -from openpilot.common.conversions import Conversions as CV -from openpilot.selfdrive.car import CarSpecs, DbcDict, PlatformConfig, Platforms, dbc_dict -from openpilot.selfdrive.car.docs_definitions import CarFootnote, CarHarness, CarDocs, CarParts, Column -from openpilot.selfdrive.car.fw_query_definitions import FwQueryConfig, Request, p16 - -Ecu = car.CarParams.Ecu - - -class CarControllerParams: - ACCEL_MIN = -3.5 # m/s - ACCEL_MAX = 2.0 # m/s - - def __init__(self, CP): - self.STEER_DELTA_UP = 3 - self.STEER_DELTA_DOWN = 7 - self.STEER_DRIVER_ALLOWANCE = 50 - self.STEER_DRIVER_MULTIPLIER = 2 - self.STEER_DRIVER_FACTOR = 1 - self.STEER_THRESHOLD = 150 - self.STEER_STEP = 1 # 100 Hz - - if CP.carFingerprint in CANFD_CAR: - self.STEER_MAX = 270 - self.STEER_DRIVER_ALLOWANCE = 250 - self.STEER_DRIVER_MULTIPLIER = 2 - self.STEER_THRESHOLD = 250 - self.STEER_DELTA_UP = 2 - self.STEER_DELTA_DOWN = 3 - - # To determine the limit for your car, find the maximum value that the stock LKAS will request. - # If the max stock LKAS request is <384, add your car to this list. - elif CP.carFingerprint in (CAR.GENESIS_G80, CAR.GENESIS_G90, CAR.HYUNDAI_ELANTRA, CAR.HYUNDAI_ELANTRA_GT_I30, CAR.HYUNDAI_IONIQ, - CAR.HYUNDAI_IONIQ_EV_LTD, CAR.HYUNDAI_SANTA_FE_PHEV_2022, CAR.HYUNDAI_SONATA_LF, CAR.KIA_FORTE, CAR.KIA_NIRO_PHEV, - CAR.KIA_OPTIMA_H, CAR.KIA_OPTIMA_H_G4_FL, CAR.KIA_SORENTO): - self.STEER_MAX = 255 - - # these cars have significantly more torque than most HKG; limit to 70% of max - elif CP.flags & HyundaiFlags.ALT_LIMITS: - self.STEER_MAX = 270 - self.STEER_DELTA_UP = 2 - self.STEER_DELTA_DOWN = 3 - - # Default for most HKG - else: - self.STEER_MAX = 384 - - -class HyundaiFlags(IntFlag): - # Dynamic Flags - CANFD_HDA2 = 1 - CANFD_ALT_BUTTONS = 2 - CANFD_ALT_GEARS = 2 ** 2 - CANFD_CAMERA_SCC = 2 ** 3 - - ALT_LIMITS = 2 ** 4 - ENABLE_BLINKERS = 2 ** 5 - CANFD_ALT_GEARS_2 = 2 ** 6 - SEND_LFA = 2 ** 7 - USE_FCA = 2 ** 8 - CANFD_HDA2_ALT_STEERING = 2 ** 9 - - # these cars use a different gas signal - HYBRID = 2 ** 10 - EV = 2 ** 11 - - # Static flags - - # If 0x500 is present on bus 1 it probably has a Mando radar outputting radar points. - # If no points are outputted by default it might be possible to turn it on using selfdrive/debug/hyundai_enable_radar_points.py - MANDO_RADAR = 2 ** 12 - CANFD = 2 ** 13 - - # The radar does SCC on these cars when HDA I, rather than the camera - RADAR_SCC = 2 ** 14 - CAMERA_SCC = 2 ** 15 - CHECKSUM_CRC8 = 2 ** 16 - CHECKSUM_6B = 2 ** 17 - - # these cars require a special panda safety mode due to missing counters and checksums in the messages - LEGACY = 2 ** 18 - - # these cars have not been verified to work with longitudinal yet - radar disable, sending correct messages, etc. - UNSUPPORTED_LONGITUDINAL = 2 ** 19 - - CANFD_NO_RADAR_DISABLE = 2 ** 20 - - CLUSTER_GEARS = 2 ** 21 - TCU_GEARS = 2 ** 22 - - MIN_STEER_32_MPH = 2 ** 23 - - -class Footnote(Enum): - CANFD = CarFootnote( - "Requires a CAN FD panda kit if not using " + - "comma 3X for this CAN FD car.", - Column.MODEL, shop_footnote=False) - - -@dataclass -class HyundaiCarDocs(CarDocs): - package: str = "Smart Cruise Control (SCC)" - - def init_make(self, CP: car.CarParams): - if CP.flags & HyundaiFlags.CANFD: - self.footnotes.insert(0, Footnote.CANFD) - - -@dataclass -class HyundaiPlatformConfig(PlatformConfig): - dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict("hyundai_kia_generic", None)) - - def init(self): - if self.flags & HyundaiFlags.MANDO_RADAR: - self.dbc_dict = dbc_dict('hyundai_kia_generic', 'hyundai_kia_mando_front_radar_generated') - - if self.flags & HyundaiFlags.MIN_STEER_32_MPH: - self.specs = self.specs.override(minSteerSpeed=32 * CV.MPH_TO_MS) - - -@dataclass -class HyundaiCanFDPlatformConfig(PlatformConfig): - dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict("hyundai_canfd", None)) - - def init(self): - self.flags |= HyundaiFlags.CANFD - - -class CAR(Platforms): - # Hyundai - HYUNDAI_AZERA_6TH_GEN = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Azera 2022", "All", car_parts=CarParts.common([CarHarness.hyundai_k]))], - CarSpecs(mass=1600, wheelbase=2.885, steerRatio=14.5), - ) - HYUNDAI_AZERA_HEV_6TH_GEN = HyundaiPlatformConfig( - [ - HyundaiCarDocs("Hyundai Azera Hybrid 2019", "All", car_parts=CarParts.common([CarHarness.hyundai_c])), - HyundaiCarDocs("Hyundai Azera Hybrid 2020", "All", car_parts=CarParts.common([CarHarness.hyundai_k])), - ], - CarSpecs(mass=1675, wheelbase=2.885, steerRatio=14.5), - flags=HyundaiFlags.HYBRID, - ) - HYUNDAI_ELANTRA = HyundaiPlatformConfig( - [ - # TODO: 2017-18 could be Hyundai G - HyundaiCarDocs("Hyundai Elantra 2017-18", min_enable_speed=19 * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_b])), - HyundaiCarDocs("Hyundai Elantra 2019", min_enable_speed=19 * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_g])), - ], - # steerRatio: 14 is Stock | Settled Params Learner values are steerRatio: 15.401566348670535, stiffnessFactor settled on 1.0081302973865127 - CarSpecs(mass=1275, wheelbase=2.7, steerRatio=15.4, tireStiffnessFactor=0.385), - flags=HyundaiFlags.LEGACY | HyundaiFlags.CLUSTER_GEARS | HyundaiFlags.MIN_STEER_32_MPH, - ) - HYUNDAI_ELANTRA_GT_I30 = HyundaiPlatformConfig( - [ - HyundaiCarDocs("Hyundai Elantra GT 2017-19", car_parts=CarParts.common([CarHarness.hyundai_e])), - HyundaiCarDocs("Hyundai i30 2017-19", car_parts=CarParts.common([CarHarness.hyundai_e])), - ], - HYUNDAI_ELANTRA.specs, - flags=HyundaiFlags.LEGACY | HyundaiFlags.CLUSTER_GEARS | HyundaiFlags.MIN_STEER_32_MPH, - ) - HYUNDAI_ELANTRA_2021 = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Elantra 2021-23", video_link="https://youtu.be/_EdYQtV52-c", car_parts=CarParts.common([CarHarness.hyundai_k]))], - CarSpecs(mass=2800 * CV.LB_TO_KG, wheelbase=2.72, steerRatio=12.9, tireStiffnessFactor=0.65), - flags=HyundaiFlags.CHECKSUM_CRC8, - ) - HYUNDAI_ELANTRA_HEV_2021 = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Elantra Hybrid 2021-23", video_link="https://youtu.be/_EdYQtV52-c", - car_parts=CarParts.common([CarHarness.hyundai_k]))], - CarSpecs(mass=3017 * CV.LB_TO_KG, wheelbase=2.72, steerRatio=12.9, tireStiffnessFactor=0.65), - flags=HyundaiFlags.CHECKSUM_CRC8 | HyundaiFlags.HYBRID, - ) - HYUNDAI_GENESIS = HyundaiPlatformConfig( - [ - # TODO: check 2015 packages - HyundaiCarDocs("Hyundai Genesis 2015-16", min_enable_speed=19 * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_j])), - HyundaiCarDocs("Genesis G80 2017", "All", min_enable_speed=19 * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_j])), - ], - CarSpecs(mass=2060, wheelbase=3.01, steerRatio=16.5, minSteerSpeed=60 * CV.KPH_TO_MS), - flags=HyundaiFlags.CHECKSUM_6B | HyundaiFlags.LEGACY, - ) - HYUNDAI_IONIQ = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Ioniq Hybrid 2017-19", car_parts=CarParts.common([CarHarness.hyundai_c]))], - CarSpecs(mass=1490, wheelbase=2.7, steerRatio=13.73, tireStiffnessFactor=0.385), - flags=HyundaiFlags.HYBRID | HyundaiFlags.MIN_STEER_32_MPH, - ) - HYUNDAI_IONIQ_HEV_2022 = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Ioniq Hybrid 2020-22", car_parts=CarParts.common([CarHarness.hyundai_h]))], # TODO: confirm 2020-21 harness, - CarSpecs(mass=1490, wheelbase=2.7, steerRatio=13.73, tireStiffnessFactor=0.385), - flags=HyundaiFlags.HYBRID | HyundaiFlags.LEGACY, - ) - HYUNDAI_IONIQ_EV_LTD = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Ioniq Electric 2019", car_parts=CarParts.common([CarHarness.hyundai_c]))], - CarSpecs(mass=1490, wheelbase=2.7, steerRatio=13.73, tireStiffnessFactor=0.385), - flags=HyundaiFlags.MANDO_RADAR | HyundaiFlags.EV | HyundaiFlags.LEGACY | HyundaiFlags.MIN_STEER_32_MPH, - ) - HYUNDAI_IONIQ_EV_2020 = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Ioniq Electric 2020", "All", car_parts=CarParts.common([CarHarness.hyundai_h]))], - CarSpecs(mass=1490, wheelbase=2.7, steerRatio=13.73, tireStiffnessFactor=0.385), - flags=HyundaiFlags.EV, - ) - HYUNDAI_IONIQ_PHEV_2019 = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Ioniq Plug-in Hybrid 2019", car_parts=CarParts.common([CarHarness.hyundai_c]))], - CarSpecs(mass=1490, wheelbase=2.7, steerRatio=13.73, tireStiffnessFactor=0.385), - flags=HyundaiFlags.HYBRID | HyundaiFlags.MIN_STEER_32_MPH, - ) - HYUNDAI_IONIQ_PHEV = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Ioniq Plug-in Hybrid 2020-22", "All", car_parts=CarParts.common([CarHarness.hyundai_h]))], - CarSpecs(mass=1490, wheelbase=2.7, steerRatio=13.73, tireStiffnessFactor=0.385), - flags=HyundaiFlags.HYBRID, - ) - HYUNDAI_KONA = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Kona 2020", min_enable_speed=6 * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_b]))], - CarSpecs(mass=1275, wheelbase=2.6, steerRatio=13.42, tireStiffnessFactor=0.385), - flags=HyundaiFlags.CLUSTER_GEARS, - ) - HYUNDAI_KONA_EV = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Kona Electric 2018-21", car_parts=CarParts.common([CarHarness.hyundai_g]))], - CarSpecs(mass=1685, wheelbase=2.6, steerRatio=13.42, tireStiffnessFactor=0.385), - flags=HyundaiFlags.EV, - ) - HYUNDAI_KONA_EV_2022 = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Kona Electric 2022-23", car_parts=CarParts.common([CarHarness.hyundai_o]))], - CarSpecs(mass=1743, wheelbase=2.6, steerRatio=13.42, tireStiffnessFactor=0.385), - flags=HyundaiFlags.CAMERA_SCC | HyundaiFlags.EV, - ) - HYUNDAI_KONA_EV_2ND_GEN = HyundaiCanFDPlatformConfig( - [HyundaiCarDocs("Hyundai Kona Electric (with HDA II, Korea only) 2023", video_link="https://www.youtube.com/watch?v=U2fOCmcQ8hw", - car_parts=CarParts.common([CarHarness.hyundai_r]))], - CarSpecs(mass=1740, wheelbase=2.66, steerRatio=13.6, tireStiffnessFactor=0.385), - flags=HyundaiFlags.EV | HyundaiFlags.CANFD_NO_RADAR_DISABLE, - ) - HYUNDAI_KONA_HEV = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Kona Hybrid 2020", car_parts=CarParts.common([CarHarness.hyundai_i]))], # TODO: check packages, - CarSpecs(mass=1425, wheelbase=2.6, steerRatio=13.42, tireStiffnessFactor=0.385), - flags=HyundaiFlags.HYBRID, - ) - HYUNDAI_SANTA_FE = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Santa Fe 2019-20", "All", video_link="https://youtu.be/bjDR0YjM__s", - car_parts=CarParts.common([CarHarness.hyundai_d]))], - CarSpecs(mass=3982 * CV.LB_TO_KG, wheelbase=2.766, steerRatio=16.55, tireStiffnessFactor=0.82), - flags=HyundaiFlags.MANDO_RADAR | HyundaiFlags.CHECKSUM_CRC8, - ) - HYUNDAI_SANTA_FE_2022 = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Santa Fe 2021-23", "All", video_link="https://youtu.be/VnHzSTygTS4", - car_parts=CarParts.common([CarHarness.hyundai_l]))], - HYUNDAI_SANTA_FE.specs, - flags=HyundaiFlags.CHECKSUM_CRC8, - ) - HYUNDAI_SANTA_FE_HEV_2022 = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Santa Fe Hybrid 2022-23", "All", car_parts=CarParts.common([CarHarness.hyundai_l]))], - HYUNDAI_SANTA_FE.specs, - flags=HyundaiFlags.CHECKSUM_CRC8 | HyundaiFlags.HYBRID, - ) - HYUNDAI_SANTA_FE_PHEV_2022 = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Santa Fe Plug-in Hybrid 2022-23", "All", car_parts=CarParts.common([CarHarness.hyundai_l]))], - HYUNDAI_SANTA_FE.specs, - flags=HyundaiFlags.CHECKSUM_CRC8 | HyundaiFlags.HYBRID, - ) - HYUNDAI_SONATA = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Sonata 2020-23", "All", video_link="https://www.youtube.com/watch?v=ix63r9kE3Fw", - car_parts=CarParts.common([CarHarness.hyundai_a]))], - CarSpecs(mass=1513, wheelbase=2.84, steerRatio=13.27 * 1.15, tireStiffnessFactor=0.65), # 15% higher at the center seems reasonable - flags=HyundaiFlags.MANDO_RADAR | HyundaiFlags.CHECKSUM_CRC8, - ) - HYUNDAI_SONATA_LF = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Sonata 2018-19", car_parts=CarParts.common([CarHarness.hyundai_e]))], - CarSpecs(mass=1536, wheelbase=2.804, steerRatio=13.27 * 1.15), # 15% higher at the center seems reasonable - - flags=HyundaiFlags.UNSUPPORTED_LONGITUDINAL | HyundaiFlags.TCU_GEARS, - ) - HYUNDAI_STARIA_4TH_GEN = HyundaiCanFDPlatformConfig( - [HyundaiCarDocs("Hyundai Staria 2023", "All", car_parts=CarParts.common([CarHarness.hyundai_k]))], - CarSpecs(mass=2205, wheelbase=3.273, steerRatio=11.94), # https://www.hyundai.com/content/dam/hyundai/au/en/models/staria-load/premium-pip-update-2023/spec-sheet/STARIA_Load_Spec-Table_March_2023_v3.1.pdf - ) - HYUNDAI_TUCSON = HyundaiPlatformConfig( - [ - HyundaiCarDocs("Hyundai Tucson 2021", min_enable_speed=19 * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_l])), - HyundaiCarDocs("Hyundai Tucson Diesel 2019", car_parts=CarParts.common([CarHarness.hyundai_l])), - ], - CarSpecs(mass=3520 * CV.LB_TO_KG, wheelbase=2.67, steerRatio=16.1, tireStiffnessFactor=0.385), - flags=HyundaiFlags.TCU_GEARS, - ) - HYUNDAI_PALISADE = HyundaiPlatformConfig( - [ - HyundaiCarDocs("Hyundai Palisade 2020-22", "All", video_link="https://youtu.be/TAnDqjF4fDY?t=456", car_parts=CarParts.common([CarHarness.hyundai_h])), - HyundaiCarDocs("Kia Telluride 2020-22", "All", car_parts=CarParts.common([CarHarness.hyundai_h])), - ], - CarSpecs(mass=1999, wheelbase=2.9, steerRatio=15.6 * 1.15, tireStiffnessFactor=0.63), - flags=HyundaiFlags.MANDO_RADAR | HyundaiFlags.CHECKSUM_CRC8, - ) - HYUNDAI_VELOSTER = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Veloster 2019-20", min_enable_speed=5. * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_e]))], - CarSpecs(mass=2917 * CV.LB_TO_KG, wheelbase=2.8, steerRatio=13.75 * 1.15, tireStiffnessFactor=0.5), - flags=HyundaiFlags.LEGACY | HyundaiFlags.TCU_GEARS, - ) - HYUNDAI_SONATA_HYBRID = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Sonata Hybrid 2020-23", "All", car_parts=CarParts.common([CarHarness.hyundai_a]))], - HYUNDAI_SONATA.specs, - flags=HyundaiFlags.MANDO_RADAR | HyundaiFlags.CHECKSUM_CRC8 | HyundaiFlags.HYBRID, - ) - HYUNDAI_IONIQ_5 = HyundaiCanFDPlatformConfig( - [ - HyundaiCarDocs("Hyundai Ioniq 5 (Southeast Asia only) 2022-23", "All", car_parts=CarParts.common([CarHarness.hyundai_q])), - HyundaiCarDocs("Hyundai Ioniq 5 (without HDA II) 2022-23", "Highway Driving Assist", car_parts=CarParts.common([CarHarness.hyundai_k])), - HyundaiCarDocs("Hyundai Ioniq 5 (with HDA II) 2022-23", "Highway Driving Assist II", car_parts=CarParts.common([CarHarness.hyundai_q])), - ], - CarSpecs(mass=1948, wheelbase=2.97, steerRatio=14.26, tireStiffnessFactor=0.65), - flags=HyundaiFlags.EV, - ) - HYUNDAI_IONIQ_6 = HyundaiCanFDPlatformConfig( - [HyundaiCarDocs("Hyundai Ioniq 6 (with HDA II) 2023-24", "Highway Driving Assist II", car_parts=CarParts.common([CarHarness.hyundai_p]))], - HYUNDAI_IONIQ_5.specs, - flags=HyundaiFlags.EV | HyundaiFlags.CANFD_NO_RADAR_DISABLE, - ) - HYUNDAI_TUCSON_4TH_GEN = HyundaiCanFDPlatformConfig( - [ - HyundaiCarDocs("Hyundai Tucson 2022", car_parts=CarParts.common([CarHarness.hyundai_n])), - HyundaiCarDocs("Hyundai Tucson 2023-24", "All", car_parts=CarParts.common([CarHarness.hyundai_n])), - HyundaiCarDocs("Hyundai Tucson Hybrid 2022-24", "All", car_parts=CarParts.common([CarHarness.hyundai_n])), - HyundaiCarDocs("Hyundai Tucson Plug-in Hybrid 2024", "All", car_parts=CarParts.common([CarHarness.hyundai_n])), - ], - CarSpecs(mass=1630, wheelbase=2.756, steerRatio=13.7, tireStiffnessFactor=0.385), - ) - HYUNDAI_SANTA_CRUZ_1ST_GEN = HyundaiCanFDPlatformConfig( - [HyundaiCarDocs("Hyundai Santa Cruz 2022-24", car_parts=CarParts.common([CarHarness.hyundai_n]))], - # weight from Limited trim - the only supported trim, steering ratio according to Hyundai News https://www.hyundainews.com/assets/documents/original/48035-2022SantaCruzProductGuideSpecsv2081521.pdf - CarSpecs(mass=1870, wheelbase=3, steerRatio=14.2), - ) - HYUNDAI_CUSTIN_1ST_GEN = HyundaiPlatformConfig( - [HyundaiCarDocs("Hyundai Custin 2023", "All", car_parts=CarParts.common([CarHarness.hyundai_k]))], - CarSpecs(mass=1690, wheelbase=3.055, steerRatio=17), # mass: from https://www.hyundai-motor.com.tw/clicktobuy/custin#spec_0, steerRatio: from learner - flags=HyundaiFlags.CHECKSUM_CRC8, - ) - - # Kia - KIA_FORTE = HyundaiPlatformConfig( - [ - HyundaiCarDocs("Kia Forte 2019-21", min_enable_speed=6 * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_g])), - HyundaiCarDocs("Kia Forte 2022-23", car_parts=CarParts.common([CarHarness.hyundai_e])), - ], - CarSpecs(mass=2878 * CV.LB_TO_KG, wheelbase=2.8, steerRatio=13.75, tireStiffnessFactor=0.5) - ) - KIA_K5_2021 = HyundaiPlatformConfig( - [HyundaiCarDocs("Kia K5 2021-24", car_parts=CarParts.common([CarHarness.hyundai_a]))], - CarSpecs(mass=3381 * CV.LB_TO_KG, wheelbase=2.85, steerRatio=13.27, tireStiffnessFactor=0.5), # 2021 Kia K5 Steering Ratio (all trims) - flags=HyundaiFlags.CHECKSUM_CRC8, - ) - KIA_K5_HEV_2020 = HyundaiPlatformConfig( - [HyundaiCarDocs("Kia K5 Hybrid 2020-22", car_parts=CarParts.common([CarHarness.hyundai_a]))], - KIA_K5_2021.specs, - flags=HyundaiFlags.MANDO_RADAR | HyundaiFlags.CHECKSUM_CRC8 | HyundaiFlags.HYBRID, - ) - KIA_K8_HEV_1ST_GEN = HyundaiCanFDPlatformConfig( - [HyundaiCarDocs("Kia K8 Hybrid (with HDA II) 2023", "Highway Driving Assist II", car_parts=CarParts.common([CarHarness.hyundai_q]))], - # mass: https://carprices.ae/brands/kia/2023/k8/1.6-turbo-hybrid, steerRatio: guesstimate from K5 platform - CarSpecs(mass=1630, wheelbase=2.895, steerRatio=13.27) - ) - KIA_NIRO_EV = HyundaiPlatformConfig( - [ - HyundaiCarDocs("Kia Niro EV 2019", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", car_parts=CarParts.common([CarHarness.hyundai_h])), - HyundaiCarDocs("Kia Niro EV 2020", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", car_parts=CarParts.common([CarHarness.hyundai_f])), - HyundaiCarDocs("Kia Niro EV 2021", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", car_parts=CarParts.common([CarHarness.hyundai_c])), - HyundaiCarDocs("Kia Niro EV 2022", "All", video_link="https://www.youtube.com/watch?v=lT7zcG6ZpGo", car_parts=CarParts.common([CarHarness.hyundai_h])), - ], - CarSpecs(mass=3543 * CV.LB_TO_KG, wheelbase=2.7, steerRatio=13.6, tireStiffnessFactor=0.385), # average of all the cars - flags=HyundaiFlags.MANDO_RADAR | HyundaiFlags.EV, - ) - KIA_NIRO_EV_2ND_GEN = HyundaiCanFDPlatformConfig( - [HyundaiCarDocs("Kia Niro EV 2023", "All", car_parts=CarParts.common([CarHarness.hyundai_a]))], - KIA_NIRO_EV.specs, - flags=HyundaiFlags.EV, - ) - KIA_NIRO_PHEV = HyundaiPlatformConfig( - [ - HyundaiCarDocs("Kia Niro Hybrid 2018", "All", min_enable_speed=10. * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_c])), - HyundaiCarDocs("Kia Niro Plug-in Hybrid 2018-19", "All", min_enable_speed=10. * CV.MPH_TO_MS, car_parts=CarParts.common([CarHarness.hyundai_c])), - HyundaiCarDocs("Kia Niro Plug-in Hybrid 2020", car_parts=CarParts.common([CarHarness.hyundai_d])), - ], - KIA_NIRO_EV.specs, - flags=HyundaiFlags.MANDO_RADAR | HyundaiFlags.HYBRID | HyundaiFlags.UNSUPPORTED_LONGITUDINAL | HyundaiFlags.MIN_STEER_32_MPH, - ) - KIA_NIRO_PHEV_2022 = HyundaiPlatformConfig( - [ - HyundaiCarDocs("Kia Niro Plug-in Hybrid 2021", car_parts=CarParts.common([CarHarness.hyundai_d])), - HyundaiCarDocs("Kia Niro Plug-in Hybrid 2022", car_parts=CarParts.common([CarHarness.hyundai_f])), - ], - KIA_NIRO_EV.specs, - flags=HyundaiFlags.HYBRID | HyundaiFlags.MANDO_RADAR, - ) - KIA_NIRO_HEV_2021 = HyundaiPlatformConfig( - [ - HyundaiCarDocs("Kia Niro Hybrid 2021", car_parts=CarParts.common([CarHarness.hyundai_d])), - HyundaiCarDocs("Kia Niro Hybrid 2022", car_parts=CarParts.common([CarHarness.hyundai_f])), - ], - KIA_NIRO_EV.specs, - flags=HyundaiFlags.HYBRID, - ) - KIA_NIRO_HEV_2ND_GEN = HyundaiCanFDPlatformConfig( - [HyundaiCarDocs("Kia Niro Hybrid 2023", car_parts=CarParts.common([CarHarness.hyundai_a]))], - KIA_NIRO_EV.specs, - ) - KIA_OPTIMA_G4 = HyundaiPlatformConfig( - [HyundaiCarDocs("Kia Optima 2017", "Advanced Smart Cruise Control", - car_parts=CarParts.common([CarHarness.hyundai_b]))], # TODO: may support 2016, 2018 - CarSpecs(mass=3558 * CV.LB_TO_KG, wheelbase=2.8, steerRatio=13.75, tireStiffnessFactor=0.5), - flags=HyundaiFlags.LEGACY | HyundaiFlags.TCU_GEARS | HyundaiFlags.MIN_STEER_32_MPH, - ) - KIA_OPTIMA_G4_FL = HyundaiPlatformConfig( - [HyundaiCarDocs("Kia Optima 2019-20", car_parts=CarParts.common([CarHarness.hyundai_g]))], - CarSpecs(mass=3558 * CV.LB_TO_KG, wheelbase=2.8, steerRatio=13.75, tireStiffnessFactor=0.5), - flags=HyundaiFlags.UNSUPPORTED_LONGITUDINAL | HyundaiFlags.TCU_GEARS, - ) - # TODO: may support adjacent years. may have a non-zero minimum steering speed - KIA_OPTIMA_H = HyundaiPlatformConfig( - [HyundaiCarDocs("Kia Optima Hybrid 2017", "Advanced Smart Cruise Control", car_parts=CarParts.common([CarHarness.hyundai_c]))], - CarSpecs(mass=3558 * CV.LB_TO_KG, wheelbase=2.8, steerRatio=13.75, tireStiffnessFactor=0.5), - flags=HyundaiFlags.HYBRID | HyundaiFlags.LEGACY, - ) - KIA_OPTIMA_H_G4_FL = HyundaiPlatformConfig( - [HyundaiCarDocs("Kia Optima Hybrid 2019", car_parts=CarParts.common([CarHarness.hyundai_h]))], - CarSpecs(mass=3558 * CV.LB_TO_KG, wheelbase=2.8, steerRatio=13.75, tireStiffnessFactor=0.5), - flags=HyundaiFlags.HYBRID | HyundaiFlags.UNSUPPORTED_LONGITUDINAL, - ) - KIA_SELTOS = HyundaiPlatformConfig( - [HyundaiCarDocs("Kia Seltos 2021", car_parts=CarParts.common([CarHarness.hyundai_a]))], - CarSpecs(mass=1337, wheelbase=2.63, steerRatio=14.56), - flags=HyundaiFlags.CHECKSUM_CRC8, - ) - KIA_SPORTAGE_5TH_GEN = HyundaiCanFDPlatformConfig( - [ - HyundaiCarDocs("Kia Sportage 2023-24", car_parts=CarParts.common([CarHarness.hyundai_n])), - HyundaiCarDocs("Kia Sportage Hybrid 2023", car_parts=CarParts.common([CarHarness.hyundai_n])), - ], - # weight from SX and above trims, average of FWD and AWD version, steering ratio according to Kia News https://www.kiamedia.com/us/en/models/sportage/2023/specifications - CarSpecs(mass=1725, wheelbase=2.756, steerRatio=13.6), - ) - KIA_SORENTO = HyundaiPlatformConfig( - [ - HyundaiCarDocs("Kia Sorento 2018", "Advanced Smart Cruise Control & LKAS", video_link="https://www.youtube.com/watch?v=Fkh3s6WHJz8", - car_parts=CarParts.common([CarHarness.hyundai_e])), - HyundaiCarDocs("Kia Sorento 2019", video_link="https://www.youtube.com/watch?v=Fkh3s6WHJz8", car_parts=CarParts.common([CarHarness.hyundai_e])), - ], - CarSpecs(mass=1985, wheelbase=2.78, steerRatio=14.4 * 1.1), # 10% higher at the center seems reasonable - flags=HyundaiFlags.CHECKSUM_6B | HyundaiFlags.UNSUPPORTED_LONGITUDINAL, - ) - KIA_SORENTO_4TH_GEN = HyundaiCanFDPlatformConfig( - [HyundaiCarDocs("Kia Sorento 2021-23", car_parts=CarParts.common([CarHarness.hyundai_k]))], - CarSpecs(mass=3957 * CV.LB_TO_KG, wheelbase=2.81, steerRatio=13.5), # average of the platforms - flags=HyundaiFlags.RADAR_SCC, - ) - KIA_SORENTO_HEV_4TH_GEN = HyundaiCanFDPlatformConfig( - [ - HyundaiCarDocs("Kia Sorento Hybrid 2021-23", "All", car_parts=CarParts.common([CarHarness.hyundai_a])), - HyundaiCarDocs("Kia Sorento Plug-in Hybrid 2022-23", "All", car_parts=CarParts.common([CarHarness.hyundai_a])), - ], - CarSpecs(mass=4395 * CV.LB_TO_KG, wheelbase=2.81, steerRatio=13.5), # average of the platforms - flags=HyundaiFlags.RADAR_SCC, - ) - KIA_STINGER = HyundaiPlatformConfig( - [HyundaiCarDocs("Kia Stinger 2018-20", video_link="https://www.youtube.com/watch?v=MJ94qoofYw0", - car_parts=CarParts.common([CarHarness.hyundai_c]))], - CarSpecs(mass=1825, wheelbase=2.78, steerRatio=14.4 * 1.15) # 15% higher at the center seems reasonable - ) - KIA_STINGER_2022 = HyundaiPlatformConfig( - [HyundaiCarDocs("Kia Stinger 2022-23", "All", car_parts=CarParts.common([CarHarness.hyundai_k]))], - KIA_STINGER.specs, - ) - KIA_CEED = HyundaiPlatformConfig( - [HyundaiCarDocs("Kia Ceed 2019", car_parts=CarParts.common([CarHarness.hyundai_e]))], - CarSpecs(mass=1450, wheelbase=2.65, steerRatio=13.75, tireStiffnessFactor=0.5), - flags=HyundaiFlags.LEGACY, - ) - KIA_EV6 = HyundaiCanFDPlatformConfig( - [ - HyundaiCarDocs("Kia EV6 (Southeast Asia only) 2022-24", "All", car_parts=CarParts.common([CarHarness.hyundai_p])), - HyundaiCarDocs("Kia EV6 (without HDA II) 2022-24", "Highway Driving Assist", car_parts=CarParts.common([CarHarness.hyundai_l])), - HyundaiCarDocs("Kia EV6 (with HDA II) 2022-24", "Highway Driving Assist II", car_parts=CarParts.common([CarHarness.hyundai_p])) - ], - CarSpecs(mass=2055, wheelbase=2.9, steerRatio=16, tireStiffnessFactor=0.65), - flags=HyundaiFlags.EV, - ) - KIA_CARNIVAL_4TH_GEN = HyundaiCanFDPlatformConfig( - [ - HyundaiCarDocs("Kia Carnival 2022-24", car_parts=CarParts.common([CarHarness.hyundai_a])), - HyundaiCarDocs("Kia Carnival (China only) 2023", car_parts=CarParts.common([CarHarness.hyundai_k])) - ], - CarSpecs(mass=2087, wheelbase=3.09, steerRatio=14.23), - flags=HyundaiFlags.RADAR_SCC, - ) - - # Genesis - GENESIS_GV60_EV_1ST_GEN = HyundaiCanFDPlatformConfig( - [ - HyundaiCarDocs("Genesis GV60 (Advanced Trim) 2023", "All", car_parts=CarParts.common([CarHarness.hyundai_a])), - HyundaiCarDocs("Genesis GV60 (Performance Trim) 2023", "All", car_parts=CarParts.common([CarHarness.hyundai_k])), - ], - CarSpecs(mass=2205, wheelbase=2.9, steerRatio=12.6), # steerRatio: https://www.motor1.com/reviews/586376/2023-genesis-gv60-first-drive/#:~:text=Relative%20to%20the%20related%20Ioniq,5%2FEV6%27s%2014.3%3A1. - flags=HyundaiFlags.EV, - ) - GENESIS_G70 = HyundaiPlatformConfig( - [HyundaiCarDocs("Genesis G70 2018", "All", car_parts=CarParts.common([CarHarness.hyundai_f]))], - CarSpecs(mass=1640, wheelbase=2.84, steerRatio=13.56), - flags=HyundaiFlags.LEGACY, - ) - GENESIS_G70_2020 = HyundaiPlatformConfig( - [ - # TODO: 2021 MY harness is unknown - HyundaiCarDocs("Genesis G70 2019-21", "All", car_parts=CarParts.common([CarHarness.hyundai_f])), - # TODO: From 3.3T Sport Advanced 2022 & Prestige 2023 Trim, 2.0T is unknown - HyundaiCarDocs("Genesis G70 2022-23", "All", car_parts=CarParts.common([CarHarness.hyundai_l])), - ], - GENESIS_G70.specs, - flags=HyundaiFlags.MANDO_RADAR, - ) - GENESIS_GV70_1ST_GEN = HyundaiCanFDPlatformConfig( - [ - HyundaiCarDocs("Genesis GV70 (2.5T Trim) 2022-23", "All", car_parts=CarParts.common([CarHarness.hyundai_l])), - HyundaiCarDocs("Genesis GV70 (3.5T Trim) 2022-23", "All", car_parts=CarParts.common([CarHarness.hyundai_m])), - ], - CarSpecs(mass=1950, wheelbase=2.87, steerRatio=14.6), - flags=HyundaiFlags.RADAR_SCC, - ) - GENESIS_G80 = HyundaiPlatformConfig( - [HyundaiCarDocs("Genesis G80 2018-19", "All", car_parts=CarParts.common([CarHarness.hyundai_h]))], - CarSpecs(mass=2060, wheelbase=3.01, steerRatio=16.5), - flags=HyundaiFlags.LEGACY, - ) - GENESIS_G90 = HyundaiPlatformConfig( - [HyundaiCarDocs("Genesis G90 2017-20", "All", car_parts=CarParts.common([CarHarness.hyundai_c]))], - CarSpecs(mass=2200, wheelbase=3.15, steerRatio=12.069), - ) - GENESIS_GV80 = HyundaiCanFDPlatformConfig( - [HyundaiCarDocs("Genesis GV80 2023", "All", car_parts=CarParts.common([CarHarness.hyundai_m]))], - CarSpecs(mass=2258, wheelbase=2.95, steerRatio=14.14), - flags=HyundaiFlags.RADAR_SCC, - ) - - -class Buttons: - NONE = 0 - RES_ACCEL = 1 - SET_DECEL = 2 - GAP_DIST = 3 - CANCEL = 4 # on newer models, this is a pause/resume button - - -def get_platform_codes(fw_versions: list[bytes]) -> set[tuple[bytes, bytes | None]]: - # Returns unique, platform-specific identification codes for a set of versions - codes = set() # (code-Optional[part], date) - for fw in fw_versions: - code_match = PLATFORM_CODE_FW_PATTERN.search(fw) - part_match = PART_NUMBER_FW_PATTERN.search(fw) - date_match = DATE_FW_PATTERN.search(fw) - if code_match is not None: - code: bytes = code_match.group() - part = part_match.group() if part_match else None - date = date_match.group() if date_match else None - if part is not None: - # part number starts with generic ECU part type, add what is specific to platform - code += b"-" + part[-5:] - - codes.add((code, date)) - return codes - - -def match_fw_to_car_fuzzy(live_fw_versions, vin, offline_fw_versions) -> set[str]: - # Non-electric CAN FD platforms often do not have platform code specifiers needed - # to distinguish between hybrid and ICE. All EVs so far are either exclusively - # electric or specify electric in the platform code. - fuzzy_platform_blacklist = {str(c) for c in (CANFD_CAR - EV_CAR - CANFD_FUZZY_WHITELIST)} - candidates: set[str] = set() - - for candidate, fws in offline_fw_versions.items(): - # Keep track of ECUs which pass all checks (platform codes, within date range) - valid_found_ecus = set() - valid_expected_ecus = {ecu[1:] for ecu in fws if ecu[0] in PLATFORM_CODE_ECUS} - for ecu, expected_versions in fws.items(): - addr = ecu[1:] - # Only check ECUs expected to have platform codes - if ecu[0] not in PLATFORM_CODE_ECUS: - continue - - # Expected platform codes & dates - codes = get_platform_codes(expected_versions) - expected_platform_codes = {code for code, _ in codes} - expected_dates = {date for _, date in codes if date is not None} - - # Found platform codes & dates - codes = get_platform_codes(live_fw_versions.get(addr, set())) - found_platform_codes = {code for code, _ in codes} - found_dates = {date for _, date in codes if date is not None} - - # Check platform code + part number matches for any found versions - if not any(found_platform_code in expected_platform_codes for found_platform_code in found_platform_codes): - break - - if ecu[0] in DATE_FW_ECUS: - # If ECU can have a FW date, require it to exist - # (this excludes candidates in the database without dates) - if not len(expected_dates) or not len(found_dates): - break - - # Check any date within range in the database, format is %y%m%d - if not any(min(expected_dates) <= found_date <= max(expected_dates) for found_date in found_dates): - break - - valid_found_ecus.add(addr) - - # If all live ECUs pass all checks for candidate, add it as a match - if valid_expected_ecus.issubset(valid_found_ecus): - candidates.add(candidate) - - return candidates - fuzzy_platform_blacklist - - -HYUNDAI_VERSION_REQUEST_LONG = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ - p16(0xf100) # Long description - -HYUNDAI_VERSION_REQUEST_ALT = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ - p16(0xf110) # Alt long description - -HYUNDAI_ECU_MANUFACTURING_DATE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ - p16(uds.DATA_IDENTIFIER_TYPE.ECU_MANUFACTURING_DATE) - -HYUNDAI_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) - -# Regex patterns for parsing platform code, FW date, and part number from FW versions -PLATFORM_CODE_FW_PATTERN = re.compile(b'((?<=' + HYUNDAI_VERSION_REQUEST_LONG[1:] + - b')[A-Z]{2}[A-Za-z0-9]{0,2})') -DATE_FW_PATTERN = re.compile(b'(?<=[ -])([0-9]{6}$)') -PART_NUMBER_FW_PATTERN = re.compile(b'(?<=[0-9][.,][0-9]{2} )([0-9]{5}[-/]?[A-Z][A-Z0-9]{3}[0-9])') - -# We've seen both ICE and hybrid for these platforms, and they have hybrid descriptors (e.g. MQ4 vs MQ4H) -CANFD_FUZZY_WHITELIST = {CAR.KIA_SORENTO_4TH_GEN, CAR.KIA_SORENTO_HEV_4TH_GEN, CAR.KIA_K8_HEV_1ST_GEN, - # TODO: the hybrid variant is not out yet - CAR.KIA_CARNIVAL_4TH_GEN} - -# List of ECUs expected to have platform codes, camera and radar should exist on all cars -# TODO: use abs, it has the platform code and part number on many platforms -PLATFORM_CODE_ECUS = [Ecu.fwdRadar, Ecu.fwdCamera, Ecu.eps] -# So far we've only seen dates in fwdCamera -# TODO: there are date codes in the ABS firmware versions in hex -DATE_FW_ECUS = [Ecu.fwdCamera] - -# Note: an ECU on CAN FD cars may sometimes send 0x30080aaaaaaaaaaa (flow control continue) while we -# are attempting to query ECUs. This currently does not seem to affect fingerprinting from the camera -FW_QUERY_CONFIG = FwQueryConfig( - requests=[ - # TODO: add back whitelists - # CAN queries (OBD-II port) - Request( - [HYUNDAI_VERSION_REQUEST_LONG], - [HYUNDAI_VERSION_RESPONSE], - ), - - # CAN & CAN-FD queries (from camera) - Request( - [HYUNDAI_VERSION_REQUEST_LONG], - [HYUNDAI_VERSION_RESPONSE], - bus=0, - auxiliary=True, - ), - Request( - [HYUNDAI_VERSION_REQUEST_LONG], - [HYUNDAI_VERSION_RESPONSE], - bus=1, - auxiliary=True, - obd_multiplexing=False, - ), - - # CAN & CAN FD query to understand the three digit date code - # HDA2 cars usually use 6 digit date codes, so skip bus 1 - Request( - [HYUNDAI_ECU_MANUFACTURING_DATE], - [HYUNDAI_VERSION_RESPONSE], - bus=0, - auxiliary=True, - logging=True, - ), - - # CAN-FD alt request logging queries for hvac and parkingAdas - Request( - [HYUNDAI_VERSION_REQUEST_ALT], - [HYUNDAI_VERSION_RESPONSE], - bus=0, - auxiliary=True, - logging=True, - ), - Request( - [HYUNDAI_VERSION_REQUEST_ALT], - [HYUNDAI_VERSION_RESPONSE], - bus=1, - auxiliary=True, - logging=True, - obd_multiplexing=False, - ), - ], - # We lose these ECUs without the comma power on these cars. - # Note that we still attempt to match with them when they are present - non_essential_ecus={ - Ecu.abs: [CAR.HYUNDAI_PALISADE, CAR.HYUNDAI_SONATA, CAR.HYUNDAI_SANTA_FE_2022, CAR.KIA_K5_2021, CAR.HYUNDAI_ELANTRA_2021, - CAR.HYUNDAI_SANTA_FE, CAR.HYUNDAI_KONA_EV_2022, CAR.HYUNDAI_KONA_EV, CAR.HYUNDAI_CUSTIN_1ST_GEN, CAR.KIA_SORENTO, - CAR.KIA_CEED, CAR.KIA_SELTOS], - }, - extra_ecus=[ - (Ecu.adas, 0x730, None), # ADAS Driving ECU on HDA2 platforms - (Ecu.parkingAdas, 0x7b1, None), # ADAS Parking ECU (may exist on all platforms) - (Ecu.hvac, 0x7b3, None), # HVAC Control Assembly - (Ecu.cornerRadar, 0x7b7, None), - (Ecu.combinationMeter, 0x7c6, None), # CAN FD Instrument cluster - ], - # Custom fuzzy fingerprinting function using platform codes, part numbers + FW dates: - match_fw_to_car_fuzzy=match_fw_to_car_fuzzy, -) - -CHECKSUM = { - "crc8": CAR.with_flags(HyundaiFlags.CHECKSUM_CRC8), - "6B": CAR.with_flags(HyundaiFlags.CHECKSUM_6B), -} - -CAN_GEARS = { - # which message has the gear. hybrid and EV use ELECT_GEAR - "use_cluster_gears": CAR.with_flags(HyundaiFlags.CLUSTER_GEARS), - "use_tcu_gears": CAR.with_flags(HyundaiFlags.TCU_GEARS), -} - -CANFD_CAR = CAR.with_flags(HyundaiFlags.CANFD) -CANFD_RADAR_SCC_CAR = CAR.with_flags(HyundaiFlags.RADAR_SCC) - -# These CAN FD cars do not accept communication control to disable the ADAS ECU, -# responds with 0x7F2822 - 'conditions not correct' -CANFD_UNSUPPORTED_LONGITUDINAL_CAR = CAR.with_flags(HyundaiFlags.CANFD_NO_RADAR_DISABLE) - -# The camera does SCC on these cars, rather than the radar -CAMERA_SCC_CAR = CAR.with_flags(HyundaiFlags.CAMERA_SCC) - -HYBRID_CAR = CAR.with_flags(HyundaiFlags.HYBRID) - -EV_CAR = CAR.with_flags(HyundaiFlags.EV) - -LEGACY_SAFETY_MODE_CAR = CAR.with_flags(HyundaiFlags.LEGACY) - -UNSUPPORTED_LONGITUDINAL_CAR = CAR.with_flags(HyundaiFlags.LEGACY) | CAR.with_flags(HyundaiFlags.UNSUPPORTED_LONGITUDINAL) - -DBC = CAR.create_dbc_map() diff --git a/car/mazda/__init__.py b/car/mazda/__init__.py deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/car/mazda/carcontroller.py b/car/mazda/carcontroller.py deleted file mode 100644 index 3d41634879..0000000000 --- a/car/mazda/carcontroller.py +++ /dev/null @@ -1,66 +0,0 @@ -from cereal import car -from opendbc.can.packer import CANPacker -from openpilot.selfdrive.car import apply_driver_steer_torque_limits -from openpilot.selfdrive.car.interfaces import CarControllerBase -from openpilot.selfdrive.car.mazda import mazdacan -from openpilot.selfdrive.car.mazda.values import CarControllerParams, Buttons - -VisualAlert = car.CarControl.HUDControl.VisualAlert - - -class CarController(CarControllerBase): - def __init__(self, dbc_name, CP, VM): - self.CP = CP - self.apply_steer_last = 0 - self.packer = CANPacker(dbc_name) - self.brake_counter = 0 - self.frame = 0 - - def update(self, CC, CS, now_nanos): - can_sends = [] - - apply_steer = 0 - - if CC.latActive: - # calculate steer and also set limits due to driver torque - new_steer = int(round(CC.actuators.steer * CarControllerParams.STEER_MAX)) - apply_steer = apply_driver_steer_torque_limits(new_steer, self.apply_steer_last, - CS.out.steeringTorque, CarControllerParams) - - if CC.cruiseControl.cancel: - # If brake is pressed, let us wait >70ms before trying to disable crz to avoid - # a race condition with the stock system, where the second cancel from openpilot - # will disable the crz 'main on'. crz ctrl msg runs at 50hz. 70ms allows us to - # read 3 messages and most likely sync state before we attempt cancel. - self.brake_counter = self.brake_counter + 1 - if self.frame % 10 == 0 and not (CS.out.brakePressed and self.brake_counter < 7): - # Cancel Stock ACC if it's enabled while OP is disengaged - # Send at a rate of 10hz until we sync with stock ACC state - can_sends.append(mazdacan.create_button_cmd(self.packer, self.CP, CS.crz_btns_counter, Buttons.CANCEL)) - else: - self.brake_counter = 0 - if CC.cruiseControl.resume and self.frame % 5 == 0: - # Mazda Stop and Go requires a RES button (or gas) press if the car stops more than 3 seconds - # Send Resume button when planner wants car to move - can_sends.append(mazdacan.create_button_cmd(self.packer, self.CP, CS.crz_btns_counter, Buttons.RESUME)) - - self.apply_steer_last = apply_steer - - # send HUD alerts - if self.frame % 50 == 0: - ldw = CC.hudControl.visualAlert == VisualAlert.ldw - steer_required = CC.hudControl.visualAlert == VisualAlert.steerRequired - # TODO: find a way to silence audible warnings so we can add more hud alerts - steer_required = steer_required and CS.lkas_allowed_speed - can_sends.append(mazdacan.create_alert_command(self.packer, CS.cam_laneinfo, ldw, steer_required)) - - # send steering command - can_sends.append(mazdacan.create_steering_control(self.packer, self.CP, - self.frame, apply_steer, CS.cam_lkas)) - - new_actuators = CC.actuators.as_builder() - new_actuators.steer = apply_steer / CarControllerParams.STEER_MAX - new_actuators.steerOutputCan = apply_steer - - self.frame += 1 - return new_actuators, can_sends diff --git a/car/mazda/carstate.py b/car/mazda/carstate.py deleted file mode 100644 index 83b238fb68..0000000000 --- a/car/mazda/carstate.py +++ /dev/null @@ -1,153 +0,0 @@ -from cereal import car -from openpilot.common.conversions import Conversions as CV -from opendbc.can.can_define import CANDefine -from opendbc.can.parser import CANParser -from openpilot.selfdrive.car.interfaces import CarStateBase -from openpilot.selfdrive.car.mazda.values import DBC, LKAS_LIMITS, MazdaFlags - -class CarState(CarStateBase): - def __init__(self, CP): - super().__init__(CP) - - can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) - self.shifter_values = can_define.dv["GEAR"]["GEAR"] - - self.crz_btns_counter = 0 - self.acc_active_last = False - self.low_speed_alert = False - self.lkas_allowed_speed = False - self.lkas_disabled = False - - self.prev_distance_button = 0 - self.distance_button = 0 - - def update(self, cp, cp_cam): - - ret = car.CarState.new_message() - - self.prev_distance_button = self.distance_button - self.distance_button = cp.vl["CRZ_BTNS"]["DISTANCE_LESS"] - - ret.wheelSpeeds = self.get_wheel_speeds( - cp.vl["WHEEL_SPEEDS"]["FL"], - cp.vl["WHEEL_SPEEDS"]["FR"], - cp.vl["WHEEL_SPEEDS"]["RL"], - cp.vl["WHEEL_SPEEDS"]["RR"], - ) - ret.vEgoRaw = (ret.wheelSpeeds.fl + ret.wheelSpeeds.fr + ret.wheelSpeeds.rl + ret.wheelSpeeds.rr) / 4. - ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) - - # Match panda speed reading - speed_kph = cp.vl["ENGINE_DATA"]["SPEED"] - ret.standstill = speed_kph <= .1 - - can_gear = int(cp.vl["GEAR"]["GEAR"]) - ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(can_gear, None)) - - ret.genericToggle = bool(cp.vl["BLINK_INFO"]["HIGH_BEAMS"]) - ret.leftBlindspot = cp.vl["BSM"]["LEFT_BS_STATUS"] != 0 - ret.rightBlindspot = cp.vl["BSM"]["RIGHT_BS_STATUS"] != 0 - ret.leftBlinker, ret.rightBlinker = self.update_blinker_from_lamp(40, cp.vl["BLINK_INFO"]["LEFT_BLINK"] == 1, - cp.vl["BLINK_INFO"]["RIGHT_BLINK"] == 1) - - ret.steeringAngleDeg = cp.vl["STEER"]["STEER_ANGLE"] - ret.steeringTorque = cp.vl["STEER_TORQUE"]["STEER_TORQUE_SENSOR"] - ret.steeringPressed = abs(ret.steeringTorque) > LKAS_LIMITS.STEER_THRESHOLD - - ret.steeringTorqueEps = cp.vl["STEER_TORQUE"]["STEER_TORQUE_MOTOR"] - ret.steeringRateDeg = cp.vl["STEER_RATE"]["STEER_ANGLE_RATE"] - - # TODO: this should be from 0 - 1. - ret.brakePressed = cp.vl["PEDALS"]["BRAKE_ON"] == 1 - ret.brake = cp.vl["BRAKE"]["BRAKE_PRESSURE"] - - ret.seatbeltUnlatched = cp.vl["SEATBELT"]["DRIVER_SEATBELT"] == 0 - ret.doorOpen = any([cp.vl["DOORS"]["FL"], cp.vl["DOORS"]["FR"], - cp.vl["DOORS"]["BL"], cp.vl["DOORS"]["BR"]]) - - # TODO: this should be from 0 - 1. - ret.gas = cp.vl["ENGINE_DATA"]["PEDAL_GAS"] - ret.gasPressed = ret.gas > 0 - - # Either due to low speed or hands off - lkas_blocked = cp.vl["STEER_RATE"]["LKAS_BLOCK"] == 1 - - if self.CP.minSteerSpeed > 0: - # LKAS is enabled at 52kph going up and disabled at 45kph going down - # wait for LKAS_BLOCK signal to clear when going up since it lags behind the speed sometimes - if speed_kph > LKAS_LIMITS.ENABLE_SPEED and not lkas_blocked: - self.lkas_allowed_speed = True - elif speed_kph < LKAS_LIMITS.DISABLE_SPEED: - self.lkas_allowed_speed = False - else: - self.lkas_allowed_speed = True - - # TODO: the signal used for available seems to be the adaptive cruise signal, instead of the main on - # it should be used for carState.cruiseState.nonAdaptive instead - ret.cruiseState.available = cp.vl["CRZ_CTRL"]["CRZ_AVAILABLE"] == 1 - ret.cruiseState.enabled = cp.vl["CRZ_CTRL"]["CRZ_ACTIVE"] == 1 - ret.cruiseState.standstill = cp.vl["PEDALS"]["STANDSTILL"] == 1 - ret.cruiseState.speed = cp.vl["CRZ_EVENTS"]["CRZ_SPEED"] * CV.KPH_TO_MS - - if ret.cruiseState.enabled: - if not self.lkas_allowed_speed and self.acc_active_last: - self.low_speed_alert = True - else: - self.low_speed_alert = False - - # Check if LKAS is disabled due to lack of driver torque when all other states indicate - # it should be enabled (steer lockout). Don't warn until we actually get lkas active - # and lose it again, i.e, after initial lkas activation - ret.steerFaultTemporary = self.lkas_allowed_speed and lkas_blocked - - self.acc_active_last = ret.cruiseState.enabled - - self.crz_btns_counter = cp.vl["CRZ_BTNS"]["CTR"] - - # camera signals - self.lkas_disabled = cp_cam.vl["CAM_LANEINFO"]["LANE_LINES"] == 0 - self.cam_lkas = cp_cam.vl["CAM_LKAS"] - self.cam_laneinfo = cp_cam.vl["CAM_LANEINFO"] - ret.steerFaultPermanent = cp_cam.vl["CAM_LKAS"]["ERR_BIT_1"] == 1 - - return ret - - @staticmethod - def get_can_parser(CP): - messages = [ - # sig_address, frequency - ("BLINK_INFO", 10), - ("STEER", 67), - ("STEER_RATE", 83), - ("STEER_TORQUE", 83), - ("WHEEL_SPEEDS", 100), - ] - - if CP.flags & MazdaFlags.GEN1: - messages += [ - ("ENGINE_DATA", 100), - ("CRZ_CTRL", 50), - ("CRZ_EVENTS", 50), - ("CRZ_BTNS", 10), - ("PEDALS", 50), - ("BRAKE", 50), - ("SEATBELT", 10), - ("DOORS", 10), - ("GEAR", 20), - ("BSM", 10), - ] - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, 0) - - @staticmethod - def get_cam_can_parser(CP): - messages = [] - - if CP.flags & MazdaFlags.GEN1: - messages += [ - # sig_address, frequency - ("CAM_LANEINFO", 2), - ("CAM_LKAS", 16), - ] - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, 2) diff --git a/car/mazda/fingerprints.py b/car/mazda/fingerprints.py deleted file mode 100644 index f460fe9950..0000000000 --- a/car/mazda/fingerprints.py +++ /dev/null @@ -1,265 +0,0 @@ -from cereal import car -from openpilot.selfdrive.car.mazda.values import CAR - -Ecu = car.CarParams.Ecu - -FW_VERSIONS = { - CAR.MAZDA_CX5_2022: { - (Ecu.eps, 0x730, None): [ - b'KSD5-3210X-C-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'PEW5-188K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PW67-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX2D-188K2-G\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX2G-188K2-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX2H-188K2-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX2H-188K2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX85-188K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXFG-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'SH54-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'K131-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'KGWD-437K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'KSD5-437K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'GSH7-67XK2-S\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-T\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-U\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.transmission, 0x7e1, None): [ - b'PG69-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PW66-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXDL-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXFG-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXFG-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYB2-21PS1-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYB2-21PS1-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYJ3-21PS1-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'SH51-21PS1-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - CAR.MAZDA_CX5: { - (Ecu.eps, 0x730, None): [ - b'K319-3210X-A-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'KCB8-3210X-B-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'KJ01-3210X-G-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'KJ01-3210X-J-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'KJ01-3210X-M-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'PA53-188K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PAR4-188K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX2E-188K2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX2F-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX2G-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX2H-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX2H-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX2H-188K2-G\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX2K-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX38-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX42-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX68-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYFA-188K2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYFC-188K2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYFD-188K2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYNF-188K2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'SHKT-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'K123-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'K131-67XK2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'K131-67XK2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'K131-67XK2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'K131-67XK2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'K131-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'K123-437K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'KBJ5-437K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'KL2K-437K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'KN0W-437K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'B61L-67XK2-R\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'B61L-67XK2-S\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'B61L-67XK2-T\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'B61L-67XK2-V\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-M\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-N\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-R\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.transmission, 0x7e1, None): [ - b'PA66-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PA66-21PS1-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX39-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX39-21PS1-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX68-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYB1-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYB1-21PS1-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYB1-21PS1-G\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYB2-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYB2-21PS1-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYB2-21PS1-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYB2-21PS1-G\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYB2-21PS1-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYNC-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'SH9T-21PS1-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - CAR.MAZDA_CX9: { - (Ecu.eps, 0x730, None): [ - b'K070-3210X-C-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'KJ01-3210X-G-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'KJ01-3210X-L-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'PX23-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX24-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXM4-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXN8-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXN8-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYD7-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYD8-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYFM-188K2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYFM-188K2-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'K123-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'K131-67XK2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'K131-67XK2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'TK80-67XK2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'TK80-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'TA0B-437K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'TK79-437K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'TK79-437K2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'TM53-437K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'TN40-437K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'B61L-67XK2-P\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'B61L-67XK2-V\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-K\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'TK80-67XK2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.transmission, 0x7e1, None): [ - b'PXM4-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXM7-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXM7-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYD5-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYD5-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYD6-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYD6-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYFM-21PS1-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYFM-21PS1-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - CAR.MAZDA_3: { - (Ecu.eps, 0x730, None): [ - b'BHN1-3210X-J-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'K070-3210X-C-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'KR11-3210X-K-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'P5JD-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PY2P-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYJW-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYKC-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYKE-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'B63C-67XK2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GHP9-67Y10---41\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'K131-67XK2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'B45A-437AS-0-08\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'B61L-67XK2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'B61L-67XK2-P\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'B61L-67XK2-Q\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'B61L-67XK2-T\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.transmission, 0x7e1, None): [ - b'P52G-21PS1-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PY2S-21PS1-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYKA-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYKE-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYKE-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - CAR.MAZDA_6: { - (Ecu.eps, 0x730, None): [ - b'GBEF-3210X-B-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GBEF-3210X-C-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GFBC-3210X-A-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'PA34-188K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PX4F-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYH7-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYH7-188K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'K131-67XK2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'K131-67XK2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'GBVH-437K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GBVH-437K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GDDM-437K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'B61L-67XK2-S\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'B61L-67XK2-T\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-P\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.transmission, 0x7e1, None): [ - b'PA28-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYH3-21PS1-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PYH7-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, - CAR.MAZDA_CX9_2021: { - (Ecu.eps, 0x730, None): [ - b'TC3M-3210X-A-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'PXGW-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXGW-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXM4-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXM4-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXM6-188K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXM7-188K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x764, None): [ - b'K131-67XK2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'K131-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x760, None): [ - b'TA0B-437K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x706, None): [ - b'GSH7-67XK2-M\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-N\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-P\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-S\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-T\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'GSH7-67XK2-U\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.transmission, 0x7e1, None): [ - b'PXM4-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXM6-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'PXM7-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - ], - }, -} diff --git a/car/mazda/interface.py b/car/mazda/interface.py deleted file mode 100755 index 6992d49ffe..0000000000 --- a/car/mazda/interface.py +++ /dev/null @@ -1,50 +0,0 @@ -#!/usr/bin/env python3 -from cereal import car -from openpilot.common.conversions import Conversions as CV -from openpilot.selfdrive.car.mazda.values import CAR, LKAS_LIMITS -from openpilot.selfdrive.car import create_button_events, get_safety_config -from openpilot.selfdrive.car.interfaces import CarInterfaceBase - -ButtonType = car.CarState.ButtonEvent.Type -EventName = car.CarEvent.EventName - -class CarInterface(CarInterfaceBase): - - @staticmethod - def _get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs): - ret.carName = "mazda" - ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.mazda)] - ret.radarUnavailable = True - - ret.dashcamOnly = candidate not in (CAR.MAZDA_CX5_2022, CAR.MAZDA_CX9_2021) - - ret.steerActuatorDelay = 0.1 - ret.steerLimitTimer = 0.8 - - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) - - if candidate not in (CAR.MAZDA_CX5_2022, ): - ret.minSteerSpeed = LKAS_LIMITS.DISABLE_SPEED * CV.KPH_TO_MS - - ret.centerToFront = ret.wheelbase * 0.41 - - return ret - - # returns a car.CarState - def _update(self, c): - ret = self.CS.update(self.cp, self.cp_cam) - - # TODO: add button types for inc and dec - ret.buttonEvents = create_button_events(self.CS.distance_button, self.CS.prev_distance_button, {1: ButtonType.gapAdjustCruise}) - - # events - events = self.create_common_events(ret) - - if self.CS.lkas_disabled: - events.add(EventName.lkasDisabled) - elif self.CS.low_speed_alert: - events.add(EventName.belowSteerSpeed) - - ret.events = events.to_msg() - - return ret diff --git a/car/mazda/mazdacan.py b/car/mazda/mazdacan.py deleted file mode 100644 index 74f6af04c5..0000000000 --- a/car/mazda/mazdacan.py +++ /dev/null @@ -1,128 +0,0 @@ -from openpilot.selfdrive.car.mazda.values import Buttons, MazdaFlags - - -def create_steering_control(packer, CP, frame, apply_steer, lkas): - - tmp = apply_steer + 2048 - - lo = tmp & 0xFF - hi = tmp >> 8 - - # copy values from camera - b1 = int(lkas["BIT_1"]) - er1 = int(lkas["ERR_BIT_1"]) - lnv = 0 - ldw = 0 - er2 = int(lkas["ERR_BIT_2"]) - - # Some older models do have these, newer models don't. - # Either way, they all work just fine if set to zero. - steering_angle = 0 - b2 = 0 - - tmp = steering_angle + 2048 - ahi = tmp >> 10 - amd = (tmp & 0x3FF) >> 2 - amd = (amd >> 4) | (( amd & 0xF) << 4) - alo = (tmp & 0x3) << 2 - - ctr = frame % 16 - # bytes: [ 1 ] [ 2 ] [ 3 ] [ 4 ] - csum = 249 - ctr - hi - lo - (lnv << 3) - er1 - (ldw << 7) - ( er2 << 4) - (b1 << 5) - - # bytes [ 5 ] [ 6 ] [ 7 ] - csum = csum - ahi - amd - alo - b2 - - if ahi == 1: - csum = csum + 15 - - if csum < 0: - if csum < -256: - csum = csum + 512 - else: - csum = csum + 256 - - csum = csum % 256 - - values = {} - if CP.flags & MazdaFlags.GEN1: - values = { - "LKAS_REQUEST": apply_steer, - "CTR": ctr, - "ERR_BIT_1": er1, - "LINE_NOT_VISIBLE" : lnv, - "LDW": ldw, - "BIT_1": b1, - "ERR_BIT_2": er2, - "STEERING_ANGLE": steering_angle, - "ANGLE_ENABLED": b2, - "CHKSUM": csum - } - - return packer.make_can_msg("CAM_LKAS", 0, values) - - -def create_alert_command(packer, cam_msg: dict, ldw: bool, steer_required: bool): - values = {s: cam_msg[s] for s in [ - "LINE_VISIBLE", - "LINE_NOT_VISIBLE", - "LANE_LINES", - "BIT1", - "BIT2", - "BIT3", - "NO_ERR_BIT", - "S1", - "S1_HBEAM", - ]} - values.update({ - # TODO: what's the difference between all these? do we need to send all? - "HANDS_WARN_3_BITS": 0b111 if steer_required else 0, - "HANDS_ON_STEER_WARN": steer_required, - "HANDS_ON_STEER_WARN_2": steer_required, - - # TODO: right lane works, left doesn't - # TODO: need to do something about L/R - "LDW_WARN_LL": 0, - "LDW_WARN_RL": 0, - }) - return packer.make_can_msg("CAM_LANEINFO", 0, values) - - -def create_button_cmd(packer, CP, counter, button): - - can = int(button == Buttons.CANCEL) - res = int(button == Buttons.RESUME) - - if CP.flags & MazdaFlags.GEN1: - values = { - "CAN_OFF": can, - "CAN_OFF_INV": (can + 1) % 2, - - "SET_P": 0, - "SET_P_INV": 1, - - "RES": res, - "RES_INV": (res + 1) % 2, - - "SET_M": 0, - "SET_M_INV": 1, - - "DISTANCE_LESS": 0, - "DISTANCE_LESS_INV": 1, - - "DISTANCE_MORE": 0, - "DISTANCE_MORE_INV": 1, - - "MODE_X": 0, - "MODE_X_INV": 1, - - "MODE_Y": 0, - "MODE_Y_INV": 1, - - "BIT1": 1, - "BIT2": 1, - "BIT3": 1, - "CTR": (counter + 1) % 16, - } - - return packer.make_can_msg("CRZ_BTNS", 0, values) diff --git a/car/mazda/radar_interface.py b/car/mazda/radar_interface.py deleted file mode 100755 index b461fcd5f8..0000000000 --- a/car/mazda/radar_interface.py +++ /dev/null @@ -1,5 +0,0 @@ -#!/usr/bin/env python3 -from openpilot.selfdrive.car.interfaces import RadarInterfaceBase - -class RadarInterface(RadarInterfaceBase): - pass diff --git a/car/mazda/values.py b/car/mazda/values.py deleted file mode 100644 index a8c808d582..0000000000 --- a/car/mazda/values.py +++ /dev/null @@ -1,104 +0,0 @@ -from dataclasses import dataclass, field -from enum import IntFlag - -from cereal import car -from openpilot.common.conversions import Conversions as CV -from openpilot.selfdrive.car import CarSpecs, DbcDict, PlatformConfig, Platforms, dbc_dict -from openpilot.selfdrive.car.docs_definitions import CarHarness, CarDocs, CarParts -from openpilot.selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries - -Ecu = car.CarParams.Ecu - - -# Steer torque limits - -class CarControllerParams: - STEER_MAX = 800 # theoretical max_steer 2047 - STEER_DELTA_UP = 10 # torque increase per refresh - STEER_DELTA_DOWN = 25 # torque decrease per refresh - STEER_DRIVER_ALLOWANCE = 15 # allowed driver torque before start limiting - STEER_DRIVER_MULTIPLIER = 1 # weight driver torque - STEER_DRIVER_FACTOR = 1 # from dbc - STEER_ERROR_MAX = 350 # max delta between torque cmd and torque motor - STEER_STEP = 1 # 100 Hz - - def __init__(self, CP): - pass - - -@dataclass -class MazdaCarDocs(CarDocs): - package: str = "All" - car_parts: CarParts = field(default_factory=CarParts.common([CarHarness.mazda])) - - -@dataclass(frozen=True, kw_only=True) -class MazdaCarSpecs(CarSpecs): - tireStiffnessFactor: float = 0.7 # not optimized yet - - -class MazdaFlags(IntFlag): - # Static flags - # Gen 1 hardware: same CAN messages and same camera - GEN1 = 1 - - -@dataclass -class MazdaPlatformConfig(PlatformConfig): - dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict('mazda_2017', None)) - flags: int = MazdaFlags.GEN1 - - -class CAR(Platforms): - MAZDA_CX5 = MazdaPlatformConfig( - [MazdaCarDocs("Mazda CX-5 2017-21")], - MazdaCarSpecs(mass=3655 * CV.LB_TO_KG, wheelbase=2.7, steerRatio=15.5) - ) - MAZDA_CX9 = MazdaPlatformConfig( - [MazdaCarDocs("Mazda CX-9 2016-20")], - MazdaCarSpecs(mass=4217 * CV.LB_TO_KG, wheelbase=3.1, steerRatio=17.6) - ) - MAZDA_3 = MazdaPlatformConfig( - [MazdaCarDocs("Mazda 3 2017-18")], - MazdaCarSpecs(mass=2875 * CV.LB_TO_KG, wheelbase=2.7, steerRatio=14.0) - ) - MAZDA_6 = MazdaPlatformConfig( - [MazdaCarDocs("Mazda 6 2017-20")], - MazdaCarSpecs(mass=3443 * CV.LB_TO_KG, wheelbase=2.83, steerRatio=15.5) - ) - MAZDA_CX9_2021 = MazdaPlatformConfig( - [MazdaCarDocs("Mazda CX-9 2021-23", video_link="https://youtu.be/dA3duO4a0O4")], - MAZDA_CX9.specs - ) - MAZDA_CX5_2022 = MazdaPlatformConfig( - [MazdaCarDocs("Mazda CX-5 2022-24")], - MAZDA_CX5.specs, - ) - - -class LKAS_LIMITS: - STEER_THRESHOLD = 15 - DISABLE_SPEED = 45 # kph - ENABLE_SPEED = 52 # kph - - -class Buttons: - NONE = 0 - SET_PLUS = 1 - SET_MINUS = 2 - RESUME = 3 - CANCEL = 4 - - -FW_QUERY_CONFIG = FwQueryConfig( - requests=[ - # TODO: check data to ensure ABS does not skip ISO-TP frames on bus 0 - Request( - [StdQueries.MANUFACTURER_SOFTWARE_VERSION_REQUEST], - [StdQueries.MANUFACTURER_SOFTWARE_VERSION_RESPONSE], - bus=0, - ), - ], -) - -DBC = CAR.create_dbc_map() diff --git a/car/mock/__init__.py b/car/mock/__init__.py deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/car/mock/carcontroller.py b/car/mock/carcontroller.py deleted file mode 100644 index 0cd37c0369..0000000000 --- a/car/mock/carcontroller.py +++ /dev/null @@ -1,5 +0,0 @@ -from openpilot.selfdrive.car.interfaces import CarControllerBase - -class CarController(CarControllerBase): - def update(self, CC, CS, now_nanos): - return CC.actuators.as_builder(), [] diff --git a/car/mock/carstate.py b/car/mock/carstate.py deleted file mode 100644 index ece908b51c..0000000000 --- a/car/mock/carstate.py +++ /dev/null @@ -1,4 +0,0 @@ -from openpilot.selfdrive.car.interfaces import CarStateBase - -class CarState(CarStateBase): - pass diff --git a/car/mock/interface.py b/car/mock/interface.py deleted file mode 100755 index 7506bab053..0000000000 --- a/car/mock/interface.py +++ /dev/null @@ -1,32 +0,0 @@ -#!/usr/bin/env python3 -from cereal import car -import cereal.messaging as messaging -from openpilot.selfdrive.car.interfaces import CarInterfaceBase - -# mocked car interface for dashcam mode -class CarInterface(CarInterfaceBase): - def __init__(self, CP, CarController, CarState): - super().__init__(CP, CarController, CarState) - - self.speed = 0. - self.sm = messaging.SubMaster(['gpsLocation', 'gpsLocationExternal']) - - @staticmethod - def _get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs): - ret.carName = "mock" - ret.mass = 1700. - ret.wheelbase = 2.70 - ret.centerToFront = ret.wheelbase * 0.5 - ret.steerRatio = 13. - ret.dashcamOnly = True - return ret - - def _update(self, c): - self.sm.update(0) - gps_sock = 'gpsLocationExternal' if self.sm.recv_frame['gpsLocationExternal'] > 1 else 'gpsLocation' - - ret = car.CarState.new_message() - ret.vEgo = self.sm[gps_sock].speed - ret.vEgoRaw = self.sm[gps_sock].speed - - return ret diff --git a/car/mock/radar_interface.py b/car/mock/radar_interface.py deleted file mode 100644 index e654bd61fd..0000000000 --- a/car/mock/radar_interface.py +++ /dev/null @@ -1,4 +0,0 @@ -from openpilot.selfdrive.car.interfaces import RadarInterfaceBase - -class RadarInterface(RadarInterfaceBase): - pass diff --git a/car/mock/values.py b/car/mock/values.py deleted file mode 100644 index f98aac2ee3..0000000000 --- a/car/mock/values.py +++ /dev/null @@ -1,9 +0,0 @@ -from openpilot.selfdrive.car import CarSpecs, PlatformConfig, Platforms - - -class CAR(Platforms): - MOCK = PlatformConfig( - [], - CarSpecs(mass=1700, wheelbase=2.7, steerRatio=13), - {} - ) diff --git a/car/nissan/__init__.py b/car/nissan/__init__.py deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/car/nissan/carcontroller.py b/car/nissan/carcontroller.py deleted file mode 100644 index c7bd231398..0000000000 --- a/car/nissan/carcontroller.py +++ /dev/null @@ -1,82 +0,0 @@ -from cereal import car -from opendbc.can.packer import CANPacker -from openpilot.selfdrive.car import apply_std_steer_angle_limits -from openpilot.selfdrive.car.interfaces import CarControllerBase -from openpilot.selfdrive.car.nissan import nissancan -from openpilot.selfdrive.car.nissan.values import CAR, CarControllerParams - -VisualAlert = car.CarControl.HUDControl.VisualAlert - - -class CarController(CarControllerBase): - def __init__(self, dbc_name, CP, VM): - self.CP = CP - self.car_fingerprint = CP.carFingerprint - self.frame = 0 - - self.lkas_max_torque = 0 - self.apply_angle_last = 0 - - self.packer = CANPacker(dbc_name) - - def update(self, CC, CS, now_nanos): - actuators = CC.actuators - hud_control = CC.hudControl - pcm_cancel_cmd = CC.cruiseControl.cancel - - can_sends = [] - - ### STEER ### - steer_hud_alert = 1 if hud_control.visualAlert in (VisualAlert.steerRequired, VisualAlert.ldw) else 0 - - if CC.latActive: - # windup slower - apply_angle = apply_std_steer_angle_limits(actuators.steeringAngleDeg, self.apply_angle_last, CS.out.vEgoRaw, CarControllerParams) - - # Max torque from driver before EPS will give up and not apply torque - if not bool(CS.out.steeringPressed): - self.lkas_max_torque = CarControllerParams.LKAS_MAX_TORQUE - else: - # Scale max torque based on how much torque the driver is applying to the wheel - self.lkas_max_torque = max( - # Scale max torque down to half LKAX_MAX_TORQUE as a minimum - CarControllerParams.LKAS_MAX_TORQUE * 0.5, - # Start scaling torque at STEER_THRESHOLD - CarControllerParams.LKAS_MAX_TORQUE - 0.6 * max(0, abs(CS.out.steeringTorque) - CarControllerParams.STEER_THRESHOLD) - ) - - else: - apply_angle = CS.out.steeringAngleDeg - self.lkas_max_torque = 0 - - self.apply_angle_last = apply_angle - - if self.CP.carFingerprint in (CAR.NISSAN_ROGUE, CAR.NISSAN_XTRAIL, CAR.NISSAN_ALTIMA) and pcm_cancel_cmd: - can_sends.append(nissancan.create_acc_cancel_cmd(self.packer, self.car_fingerprint, CS.cruise_throttle_msg)) - - # TODO: Find better way to cancel! - # For some reason spamming the cancel button is unreliable on the Leaf - # We now cancel by making propilot think the seatbelt is unlatched, - # this generates a beep and a warning message every time you disengage - if self.CP.carFingerprint in (CAR.NISSAN_LEAF, CAR.NISSAN_LEAF_IC) and self.frame % 2 == 0: - can_sends.append(nissancan.create_cancel_msg(self.packer, CS.cancel_msg, pcm_cancel_cmd)) - - can_sends.append(nissancan.create_steering_control( - self.packer, apply_angle, self.frame, CC.latActive, self.lkas_max_torque)) - - # Below are the HUD messages. We copy the stock message and modify - if self.CP.carFingerprint != CAR.NISSAN_ALTIMA: - if self.frame % 2 == 0: - can_sends.append(nissancan.create_lkas_hud_msg(self.packer, CS.lkas_hud_msg, CC.enabled, hud_control.leftLaneVisible, hud_control.rightLaneVisible, - hud_control.leftLaneDepart, hud_control.rightLaneDepart)) - - if self.frame % 50 == 0: - can_sends.append(nissancan.create_lkas_hud_info_msg( - self.packer, CS.lkas_hud_info_msg, steer_hud_alert - )) - - new_actuators = actuators.as_builder() - new_actuators.steeringAngleDeg = apply_angle - - self.frame += 1 - return new_actuators, can_sends diff --git a/car/nissan/carstate.py b/car/nissan/carstate.py deleted file mode 100644 index 57146b49c4..0000000000 --- a/car/nissan/carstate.py +++ /dev/null @@ -1,197 +0,0 @@ -import copy -from collections import deque -from cereal import car -from opendbc.can.can_define import CANDefine -from openpilot.selfdrive.car.interfaces import CarStateBase -from openpilot.common.conversions import Conversions as CV -from opendbc.can.parser import CANParser -from openpilot.selfdrive.car.nissan.values import CAR, DBC, CarControllerParams - -TORQUE_SAMPLES = 12 - -class CarState(CarStateBase): - def __init__(self, CP): - super().__init__(CP) - can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) - - self.lkas_hud_msg = {} - self.lkas_hud_info_msg = {} - - self.steeringTorqueSamples = deque(TORQUE_SAMPLES*[0], TORQUE_SAMPLES) - self.shifter_values = can_define.dv["GEARBOX"]["GEAR_SHIFTER"] - - self.prev_distance_button = 0 - self.distance_button = 0 - - def update(self, cp, cp_adas, cp_cam): - ret = car.CarState.new_message() - - self.prev_distance_button = self.distance_button - self.distance_button = cp.vl["CRUISE_THROTTLE"]["FOLLOW_DISTANCE_BUTTON"] - - if self.CP.carFingerprint in (CAR.NISSAN_ROGUE, CAR.NISSAN_XTRAIL, CAR.NISSAN_ALTIMA): - ret.gas = cp.vl["GAS_PEDAL"]["GAS_PEDAL"] - elif self.CP.carFingerprint in (CAR.NISSAN_LEAF, CAR.NISSAN_LEAF_IC): - ret.gas = cp.vl["CRUISE_THROTTLE"]["GAS_PEDAL"] - - ret.gasPressed = bool(ret.gas > 3) - - if self.CP.carFingerprint in (CAR.NISSAN_ROGUE, CAR.NISSAN_XTRAIL, CAR.NISSAN_ALTIMA): - ret.brakePressed = bool(cp.vl["DOORS_LIGHTS"]["USER_BRAKE_PRESSED"]) - elif self.CP.carFingerprint in (CAR.NISSAN_LEAF, CAR.NISSAN_LEAF_IC): - ret.brakePressed = bool(cp.vl["CRUISE_THROTTLE"]["USER_BRAKE_PRESSED"]) - - ret.wheelSpeeds = self.get_wheel_speeds( - cp.vl["WHEEL_SPEEDS_FRONT"]["WHEEL_SPEED_FL"], - cp.vl["WHEEL_SPEEDS_FRONT"]["WHEEL_SPEED_FR"], - cp.vl["WHEEL_SPEEDS_REAR"]["WHEEL_SPEED_RL"], - cp.vl["WHEEL_SPEEDS_REAR"]["WHEEL_SPEED_RR"], - ) - ret.vEgoRaw = (ret.wheelSpeeds.fl + ret.wheelSpeeds.fr + ret.wheelSpeeds.rl + ret.wheelSpeeds.rr) / 4. - - ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) - ret.standstill = cp.vl["WHEEL_SPEEDS_REAR"]["WHEEL_SPEED_RL"] == 0.0 and cp.vl["WHEEL_SPEEDS_REAR"]["WHEEL_SPEED_RR"] == 0.0 - - if self.CP.carFingerprint == CAR.NISSAN_ALTIMA: - ret.cruiseState.enabled = bool(cp.vl["CRUISE_STATE"]["CRUISE_ENABLED"]) - else: - ret.cruiseState.enabled = bool(cp_adas.vl["CRUISE_STATE"]["CRUISE_ENABLED"]) - - if self.CP.carFingerprint in (CAR.NISSAN_ROGUE, CAR.NISSAN_XTRAIL): - ret.seatbeltUnlatched = cp.vl["HUD"]["SEATBELT_DRIVER_LATCHED"] == 0 - ret.cruiseState.available = bool(cp_cam.vl["PRO_PILOT"]["CRUISE_ON"]) - elif self.CP.carFingerprint in (CAR.NISSAN_LEAF, CAR.NISSAN_LEAF_IC): - if self.CP.carFingerprint == CAR.NISSAN_LEAF: - ret.seatbeltUnlatched = cp.vl["SEATBELT"]["SEATBELT_DRIVER_LATCHED"] == 0 - elif self.CP.carFingerprint == CAR.NISSAN_LEAF_IC: - ret.seatbeltUnlatched = cp.vl["CANCEL_MSG"]["CANCEL_SEATBELT"] == 1 - ret.cruiseState.available = bool(cp.vl["CRUISE_THROTTLE"]["CRUISE_AVAILABLE"]) - elif self.CP.carFingerprint == CAR.NISSAN_ALTIMA: - ret.seatbeltUnlatched = cp.vl["HUD"]["SEATBELT_DRIVER_LATCHED"] == 0 - ret.cruiseState.available = bool(cp_adas.vl["PRO_PILOT"]["CRUISE_ON"]) - - if self.CP.carFingerprint == CAR.NISSAN_ALTIMA: - speed = cp.vl["PROPILOT_HUD"]["SET_SPEED"] - else: - speed = cp_adas.vl["PROPILOT_HUD"]["SET_SPEED"] - - if speed != 255: - if self.CP.carFingerprint in (CAR.NISSAN_LEAF, CAR.NISSAN_LEAF_IC): - conversion = CV.MPH_TO_MS if cp.vl["HUD_SETTINGS"]["SPEED_MPH"] else CV.KPH_TO_MS - else: - conversion = CV.MPH_TO_MS if cp.vl["HUD"]["SPEED_MPH"] else CV.KPH_TO_MS - ret.cruiseState.speed = speed * conversion - ret.cruiseState.speedCluster = (speed - 1) * conversion # Speed on HUD is always 1 lower than actually sent on can bus - - if self.CP.carFingerprint == CAR.NISSAN_ALTIMA: - ret.steeringTorque = cp_cam.vl["STEER_TORQUE_SENSOR"]["STEER_TORQUE_DRIVER"] - else: - ret.steeringTorque = cp.vl["STEER_TORQUE_SENSOR"]["STEER_TORQUE_DRIVER"] - - self.steeringTorqueSamples.append(ret.steeringTorque) - # Filtering driver torque to prevent steeringPressed false positives - ret.steeringPressed = bool(abs(sum(self.steeringTorqueSamples) / TORQUE_SAMPLES) > CarControllerParams.STEER_THRESHOLD) - - ret.steeringAngleDeg = cp.vl["STEER_ANGLE_SENSOR"]["STEER_ANGLE"] - - ret.leftBlinker = bool(cp.vl["LIGHTS"]["LEFT_BLINKER"]) - ret.rightBlinker = bool(cp.vl["LIGHTS"]["RIGHT_BLINKER"]) - - ret.doorOpen = any([cp.vl["DOORS_LIGHTS"]["DOOR_OPEN_RR"], - cp.vl["DOORS_LIGHTS"]["DOOR_OPEN_RL"], - cp.vl["DOORS_LIGHTS"]["DOOR_OPEN_FR"], - cp.vl["DOORS_LIGHTS"]["DOOR_OPEN_FL"]]) - - ret.espDisabled = bool(cp.vl["ESP"]["ESP_DISABLED"]) - - can_gear = int(cp.vl["GEARBOX"]["GEAR_SHIFTER"]) - ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(can_gear, None)) - - if self.CP.carFingerprint == CAR.NISSAN_ALTIMA: - self.lkas_enabled = bool(cp.vl["LKAS_SETTINGS"]["LKAS_ENABLED"]) - else: - self.lkas_enabled = bool(cp_adas.vl["LKAS_SETTINGS"]["LKAS_ENABLED"]) - - self.cruise_throttle_msg = copy.copy(cp.vl["CRUISE_THROTTLE"]) - - if self.CP.carFingerprint in (CAR.NISSAN_LEAF, CAR.NISSAN_LEAF_IC): - self.cancel_msg = copy.copy(cp.vl["CANCEL_MSG"]) - - if self.CP.carFingerprint != CAR.NISSAN_ALTIMA: - self.lkas_hud_msg = copy.copy(cp_adas.vl["PROPILOT_HUD"]) - self.lkas_hud_info_msg = copy.copy(cp_adas.vl["PROPILOT_HUD_INFO_MSG"]) - - return ret - - @staticmethod - def get_can_parser(CP): - messages = [ - # sig_address, frequency - ("STEER_ANGLE_SENSOR", 100), - ("WHEEL_SPEEDS_REAR", 50), - ("WHEEL_SPEEDS_FRONT", 50), - ("ESP", 25), - ("GEARBOX", 25), - ("DOORS_LIGHTS", 10), - ("LIGHTS", 10), - ] - - if CP.carFingerprint in (CAR.NISSAN_ROGUE, CAR.NISSAN_XTRAIL, CAR.NISSAN_ALTIMA): - messages += [ - ("GAS_PEDAL", 100), - ("CRUISE_THROTTLE", 50), - ("HUD", 25), - ] - - elif CP.carFingerprint in (CAR.NISSAN_LEAF, CAR.NISSAN_LEAF_IC): - messages += [ - ("BRAKE_PEDAL", 100), - ("CRUISE_THROTTLE", 50), - ("CANCEL_MSG", 50), - ("HUD_SETTINGS", 25), - ("SEATBELT", 10), - ] - - if CP.carFingerprint == CAR.NISSAN_ALTIMA: - messages += [ - ("CRUISE_STATE", 10), - ("LKAS_SETTINGS", 10), - ("PROPILOT_HUD", 50), - ] - return CANParser(DBC[CP.carFingerprint]["pt"], messages, 1) - - messages.append(("STEER_TORQUE_SENSOR", 100)) - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, 0) - - @staticmethod - def get_adas_can_parser(CP): - # this function generates lists for signal, messages and initial values - - if CP.carFingerprint == CAR.NISSAN_ALTIMA: - messages = [ - ("LKAS", 100), - ("PRO_PILOT", 100), - ] - else: - messages = [ - ("PROPILOT_HUD_INFO_MSG", 2), - ("LKAS_SETTINGS", 10), - ("CRUISE_STATE", 50), - ("PROPILOT_HUD", 50), - ("LKAS", 100), - ] - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, 2) - - @staticmethod - def get_cam_can_parser(CP): - messages = [] - - if CP.carFingerprint in (CAR.NISSAN_ROGUE, CAR.NISSAN_XTRAIL): - messages.append(("PRO_PILOT", 100)) - elif CP.carFingerprint == CAR.NISSAN_ALTIMA: - messages.append(("STEER_TORQUE_SENSOR", 100)) - return CANParser(DBC[CP.carFingerprint]["pt"], messages, 0) - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, 1) diff --git a/car/nissan/fingerprints.py b/car/nissan/fingerprints.py deleted file mode 100644 index 743feeace9..0000000000 --- a/car/nissan/fingerprints.py +++ /dev/null @@ -1,119 +0,0 @@ -# ruff: noqa: E501 -from cereal import car -from openpilot.selfdrive.car.nissan.values import CAR - -Ecu = car.CarParams.Ecu - -FINGERPRINTS = { - CAR.NISSAN_XTRAIL: [{ - 2: 5, 42: 6, 346: 6, 347: 5, 348: 8, 349: 7, 361: 8, 386: 8, 389: 8, 397: 8, 398: 8, 403: 8, 520: 2, 523: 6, 548: 8, 645: 8, 658: 8, 665: 8, 666: 8, 674: 2, 682: 8, 683: 8, 689: 8, 723: 8, 758: 3, 768: 2, 783: 3, 851: 8, 855: 8, 1041: 8, 1055: 2, 1104: 4, 1105: 6, 1107: 4, 1108: 8, 1111: 4, 1227: 8, 1228: 8, 1247: 4, 1266: 8, 1273: 7, 1342: 1, 1376: 6, 1401: 8, 1474: 2, 1497: 3, 1821: 8, 1823: 8, 1837: 8, 2015: 8, 2016: 8, 2024: 8 - }, - { - 2: 5, 42: 6, 346: 6, 347: 5, 348: 8, 349: 7, 361: 8, 386: 8, 389: 8, 397: 8, 398: 8, 403: 8, 520: 2, 523: 6, 527: 1, 548: 8, 637: 4, 645: 8, 658: 8, 665: 8, 666: 8, 674: 2, 682: 8, 683: 8, 689: 8, 723: 8, 758: 3, 768: 6, 783: 3, 851: 8, 855: 8, 1041: 8, 1055: 2, 1104: 4, 1105: 6, 1107: 4, 1108: 8, 1111: 4, 1227: 8, 1228: 8, 1247: 4, 1266: 8, 1273: 7, 1342: 1, 1376: 6, 1401: 8, 1474: 8, 1497: 3, 1534: 6, 1792: 8, 1821: 8, 1823: 8, 1837: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 2015: 8, 2016: 8, 2024: 8 - }], - CAR.NISSAN_LEAF: [{ - 2: 5, 42: 6, 264: 3, 361: 8, 372: 8, 384: 8, 389: 8, 403: 8, 459: 7, 460: 4, 470: 8, 520: 1, 569: 8, 581: 8, 634: 7, 640: 8, 644: 8, 645: 8, 646: 5, 658: 8, 682: 8, 683: 8, 689: 8, 724: 6, 758: 3, 761: 2, 783: 3, 852: 8, 853: 8, 856: 8, 861: 8, 944: 1, 976: 6, 1008: 7, 1011: 7, 1057: 3, 1227: 8, 1228: 8, 1261: 5, 1342: 1, 1354: 8, 1361: 8, 1459: 8, 1477: 8, 1497: 3, 1549: 8, 1573: 6, 1821: 8, 1837: 8, 1856: 8, 1859: 8, 1861: 8, 1864: 8, 1874: 8, 1888: 8, 1891: 8, 1893: 8, 1906: 8, 1947: 8, 1949: 8, 1979: 8, 1981: 8, 2016: 8, 2017: 8, 2021: 8, 643: 5, 1792: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 1988: 8, 2000: 8, 2001: 8, 2004: 8, 2005: 8, 2015: 8 - }, - { - 2: 5, 42: 8, 264: 3, 361: 8, 372: 8, 384: 8, 389: 8, 403: 8, 459: 7, 460: 4, 470: 8, 520: 1, 569: 8, 581: 8, 634: 7, 640: 8, 643: 5, 644: 8, 645: 8, 646: 5, 658: 8, 682: 8, 683: 8, 689: 8, 724: 6, 758: 3, 761: 2, 772: 8, 773: 6, 774: 7, 775: 8, 776: 6, 777: 7, 778: 6, 783: 3, 852: 8, 853: 8, 856: 8, 861: 8, 943: 8, 944: 1, 976: 6, 1008: 7, 1009: 8, 1010: 8, 1011: 7, 1012: 8, 1013: 8, 1019: 8, 1020: 8, 1021: 8, 1022: 8, 1057: 3, 1227: 8, 1228: 8, 1261: 5, 1342: 1, 1354: 8, 1361: 8, 1402: 8, 1459: 8, 1477: 8, 1497: 3, 1549: 8, 1573: 6, 1821: 8, 1837: 8 - }], - CAR.NISSAN_LEAF_IC: [{ - 2: 5, 42: 6, 264: 3, 282: 8, 361: 8, 372: 8, 384: 8, 389: 8, 403: 8, 459: 7, 460: 4, 470: 8, 520: 1, 569: 8, 581: 8, 634: 7, 640: 8, 643: 5, 644: 8, 645: 8, 646: 5, 658: 8, 682: 8, 683: 8, 689: 8, 756: 5, 758: 3, 761: 2, 783: 3, 830: 2, 852: 8, 853: 8, 856: 8, 861: 8, 943: 8, 944: 1, 1001: 6, 1057: 3, 1227: 8, 1228: 8, 1229: 8, 1342: 1, 1354: 8, 1361: 8, 1459: 8, 1477: 8, 1497: 3, 1514: 6, 1549: 8, 1573: 6, 1792: 8, 1821: 8, 1822: 8, 1837: 8, 1838: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 1988: 8, 2000: 8, 2001: 8, 2004: 8, 2005: 8, 2015: 8, 2016: 8, 2017: 8 - }], - CAR.NISSAN_ROGUE: [{ - 2: 5, 42: 6, 346: 6, 347: 5, 348: 8, 349: 7, 361: 8, 386: 8, 389: 8, 397: 8, 398: 8, 403: 8, 520: 2, 523: 6, 548: 8, 634: 7, 643: 5, 645: 8, 658: 8, 665: 8, 666: 8, 674: 2, 682: 8, 683: 8, 689: 8, 723: 8, 758: 3, 772: 8, 773: 6, 774: 7, 775: 8, 776: 6, 777: 7, 778: 6, 783: 3, 851: 8, 855: 8, 1041: 8, 1042: 8, 1055: 2, 1104: 4, 1105: 6, 1107: 4, 1108: 8, 1110: 7, 1111: 7, 1227: 8, 1228: 8, 1247: 4, 1266: 8, 1273: 7, 1342: 1, 1376: 6, 1401: 8, 1474: 2, 1497: 3, 1534: 7, 1792: 8, 1821: 8, 1823: 8, 1837: 8, 1839: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 1988: 8, 2000: 8, 2001: 8, 2004: 8, 2005: 8, 2015: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8 - }], - CAR.NISSAN_ALTIMA: [{ - 2: 5, 42: 6, 346: 6, 347: 5, 348: 8, 349: 7, 361: 8, 386: 8, 389: 8, 397: 8, 398: 8, 403: 8, 438: 8, 451: 8, 517: 8, 520: 2, 522: 8, 523: 6, 539: 8, 541: 7, 542: 8, 543: 8, 544: 8, 545: 8, 546: 8, 547: 8, 548: 8, 570: 8, 576: 8, 577: 8, 582: 8, 583: 8, 584: 8, 586: 8, 587: 8, 588: 8, 589: 8, 590: 8, 591: 8, 592: 8, 600: 8, 601: 8, 610: 8, 611: 8, 612: 8, 614: 8, 615: 8, 616: 8, 617: 8, 622: 8, 623: 8, 634: 7, 638: 8, 645: 8, 648: 5, 654: 6, 658: 8, 659: 8, 660: 8, 661: 8, 665: 8, 666: 8, 674: 2, 675: 8, 676: 8, 682: 8, 683: 8, 684: 8, 685: 8, 686: 8, 687: 8, 689: 8, 690: 8, 703: 8, 708: 7, 709: 7, 711: 7, 712: 7, 713: 7, 714: 8, 715: 8, 716: 8, 717: 7, 718: 7, 719: 7, 720: 7, 723: 8, 726: 7, 727: 7, 728: 7, 735: 8, 746: 8, 748: 6, 749: 6, 750: 8, 758: 3, 772: 8, 773: 6, 774: 7, 775: 8, 776: 6, 777: 7, 778: 6, 779: 7, 781: 7, 782: 7, 783: 3, 851: 8, 855: 5, 1001: 6, 1041: 8, 1042: 8, 1055: 3, 1100: 7, 1104: 4, 1105: 6, 1107: 4, 1108: 8, 1110: 7, 1111: 7, 1144: 7, 1145: 7, 1227: 8, 1228: 8, 1229: 8, 1232: 8, 1247: 4, 1258: 8, 1259: 8, 1266: 8, 1273: 7, 1306: 1, 1314: 8, 1323: 8, 1324: 8, 1342: 1, 1376: 8, 1401: 8, 1454: 8, 1497: 3, 1514: 6, 1526: 8, 1527: 5, 1792: 8, 1821: 8, 1823: 8, 1837: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 1988: 8, 2000: 8, 2001: 8, 2004: 8, 2005: 8, 2015: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8 - }], -} - -FW_VERSIONS = { - CAR.NISSAN_ALTIMA: { - (Ecu.fwdCamera, 0x707, None): [ - b'284N86CA1D', - ], - (Ecu.eps, 0x742, None): [ - b'6CA2B\xa9A\x02\x02G8A89P90D6A\x00\x00\x01\x80', - ], - (Ecu.engine, 0x7e0, None): [ - b'237109HE2B', - ], - (Ecu.gateway, 0x18dad0f1, None): [ - b'284U29HE0A', - ], - }, - CAR.NISSAN_LEAF: { - (Ecu.abs, 0x740, None): [ - b'476605SA1C', - b'476605SA7D', - b'476605SC2D', - b'476606WK7B', - b'476606WK9B', - ], - (Ecu.eps, 0x742, None): [ - b'5SA2A\x99A\x05\x02N123F\x15b\x00\x00\x00\x00\x00\x00\x00\x80', - b'5SA2A\xb7A\x05\x02N123F\x15\xa2\x00\x00\x00\x00\x00\x00\x00\x80', - b'5SN2A\xb7A\x05\x02N123F\x15\xa2\x00\x00\x00\x00\x00\x00\x00\x80', - b'5SN2A\xb7A\x05\x02N126F\x15\xb2\x00\x00\x00\x00\x00\x00\x00\x80', - ], - (Ecu.fwdCamera, 0x707, None): [ - b'5SA0ADB\x04\x18\x00\x00\x00\x00\x00_*6\x04\x94a\x00\x00\x00\x80', - b'5SA2ADB\x04\x18\x00\x00\x00\x00\x00_*6\x04\x94a\x00\x00\x00\x80', - b'6WK2ADB\x04\x18\x00\x00\x00\x00\x00R;1\x18\x99\x10\x00\x00\x00\x80', - b'6WK2BDB\x04\x18\x00\x00\x00\x00\x00R;1\x18\x99\x10\x00\x00\x00\x80', - b'6WK2CDB\x04\x18\x00\x00\x00\x00\x00R=1\x18\x99\x10\x00\x00\x00\x80', - ], - (Ecu.gateway, 0x18dad0f1, None): [ - b'284U25SA3C', - b'284U25SP0C', - b'284U25SP1C', - b'284U26WK0A', - b'284U26WK0C', - ], - }, - CAR.NISSAN_LEAF_IC: { - (Ecu.fwdCamera, 0x707, None): [ - b'5SH1BDB\x04\x18\x00\x00\x00\x00\x00_-?\x04\x91\xf2\x00\x00\x00\x80', - b'5SH4BDB\x04\x18\x00\x00\x00\x00\x00_-?\x04\x91\xf2\x00\x00\x00\x80', - b'5SK0ADB\x04\x18\x00\x00\x00\x00\x00_(5\x07\x9aQ\x00\x00\x00\x80', - ], - (Ecu.abs, 0x740, None): [ - b'476605SD2E', - b'476605SH1D', - b'476605SK2A', - ], - (Ecu.eps, 0x742, None): [ - b'5SH2A\x99A\x05\x02N123F\x15\x81\x00\x00\x00\x00\x00\x00\x00\x80', - b'5SH2C\xb7A\x05\x02N123F\x15\xa3\x00\x00\x00\x00\x00\x00\x00\x80', - b'5SK3A\x99A\x05\x02N123F\x15u\x00\x00\x00\x00\x00\x00\x00\x80', - ], - (Ecu.gateway, 0x18dad0f1, None): [ - b'284U25SF0C', - b'284U25SH3A', - b'284U25SK2D', - ], - }, - CAR.NISSAN_XTRAIL: { - (Ecu.fwdCamera, 0x707, None): [ - b'284N86FR2A', - ], - (Ecu.abs, 0x740, None): [ - b'6FU0AD\x11\x02\x00\x02e\x95e\x80iQ#\x01\x00\x00\x00\x00\x00\x80', - b'6FU1BD\x11\x02\x00\x02e\x95e\x80iX#\x01\x00\x00\x00\x00\x00\x80', - ], - (Ecu.eps, 0x742, None): [ - b'6FP2A\x99A\x05\x02N123F\x18\x02\x00\x00\x00\x00\x00\x00\x00\x80', - ], - (Ecu.combinationMeter, 0x743, None): [ - b'6FR2A\x18B\x05\x17\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x80', - ], - (Ecu.engine, 0x7e0, None): [ - b'6FR9A\xa0A\x06\x04\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x80', - b'6FU9B\xa0A\x06\x04\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x80', - ], - (Ecu.gateway, 0x18dad0f1, None): [ - b'284U26FR0E', - ], - }, -} diff --git a/car/nissan/interface.py b/car/nissan/interface.py deleted file mode 100644 index 2e9a990610..0000000000 --- a/car/nissan/interface.py +++ /dev/null @@ -1,44 +0,0 @@ -from cereal import car -from panda import Panda -from openpilot.selfdrive.car import create_button_events, get_safety_config -from openpilot.selfdrive.car.interfaces import CarInterfaceBase -from openpilot.selfdrive.car.nissan.values import CAR - -ButtonType = car.CarState.ButtonEvent.Type - - -class CarInterface(CarInterfaceBase): - - @staticmethod - def _get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs): - ret.carName = "nissan" - ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.nissan)] - ret.autoResumeSng = False - - ret.steerLimitTimer = 1.0 - - ret.steerActuatorDelay = 0.1 - - ret.steerControlType = car.CarParams.SteerControlType.angle - ret.radarUnavailable = True - - if candidate == CAR.NISSAN_ALTIMA: - # Altima has EPS on C-CAN unlike the others that have it on V-CAN - ret.safetyConfigs[0].safetyParam |= Panda.FLAG_NISSAN_ALT_EPS_BUS - - return ret - - # returns a car.CarState - def _update(self, c): - ret = self.CS.update(self.cp, self.cp_adas, self.cp_cam) - - ret.buttonEvents = create_button_events(self.CS.distance_button, self.CS.prev_distance_button, {1: ButtonType.gapAdjustCruise}) - - events = self.create_common_events(ret, extra_gears=[car.CarState.GearShifter.brake]) - - if self.CS.lkas_enabled: - events.add(car.CarEvent.EventName.invalidLkasSetting) - - ret.events = events.to_msg() - - return ret diff --git a/car/nissan/nissancan.py b/car/nissan/nissancan.py deleted file mode 100644 index b9a1b4f843..0000000000 --- a/car/nissan/nissancan.py +++ /dev/null @@ -1,154 +0,0 @@ -import crcmod -from openpilot.selfdrive.car.nissan.values import CAR - -# TODO: add this checksum to the CANPacker -nissan_checksum = crcmod.mkCrcFun(0x11d, initCrc=0x00, rev=False, xorOut=0xff) - - -def create_steering_control(packer, apply_steer, frame, steer_on, lkas_max_torque): - values = { - "COUNTER": frame % 0x10, - "DESIRED_ANGLE": apply_steer, - "SET_0x80_2": 0x80, - "SET_0x80": 0x80, - "MAX_TORQUE": lkas_max_torque if steer_on else 0, - "LKA_ACTIVE": steer_on, - } - - dat = packer.make_can_msg("LKAS", 0, values)[2] - - values["CHECKSUM"] = nissan_checksum(dat[:7]) - return packer.make_can_msg("LKAS", 0, values) - - -def create_acc_cancel_cmd(packer, car_fingerprint, cruise_throttle_msg): - values = {s: cruise_throttle_msg[s] for s in [ - "COUNTER", - "PROPILOT_BUTTON", - "CANCEL_BUTTON", - "GAS_PEDAL_INVERTED", - "SET_BUTTON", - "RES_BUTTON", - "FOLLOW_DISTANCE_BUTTON", - "NO_BUTTON_PRESSED", - "GAS_PEDAL", - "USER_BRAKE_PRESSED", - "NEW_SIGNAL_2", - "GAS_PRESSED_INVERTED", - "unsure1", - "unsure2", - "unsure3", - ]} - can_bus = 1 if car_fingerprint == CAR.NISSAN_ALTIMA else 2 - - values["CANCEL_BUTTON"] = 1 - values["NO_BUTTON_PRESSED"] = 0 - values["PROPILOT_BUTTON"] = 0 - values["SET_BUTTON"] = 0 - values["RES_BUTTON"] = 0 - values["FOLLOW_DISTANCE_BUTTON"] = 0 - - return packer.make_can_msg("CRUISE_THROTTLE", can_bus, values) - - -def create_cancel_msg(packer, cancel_msg, cruise_cancel): - values = {s: cancel_msg[s] for s in [ - "CANCEL_SEATBELT", - "NEW_SIGNAL_1", - "NEW_SIGNAL_2", - "NEW_SIGNAL_3", - ]} - - if cruise_cancel: - values["CANCEL_SEATBELT"] = 1 - - return packer.make_can_msg("CANCEL_MSG", 2, values) - - -def create_lkas_hud_msg(packer, lkas_hud_msg, enabled, left_line, right_line, left_lane_depart, right_lane_depart): - values = {s: lkas_hud_msg[s] for s in [ - "LARGE_WARNING_FLASHING", - "SIDE_RADAR_ERROR_FLASHING1", - "SIDE_RADAR_ERROR_FLASHING2", - "LEAD_CAR", - "LEAD_CAR_ERROR", - "FRONT_RADAR_ERROR", - "FRONT_RADAR_ERROR_FLASHING", - "SIDE_RADAR_ERROR_FLASHING3", - "LKAS_ERROR_FLASHING", - "SAFETY_SHIELD_ACTIVE", - "RIGHT_LANE_GREEN_FLASH", - "LEFT_LANE_GREEN_FLASH", - "FOLLOW_DISTANCE", - "AUDIBLE_TONE", - "SPEED_SET_ICON", - "SMALL_STEERING_WHEEL_ICON", - "unknown59", - "unknown55", - "unknown26", - "unknown28", - "unknown31", - "SET_SPEED", - "unknown43", - "unknown08", - "unknown05", - "unknown02", - ]} - - values["RIGHT_LANE_YELLOW_FLASH"] = 1 if right_lane_depart else 0 - values["LEFT_LANE_YELLOW_FLASH"] = 1 if left_lane_depart else 0 - - values["LARGE_STEERING_WHEEL_ICON"] = 2 if enabled else 0 - values["RIGHT_LANE_GREEN"] = 1 if right_line and enabled else 0 - values["LEFT_LANE_GREEN"] = 1 if left_line and enabled else 0 - - return packer.make_can_msg("PROPILOT_HUD", 0, values) - - -def create_lkas_hud_info_msg(packer, lkas_hud_info_msg, steer_hud_alert): - values = {s: lkas_hud_info_msg[s] for s in [ - "NA_HIGH_ACCEL_TEMP", - "SIDE_RADAR_NA_HIGH_CABIN_TEMP", - "SIDE_RADAR_MALFUNCTION", - "LKAS_MALFUNCTION", - "FRONT_RADAR_MALFUNCTION", - "SIDE_RADAR_NA_CLEAN_REAR_CAMERA", - "NA_POOR_ROAD_CONDITIONS", - "CURRENTLY_UNAVAILABLE", - "SAFETY_SHIELD_OFF", - "FRONT_COLLISION_NA_FRONT_RADAR_OBSTRUCTION", - "PEDAL_MISSAPPLICATION_SYSTEM_ACTIVATED", - "SIDE_IMPACT_NA_RADAR_OBSTRUCTION", - "WARNING_DO_NOT_ENTER", - "SIDE_IMPACT_SYSTEM_OFF", - "SIDE_IMPACT_MALFUNCTION", - "FRONT_COLLISION_MALFUNCTION", - "SIDE_RADAR_MALFUNCTION2", - "LKAS_MALFUNCTION2", - "FRONT_RADAR_MALFUNCTION2", - "PROPILOT_NA_MSGS", - "BOTTOM_MSG", - "HANDS_ON_WHEEL_WARNING", - "WARNING_STEP_ON_BRAKE_NOW", - "PROPILOT_NA_FRONT_CAMERA_OBSTRUCTED", - "PROPILOT_NA_HIGH_CABIN_TEMP", - "WARNING_PROPILOT_MALFUNCTION", - "ACC_UNAVAILABLE_HIGH_CABIN_TEMP", - "ACC_NA_FRONT_CAMERA_IMPARED", - "unknown07", - "unknown10", - "unknown15", - "unknown23", - "unknown19", - "unknown31", - "unknown32", - "unknown46", - "unknown61", - "unknown55", - "unknown50", - ]} - - if steer_hud_alert: - values["HANDS_ON_WHEEL_WARNING"] = 1 - - return packer.make_can_msg("PROPILOT_HUD_INFO_MSG", 0, values) diff --git a/car/nissan/radar_interface.py b/car/nissan/radar_interface.py deleted file mode 100644 index e654bd61fd..0000000000 --- a/car/nissan/radar_interface.py +++ /dev/null @@ -1,4 +0,0 @@ -from openpilot.selfdrive.car.interfaces import RadarInterfaceBase - -class RadarInterface(RadarInterfaceBase): - pass diff --git a/car/nissan/values.py b/car/nissan/values.py deleted file mode 100644 index eecffb21bc..0000000000 --- a/car/nissan/values.py +++ /dev/null @@ -1,107 +0,0 @@ -from dataclasses import dataclass, field - -from cereal import car -from panda.python import uds -from openpilot.selfdrive.car import AngleRateLimit, CarSpecs, DbcDict, PlatformConfig, Platforms, dbc_dict -from openpilot.selfdrive.car.docs_definitions import CarDocs, CarHarness, CarParts -from openpilot.selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries - -Ecu = car.CarParams.Ecu - - -class CarControllerParams: - ANGLE_RATE_LIMIT_UP = AngleRateLimit(speed_bp=[0., 5., 15.], angle_v=[5., .8, .15]) - ANGLE_RATE_LIMIT_DOWN = AngleRateLimit(speed_bp=[0., 5., 15.], angle_v=[5., 3.5, 0.4]) - LKAS_MAX_TORQUE = 1 # A value of 1 is easy to overpower - STEER_THRESHOLD = 1.0 - - def __init__(self, CP): - pass - - -@dataclass -class NissanCarDocs(CarDocs): - package: str = "ProPILOT Assist" - car_parts: CarParts = field(default_factory=CarParts.common([CarHarness.nissan_a])) - - -@dataclass(frozen=True) -class NissanCarSpecs(CarSpecs): - centerToFrontRatio: float = 0.44 - steerRatio: float = 17. - - -@dataclass -class NissanPlatformConfig(PlatformConfig): - dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict('nissan_x_trail_2017_generated', None)) - - -class CAR(Platforms): - NISSAN_XTRAIL = NissanPlatformConfig( - [NissanCarDocs("Nissan X-Trail 2017")], - NissanCarSpecs(mass=1610, wheelbase=2.705) - ) - NISSAN_LEAF = NissanPlatformConfig( - [NissanCarDocs("Nissan Leaf 2018-23", video_link="https://youtu.be/vaMbtAh_0cY")], - NissanCarSpecs(mass=1610, wheelbase=2.705), - dbc_dict('nissan_leaf_2018_generated', None), - ) - # Leaf with ADAS ECU found behind instrument cluster instead of glovebox - # Currently the only known difference between them is the inverted seatbelt signal. - NISSAN_LEAF_IC = NISSAN_LEAF.override(car_docs=[]) - NISSAN_ROGUE = NissanPlatformConfig( - [NissanCarDocs("Nissan Rogue 2018-20")], - NissanCarSpecs(mass=1610, wheelbase=2.705) - ) - NISSAN_ALTIMA = NissanPlatformConfig( - [NissanCarDocs("Nissan Altima 2019-20", car_parts=CarParts.common([CarHarness.nissan_b]))], - NissanCarSpecs(mass=1492, wheelbase=2.824) - ) - - -DBC = CAR.create_dbc_map() - -# Default diagnostic session -NISSAN_DIAGNOSTIC_REQUEST_KWP = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL, 0x81]) -NISSAN_DIAGNOSTIC_RESPONSE_KWP = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL + 0x40, 0x81]) - -# Manufacturer specific -NISSAN_DIAGNOSTIC_REQUEST_KWP_2 = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL, 0xda]) -NISSAN_DIAGNOSTIC_RESPONSE_KWP_2 = bytes([uds.SERVICE_TYPE.DIAGNOSTIC_SESSION_CONTROL + 0x40, 0xda]) - -NISSAN_VERSION_REQUEST_KWP = b'\x21\x83' -NISSAN_VERSION_RESPONSE_KWP = b'\x61\x83' - -NISSAN_RX_OFFSET = 0x20 - -FW_QUERY_CONFIG = FwQueryConfig( - requests=[request for bus, logging in ((0, False), (1, True)) for request in [ - Request( - [NISSAN_DIAGNOSTIC_REQUEST_KWP, NISSAN_VERSION_REQUEST_KWP], - [NISSAN_DIAGNOSTIC_RESPONSE_KWP, NISSAN_VERSION_RESPONSE_KWP], - bus=bus, - logging=logging, - ), - Request( - [NISSAN_DIAGNOSTIC_REQUEST_KWP, NISSAN_VERSION_REQUEST_KWP], - [NISSAN_DIAGNOSTIC_RESPONSE_KWP, NISSAN_VERSION_RESPONSE_KWP], - rx_offset=NISSAN_RX_OFFSET, - bus=bus, - logging=logging, - ), - # Rogue's engine solely responds to this - Request( - [NISSAN_DIAGNOSTIC_REQUEST_KWP_2, NISSAN_VERSION_REQUEST_KWP], - [NISSAN_DIAGNOSTIC_RESPONSE_KWP_2, NISSAN_VERSION_RESPONSE_KWP], - bus=bus, - logging=logging, - ), - Request( - [StdQueries.MANUFACTURER_SOFTWARE_VERSION_REQUEST], - [StdQueries.MANUFACTURER_SOFTWARE_VERSION_RESPONSE], - rx_offset=NISSAN_RX_OFFSET, - bus=bus, - logging=logging, - ), - ]], -) diff --git a/car/subaru/__init__.py b/car/subaru/__init__.py deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/car/subaru/carcontroller.py b/car/subaru/carcontroller.py deleted file mode 100644 index d89ae8c639..0000000000 --- a/car/subaru/carcontroller.py +++ /dev/null @@ -1,144 +0,0 @@ -from openpilot.common.numpy_fast import clip, interp -from opendbc.can.packer import CANPacker -from openpilot.selfdrive.car import apply_driver_steer_torque_limits, common_fault_avoidance -from openpilot.selfdrive.car.interfaces import CarControllerBase -from openpilot.selfdrive.car.subaru import subarucan -from openpilot.selfdrive.car.subaru.values import DBC, GLOBAL_ES_ADDR, CanBus, CarControllerParams, SubaruFlags - -# FIXME: These limits aren't exact. The real limit is more than likely over a larger time period and -# involves the total steering angle change rather than rate, but these limits work well for now -MAX_STEER_RATE = 25 # deg/s -MAX_STEER_RATE_FRAMES = 7 # tx control frames needed before torque can be cut - - -class CarController(CarControllerBase): - def __init__(self, dbc_name, CP, VM): - self.CP = CP - self.apply_steer_last = 0 - self.frame = 0 - - self.cruise_button_prev = 0 - self.steer_rate_counter = 0 - - self.p = CarControllerParams(CP) - self.packer = CANPacker(DBC[CP.carFingerprint]['pt']) - - def update(self, CC, CS, now_nanos): - actuators = CC.actuators - hud_control = CC.hudControl - pcm_cancel_cmd = CC.cruiseControl.cancel - - can_sends = [] - - # *** steering *** - if (self.frame % self.p.STEER_STEP) == 0: - apply_steer = int(round(actuators.steer * self.p.STEER_MAX)) - - # limits due to driver torque - - new_steer = int(round(apply_steer)) - apply_steer = apply_driver_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.p) - - if not CC.latActive: - apply_steer = 0 - - if self.CP.flags & SubaruFlags.PREGLOBAL: - can_sends.append(subarucan.create_preglobal_steering_control(self.packer, self.frame // self.p.STEER_STEP, apply_steer, CC.latActive)) - else: - apply_steer_req = CC.latActive - - if self.CP.flags & SubaruFlags.STEER_RATE_LIMITED: - # Steering rate fault prevention - self.steer_rate_counter, apply_steer_req = \ - common_fault_avoidance(abs(CS.out.steeringRateDeg) > MAX_STEER_RATE, apply_steer_req, - self.steer_rate_counter, MAX_STEER_RATE_FRAMES) - - can_sends.append(subarucan.create_steering_control(self.packer, apply_steer, apply_steer_req)) - - self.apply_steer_last = apply_steer - - # *** longitudinal *** - - if CC.longActive: - apply_throttle = int(round(interp(actuators.accel, CarControllerParams.THROTTLE_LOOKUP_BP, CarControllerParams.THROTTLE_LOOKUP_V))) - apply_rpm = int(round(interp(actuators.accel, CarControllerParams.RPM_LOOKUP_BP, CarControllerParams.RPM_LOOKUP_V))) - apply_brake = int(round(interp(actuators.accel, CarControllerParams.BRAKE_LOOKUP_BP, CarControllerParams.BRAKE_LOOKUP_V))) - - # limit min and max values - cruise_throttle = clip(apply_throttle, CarControllerParams.THROTTLE_MIN, CarControllerParams.THROTTLE_MAX) - cruise_rpm = clip(apply_rpm, CarControllerParams.RPM_MIN, CarControllerParams.RPM_MAX) - cruise_brake = clip(apply_brake, CarControllerParams.BRAKE_MIN, CarControllerParams.BRAKE_MAX) - else: - cruise_throttle = CarControllerParams.THROTTLE_INACTIVE - cruise_rpm = CarControllerParams.RPM_MIN - cruise_brake = CarControllerParams.BRAKE_MIN - - # *** alerts and pcm cancel *** - if self.CP.flags & SubaruFlags.PREGLOBAL: - if self.frame % 5 == 0: - # 1 = main, 2 = set shallow, 3 = set deep, 4 = resume shallow, 5 = resume deep - # disengage ACC when OP is disengaged - if pcm_cancel_cmd: - cruise_button = 1 - # turn main on if off and past start-up state - elif not CS.out.cruiseState.available and CS.ready: - cruise_button = 1 - else: - cruise_button = CS.cruise_button - - # unstick previous mocked button press - if cruise_button == 1 and self.cruise_button_prev == 1: - cruise_button = 0 - self.cruise_button_prev = cruise_button - - can_sends.append(subarucan.create_preglobal_es_distance(self.packer, cruise_button, CS.es_distance_msg)) - - else: - if self.frame % 10 == 0: - can_sends.append(subarucan.create_es_dashstatus(self.packer, self.frame // 10, CS.es_dashstatus_msg, CC.enabled, - self.CP.openpilotLongitudinalControl, CC.longActive, hud_control.leadVisible)) - - can_sends.append(subarucan.create_es_lkas_state(self.packer, self.frame // 10, CS.es_lkas_state_msg, CC.enabled, hud_control.visualAlert, - hud_control.leftLaneVisible, hud_control.rightLaneVisible, - hud_control.leftLaneDepart, hud_control.rightLaneDepart)) - - if self.CP.flags & SubaruFlags.SEND_INFOTAINMENT: - can_sends.append(subarucan.create_es_infotainment(self.packer, self.frame // 10, CS.es_infotainment_msg, hud_control.visualAlert)) - - if self.CP.openpilotLongitudinalControl: - if self.frame % 5 == 0: - can_sends.append(subarucan.create_es_status(self.packer, self.frame // 5, CS.es_status_msg, - self.CP.openpilotLongitudinalControl, CC.longActive, cruise_rpm)) - - can_sends.append(subarucan.create_es_brake(self.packer, self.frame // 5, CS.es_brake_msg, - self.CP.openpilotLongitudinalControl, CC.longActive, cruise_brake)) - - can_sends.append(subarucan.create_es_distance(self.packer, self.frame // 5, CS.es_distance_msg, 0, pcm_cancel_cmd, - self.CP.openpilotLongitudinalControl, cruise_brake > 0, cruise_throttle)) - else: - if pcm_cancel_cmd: - if not (self.CP.flags & SubaruFlags.HYBRID): - bus = CanBus.alt if self.CP.flags & SubaruFlags.GLOBAL_GEN2 else CanBus.main - can_sends.append(subarucan.create_es_distance(self.packer, CS.es_distance_msg["COUNTER"] + 1, CS.es_distance_msg, bus, pcm_cancel_cmd)) - - if self.CP.flags & SubaruFlags.DISABLE_EYESIGHT: - # Tester present (keeps eyesight disabled) - if self.frame % 100 == 0: - can_sends.append([GLOBAL_ES_ADDR, 0, b"\x02\x3E\x80\x00\x00\x00\x00\x00", CanBus.camera]) - - # Create all of the other eyesight messages to keep the rest of the car happy when eyesight is disabled - if self.frame % 5 == 0: - can_sends.append(subarucan.create_es_highbeamassist(self.packer)) - - if self.frame % 10 == 0: - can_sends.append(subarucan.create_es_static_1(self.packer)) - - if self.frame % 2 == 0: - can_sends.append(subarucan.create_es_static_2(self.packer)) - - new_actuators = actuators.as_builder() - new_actuators.steer = self.apply_steer_last / self.p.STEER_MAX - new_actuators.steerOutputCan = self.apply_steer_last - - self.frame += 1 - return new_actuators, can_sends diff --git a/car/subaru/carstate.py b/car/subaru/carstate.py deleted file mode 100644 index 821ff2c151..0000000000 --- a/car/subaru/carstate.py +++ /dev/null @@ -1,229 +0,0 @@ -import copy -from cereal import car -from opendbc.can.can_define import CANDefine -from openpilot.common.conversions import Conversions as CV -from openpilot.selfdrive.car.interfaces import CarStateBase -from opendbc.can.parser import CANParser -from openpilot.selfdrive.car.subaru.values import DBC, CanBus, SubaruFlags -from openpilot.selfdrive.car import CanSignalRateCalculator - - -class CarState(CarStateBase): - def __init__(self, CP): - super().__init__(CP) - can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) - self.shifter_values = can_define.dv["Transmission"]["Gear"] - - self.angle_rate_calulator = CanSignalRateCalculator(50) - - def update(self, cp, cp_cam, cp_body): - ret = car.CarState.new_message() - - throttle_msg = cp.vl["Throttle"] if not (self.CP.flags & SubaruFlags.HYBRID) else cp_body.vl["Throttle_Hybrid"] - ret.gas = throttle_msg["Throttle_Pedal"] / 255. - - ret.gasPressed = ret.gas > 1e-5 - if self.CP.flags & SubaruFlags.PREGLOBAL: - ret.brakePressed = cp.vl["Brake_Pedal"]["Brake_Pedal"] > 0 - else: - cp_brakes = cp_body if self.CP.flags & SubaruFlags.GLOBAL_GEN2 else cp - ret.brakePressed = cp_brakes.vl["Brake_Status"]["Brake"] == 1 - - cp_es_distance = cp_body if self.CP.flags & (SubaruFlags.GLOBAL_GEN2 | SubaruFlags.HYBRID) else cp_cam - if not (self.CP.flags & SubaruFlags.HYBRID): - eyesight_fault = bool(cp_es_distance.vl["ES_Distance"]["Cruise_Fault"]) - - # if openpilot is controlling long, an eyesight fault is a non-critical fault. otherwise it's an ACC fault - if self.CP.openpilotLongitudinalControl: - ret.carFaultedNonCritical = eyesight_fault - else: - ret.accFaulted = eyesight_fault - - cp_wheels = cp_body if self.CP.flags & SubaruFlags.GLOBAL_GEN2 else cp - ret.wheelSpeeds = self.get_wheel_speeds( - cp_wheels.vl["Wheel_Speeds"]["FL"], - cp_wheels.vl["Wheel_Speeds"]["FR"], - cp_wheels.vl["Wheel_Speeds"]["RL"], - cp_wheels.vl["Wheel_Speeds"]["RR"], - ) - ret.vEgoRaw = (ret.wheelSpeeds.fl + ret.wheelSpeeds.fr + ret.wheelSpeeds.rl + ret.wheelSpeeds.rr) / 4. - ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) - ret.standstill = ret.vEgoRaw == 0 - - # continuous blinker signals for assisted lane change - ret.leftBlinker, ret.rightBlinker = self.update_blinker_from_lamp(50, cp.vl["Dashlights"]["LEFT_BLINKER"], - cp.vl["Dashlights"]["RIGHT_BLINKER"]) - - if self.CP.enableBsm: - ret.leftBlindspot = (cp.vl["BSD_RCTA"]["L_ADJACENT"] == 1) or (cp.vl["BSD_RCTA"]["L_APPROACHING"] == 1) - ret.rightBlindspot = (cp.vl["BSD_RCTA"]["R_ADJACENT"] == 1) or (cp.vl["BSD_RCTA"]["R_APPROACHING"] == 1) - - cp_transmission = cp_body if self.CP.flags & SubaruFlags.HYBRID else cp - can_gear = int(cp_transmission.vl["Transmission"]["Gear"]) - ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(can_gear, None)) - - ret.steeringAngleDeg = cp.vl["Steering_Torque"]["Steering_Angle"] - - if not (self.CP.flags & SubaruFlags.PREGLOBAL): - # ideally we get this from the car, but unclear if it exists. diagnostic software doesn't even have it - ret.steeringRateDeg = self.angle_rate_calulator.update(ret.steeringAngleDeg, cp.vl["Steering_Torque"]["COUNTER"]) - - ret.steeringTorque = cp.vl["Steering_Torque"]["Steer_Torque_Sensor"] - ret.steeringTorqueEps = cp.vl["Steering_Torque"]["Steer_Torque_Output"] - - steer_threshold = 75 if self.CP.flags & SubaruFlags.PREGLOBAL else 80 - ret.steeringPressed = abs(ret.steeringTorque) > steer_threshold - - cp_cruise = cp_body if self.CP.flags & SubaruFlags.GLOBAL_GEN2 else cp - if self.CP.flags & SubaruFlags.HYBRID: - ret.cruiseState.enabled = cp_cam.vl["ES_DashStatus"]['Cruise_Activated'] != 0 - ret.cruiseState.available = cp_cam.vl["ES_DashStatus"]['Cruise_On'] != 0 - else: - ret.cruiseState.enabled = cp_cruise.vl["CruiseControl"]["Cruise_Activated"] != 0 - ret.cruiseState.available = cp_cruise.vl["CruiseControl"]["Cruise_On"] != 0 - ret.cruiseState.speed = cp_cam.vl["ES_DashStatus"]["Cruise_Set_Speed"] * CV.KPH_TO_MS - - if (self.CP.flags & SubaruFlags.PREGLOBAL and cp.vl["Dash_State2"]["UNITS"] == 1) or \ - (not (self.CP.flags & SubaruFlags.PREGLOBAL) and cp.vl["Dashlights"]["UNITS"] == 1): - ret.cruiseState.speed *= CV.MPH_TO_KPH - - ret.seatbeltUnlatched = cp.vl["Dashlights"]["SEATBELT_FL"] == 1 - ret.doorOpen = any([cp.vl["BodyInfo"]["DOOR_OPEN_RR"], - cp.vl["BodyInfo"]["DOOR_OPEN_RL"], - cp.vl["BodyInfo"]["DOOR_OPEN_FR"], - cp.vl["BodyInfo"]["DOOR_OPEN_FL"]]) - ret.steerFaultPermanent = cp.vl["Steering_Torque"]["Steer_Error_1"] == 1 - - if self.CP.flags & SubaruFlags.PREGLOBAL: - self.cruise_button = cp_cam.vl["ES_Distance"]["Cruise_Button"] - self.ready = not cp_cam.vl["ES_DashStatus"]["Not_Ready_Startup"] - else: - ret.steerFaultTemporary = cp.vl["Steering_Torque"]["Steer_Warning"] == 1 - ret.cruiseState.nonAdaptive = cp_cam.vl["ES_DashStatus"]["Conventional_Cruise"] == 1 - ret.cruiseState.standstill = cp_cam.vl["ES_DashStatus"]["Cruise_State"] == 3 - ret.stockFcw = (cp_cam.vl["ES_LKAS_State"]["LKAS_Alert"] == 1) or \ - (cp_cam.vl["ES_LKAS_State"]["LKAS_Alert"] == 2) - - self.es_lkas_state_msg = copy.copy(cp_cam.vl["ES_LKAS_State"]) - cp_es_brake = cp_body if self.CP.flags & SubaruFlags.GLOBAL_GEN2 else cp_cam - self.es_brake_msg = copy.copy(cp_es_brake.vl["ES_Brake"]) - cp_es_status = cp_body if self.CP.flags & SubaruFlags.GLOBAL_GEN2 else cp_cam - - # TODO: Hybrid cars don't have ES_Distance, need a replacement - if not (self.CP.flags & SubaruFlags.HYBRID): - # 8 is known AEB, there are a few other values related to AEB we ignore - ret.stockAeb = (cp_es_distance.vl["ES_Brake"]["AEB_Status"] == 8) and \ - (cp_es_distance.vl["ES_Brake"]["Brake_Pressure"] != 0) - - self.es_status_msg = copy.copy(cp_es_status.vl["ES_Status"]) - self.cruise_control_msg = copy.copy(cp_cruise.vl["CruiseControl"]) - - if not (self.CP.flags & SubaruFlags.HYBRID): - self.es_distance_msg = copy.copy(cp_es_distance.vl["ES_Distance"]) - - self.es_dashstatus_msg = copy.copy(cp_cam.vl["ES_DashStatus"]) - if self.CP.flags & SubaruFlags.SEND_INFOTAINMENT: - self.es_infotainment_msg = copy.copy(cp_cam.vl["ES_Infotainment"]) - - return ret - - @staticmethod - def get_common_global_body_messages(CP): - messages = [ - ("Wheel_Speeds", 50), - ("Brake_Status", 50), - ] - - if not (CP.flags & SubaruFlags.HYBRID): - messages.append(("CruiseControl", 20)) - - return messages - - @staticmethod - def get_common_global_es_messages(CP): - messages = [ - ("ES_Brake", 20), - ] - - if not (CP.flags & SubaruFlags.HYBRID): - messages += [ - ("ES_Distance", 20), - ("ES_Status", 20) - ] - - return messages - - @staticmethod - def get_common_preglobal_body_messages(): - messages = [ - ("CruiseControl", 50), - ("Wheel_Speeds", 50), - ("Dash_State2", 1), - ] - - return messages - - @staticmethod - def get_can_parser(CP): - messages = [ - # sig_address, frequency - ("Dashlights", 10), - ("Steering_Torque", 50), - ("BodyInfo", 1), - ("Brake_Pedal", 50), - ] - - if not (CP.flags & SubaruFlags.HYBRID): - messages += [ - ("Throttle", 100), - ("Transmission", 100) - ] - - if CP.enableBsm: - messages.append(("BSD_RCTA", 17)) - - if not (CP.flags & SubaruFlags.PREGLOBAL): - if not (CP.flags & SubaruFlags.GLOBAL_GEN2): - messages += CarState.get_common_global_body_messages(CP) - else: - messages += CarState.get_common_preglobal_body_messages() - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus.main) - - @staticmethod - def get_cam_can_parser(CP): - if CP.flags & SubaruFlags.PREGLOBAL: - messages = [ - ("ES_DashStatus", 20), - ("ES_Distance", 20), - ] - else: - messages = [ - ("ES_DashStatus", 10), - ("ES_LKAS_State", 10), - ] - - if not (CP.flags & SubaruFlags.GLOBAL_GEN2): - messages += CarState.get_common_global_es_messages(CP) - - if CP.flags & SubaruFlags.SEND_INFOTAINMENT: - messages.append(("ES_Infotainment", 10)) - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus.camera) - - @staticmethod - def get_body_can_parser(CP): - messages = [] - - if CP.flags & SubaruFlags.GLOBAL_GEN2: - messages += CarState.get_common_global_body_messages(CP) - messages += CarState.get_common_global_es_messages(CP) - - if CP.flags & SubaruFlags.HYBRID: - messages += [ - ("Throttle_Hybrid", 40), - ("Transmission", 100) - ] - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, CanBus.alt) - diff --git a/car/subaru/fingerprints.py b/car/subaru/fingerprints.py deleted file mode 100644 index 10c713501f..0000000000 --- a/car/subaru/fingerprints.py +++ /dev/null @@ -1,563 +0,0 @@ -from cereal import car -from openpilot.selfdrive.car.subaru.values import CAR - -Ecu = car.CarParams.Ecu - -FW_VERSIONS = { - CAR.SUBARU_ASCENT: { - (Ecu.abs, 0x7b0, None): [ - b'\xa5 \x19\x02\x00', - b'\xa5 !\x02\x00', - ], - (Ecu.eps, 0x746, None): [ - b'\x05\xc0\xd0\x00', - b'\x85\xc0\xd0\x00', - b'\x95\xc0\xd0\x00', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x00\x00d\xb9\x00\x00\x00\x00', - b'\x00\x00d\xb9\x1f@ \x10', - b'\x00\x00e@\x00\x00\x00\x00', - b'\x00\x00e@\x1f@ $', - b"\x00\x00e~\x1f@ '", - ], - (Ecu.engine, 0x7e0, None): [ - b'\xbb,\xa0t\x07', - b'\xd1,\xa0q\x07', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\x00>\xf0\x00\x00', - b'\x00\xfe\xf7\x00\x00', - b'\x01\xfe\xf7\x00\x00', - b'\x01\xfe\xf9\x00\x00', - b'\x01\xfe\xfa\x00\x00', - ], - }, - CAR.SUBARU_ASCENT_2023: { - (Ecu.abs, 0x7b0, None): [ - b'\xa5 #\x03\x00', - ], - (Ecu.eps, 0x746, None): [ - b'%\xc0\xd0\x11', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x05!\x08\x1dK\x05!\x08\x01/', - ], - (Ecu.engine, 0x7a2, None): [ - b'\xe5,\xa0P\x07', - ], - (Ecu.transmission, 0x7a3, None): [ - b'\x04\xfe\xf3\x00\x00', - ], - }, - CAR.SUBARU_LEGACY: { - (Ecu.abs, 0x7b0, None): [ - b'\xa1 \x02\x01', - b'\xa1 \x02\x02', - b'\xa1 \x03\x03', - b'\xa1 \x04\x01', - ], - (Ecu.eps, 0x746, None): [ - b'\x9b\xc0\x11\x00', - b'\x9b\xc0\x11\x02', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x00\x00e\x80\x00\x1f@ \x19\x00', - b'\x00\x00e\x9a\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xde"a0\x07', - b'\xde,\xa0@\x07', - b'\xe2"aq\x07', - b'\xe2,\xa0@\x07', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xa5\xf6\x05@\x00', - b'\xa5\xfe\xc7@\x00', - b'\xa7\xf6\x04@\x00', - b'\xa7\xfe\xc4@\x00', - ], - }, - CAR.SUBARU_IMPREZA: { - (Ecu.abs, 0x7b0, None): [ - b'z\x84\x19\x90\x00', - b'z\x94\x08\x90\x00', - b'z\x94\x08\x90\x01', - b'z\x94\x0c\x90\x00', - b'z\x94\x0c\x90\x01', - b'z\x94.\x90\x00', - b'z\x94?\x90\x00', - b'z\x9c\x19\x80\x01', - b'\xa2 \x185\x00', - b'\xa2 \x193\x00', - b'\xa2 \x194\x00', - b'\xa2 \x19`\x00', - ], - (Ecu.eps, 0x746, None): [ - b'z\xc0\x00\x00', - b'z\xc0\x04\x00', - b'z\xc0\x08\x00', - b'z\xc0\n\x00', - b'z\xc0\x0c\x00', - b'\x8a\xc0\x00\x00', - b'\x8a\xc0\x10\x00', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x00\x00c\xf4\x00\x00\x00\x00', - b'\x00\x00c\xf4\x1f@ \x07', - b'\x00\x00d)\x00\x00\x00\x00', - b'\x00\x00d)\x1f@ \x07', - b'\x00\x00dd\x00\x00\x00\x00', - b'\x00\x00dd\x1f@ \x0e', - b'\x00\x00d\xb5\x1f@ \x0e', - b'\x00\x00d\xdc\x00\x00\x00\x00', - b'\x00\x00d\xdc\x1f@ \x0e', - b'\x00\x00e\x02\x1f@ \x14', - b'\x00\x00e\x1c\x00\x00\x00\x00', - b'\x00\x00e\x1c\x1f@ \x14', - b'\x00\x00e+\x00\x00\x00\x00', - b'\x00\x00e+\x1f@ \x14', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xaa\x00Bu\x07', - b'\xaa\x01bt\x07', - b'\xaa!`u\x07', - b'\xaa!au\x07', - b'\xaa!av\x07', - b'\xaa!aw\x07', - b'\xaa!dq\x07', - b'\xaa!ds\x07', - b'\xaa!dt\x07', - b'\xaaafs\x07', - b'\xbe!as\x07', - b'\xbe!at\x07', - b'\xbeacr\x07', - b'\xc5!`r\x07', - b'\xc5!`s\x07', - b'\xc5!ap\x07', - b'\xc5!ar\x07', - b'\xc5!as\x07', - b'\xc5!dr\x07', - b'\xc5!ds\x07', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xe3\xd0\x081\x00', - b'\xe3\xd5\x161\x00', - b'\xe3\xe5F1\x00', - b'\xe3\xf5\x06\x00\x00', - b'\xe3\xf5\x07\x00\x00', - b'\xe3\xf5C\x00\x00', - b'\xe3\xf5F\x00\x00', - b'\xe3\xf5G\x00\x00', - b'\xe4\xe5\x021\x00', - b'\xe4\xe5\x061\x00', - b'\xe4\xf5\x02\x00\x00', - b'\xe4\xf5\x07\x00\x00', - b'\xe5\xf5\x04\x00\x00', - b'\xe5\xf5$\x00\x00', - b'\xe5\xf5B\x00\x00', - ], - }, - CAR.SUBARU_IMPREZA_2020: { - (Ecu.abs, 0x7b0, None): [ - b'\xa2 \x193\x00', - b'\xa2 \x194\x00', - b'\xa2 `\x00', - b'\xa2 !3\x00', - b'\xa2 !6\x00', - b'\xa2 !`\x00', - b'\xa2 !i\x00', - ], - (Ecu.eps, 0x746, None): [ - b'\n\xc0\x04\x00', - b'\n\xc0\x04\x01', - b'\x9a\xc0\x00\x00', - b'\x9a\xc0\x04\x00', - b'\x9a\xc0\n\x01', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x00\x00eb\x1f@ "', - b'\x00\x00eq\x00\x00\x00\x00', - b'\x00\x00eq\x1f@ "', - b'\x00\x00e\x8f\x00\x00\x00\x00', - b'\x00\x00e\x8f\x1f@ )', - b'\x00\x00e\x92\x00\x00\x00\x00', - b'\x00\x00e\xa4\x00\x00\x00\x00', - b'\x00\x00e\xa4\x1f@ (', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xca!`0\x07', - b'\xca!`p\x07', - b'\xca!ap\x07', - b'\xca!f@\x07', - b'\xca!fp\x07', - b'\xcaacp\x07', - b'\xcc!`p\x07', - b'\xcc!fp\x07', - b'\xcc"f0\x07', - b'\xe6!`@\x07', - b'\xe6!fp\x07', - b'\xe6"f0\x07', - b'\xe6"fp\x07', - b'\xf3"f@\x07', - b'\xf3"fp\x07', - b'\xf3"fr\x07', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xe6\x15\x042\x00', - b'\xe6\xf5\x04\x00\x00', - b'\xe6\xf5$\x00\x00', - b'\xe6\xf5D0\x00', - b'\xe7\xf5\x04\x00\x00', - b'\xe7\xf5D0\x00', - b'\xe7\xf6B0\x00', - b'\xe9\xf5"\x00\x00', - b'\xe9\xf5B0\x00', - b'\xe9\xf6B0\x00', - b'\xe9\xf6F0\x00', - ], - }, - CAR.SUBARU_CROSSTREK_HYBRID: { - (Ecu.abs, 0x7b0, None): [ - b'\xa2 \x19e\x01', - b'\xa2 !e\x01', - ], - (Ecu.eps, 0x746, None): [ - b'\n\xc2\x01\x00', - b'\x9a\xc2\x01\x00', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x00\x00el\x1f@ #', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xd7!`@\x07', - b'\xd7!`p\x07', - b'\xf4!`0\x07', - ], - }, - CAR.SUBARU_FORESTER: { - (Ecu.abs, 0x7b0, None): [ - b'\xa3 \x18\x14\x00', - b'\xa3 \x18&\x00', - b'\xa3 \x19\x14\x00', - b'\xa3 \x19&\x00', - b'\xa3 \x19h\x00', - b'\xa3 \x14\x00', - b'\xa3 \x14\x01', - ], - (Ecu.eps, 0x746, None): [ - b'\x8d\xc0\x00\x00', - b'\x8d\xc0\x04\x00', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x00\x00e!\x00\x00\x00\x00', - b'\x00\x00e!\x1f@ \x11', - b'\x00\x00e^\x00\x00\x00\x00', - b'\x00\x00e^\x1f@ !', - b'\x00\x00e`\x00\x00\x00\x00', - b'\x00\x00e`\x1f@ ', - b'\x00\x00e\x97\x00\x00\x00\x00', - b'\x00\x00e\x97\x1f@ 0', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xb6"`A\x07', - b'\xb6\xa2`A\x07', - b'\xcb"`@\x07', - b'\xcb"`p\x07', - b'\xcf"`0\x07', - b'\xcf"`p\x07', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\x1a\xe6B1\x00', - b'\x1a\xe6F1\x00', - b'\x1a\xf6B0\x00', - b'\x1a\xf6B`\x00', - b'\x1a\xf6F`\x00', - b'\x1a\xf6b0\x00', - b'\x1a\xf6b`\x00', - b'\x1a\xf6f`\x00', - ], - }, - CAR.SUBARU_FORESTER_HYBRID: { - (Ecu.abs, 0x7b0, None): [ - b'\xa3 \x19T\x00', - ], - (Ecu.eps, 0x746, None): [ - b'\x8d\xc2\x00\x00', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x00\x00eY\x1f@ !', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xd2\xa1`r\x07', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\x1b\xa7@a\x00', - ], - }, - CAR.SUBARU_FORESTER_PREGLOBAL: { - (Ecu.abs, 0x7b0, None): [ - b'm\x97\x14@', - b'}\x97\x14@', - ], - (Ecu.eps, 0x746, None): [ - b'm\xc0\x10\x00', - b'}\xc0\x10\x00', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x00\x00c\xe9\x00\x00\x00\x00', - b'\x00\x00c\xe9\x1f@ \x03', - b'\x00\x00d5\x1f@ \t', - b'\x00\x00d\xd3\x1f@ \t', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xa7"@0\x07', - b'\xa7"@p\x07', - b'\xa7)\xa0q\x07', - b'\xba"@@\x07', - b'\xba"@p\x07', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\x1a\xf6F`\x00', - b'\xda\xf2`\x80\x00', - b'\xda\xf2`p\x00', - b'\xda\xfd\xe0\x80\x00', - b'\xdc\xf2@`\x00', - b'\xdc\xf2``\x00', - b'\xdc\xf2`\x80\x00', - b'\xdc\xf2`\x81\x00', - ], - }, - CAR.SUBARU_LEGACY_PREGLOBAL: { - (Ecu.abs, 0x7b0, None): [ - b'[\x97D\x00', - b'[\xba\xc4\x03', - b'k\x97D\x00', - b'k\x9aD\x00', - b'{\x97D\x00', - ], - (Ecu.eps, 0x746, None): [ - b'K\xb0\x00\x01', - b'[\xb0\x00\x01', - b'k\xb0\x00\x00', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x00\x00c\x94\x1f@\x10\x08', - b'\x00\x00c\xb7\x1f@\x10\x16', - b'\x00\x00c\xec\x1f@ \x04', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xa0"@q\x07', - b'\xa0+@p\x07', - b'\xab*@r\x07', - b'\xab+@p\x07', - b'\xb4"@0\x07', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xbd\xf2\x00`\x00', - b'\xbe\xf2\x00p\x00', - b'\xbe\xfb\xc0p\x00', - b'\xbf\xf2\x00\x80\x00', - b'\xbf\xfb\xc0\x80\x00', - ], - }, - CAR.SUBARU_OUTBACK_PREGLOBAL: { - (Ecu.abs, 0x7b0, None): [ - b'[\xba\xac\x03', - b'[\xf7\xac\x00', - b'[\xf7\xac\x03', - b'[\xf7\xbc\x03', - b'k\x97\xac\x00', - b'k\x9a\xac\x00', - b'{\x97\xac\x00', - b'{\x9a\xac\x00', - ], - (Ecu.eps, 0x746, None): [ - b'K\xb0\x00\x00', - b'K\xb0\x00\x02', - b'[\xb0\x00\x00', - b'k\xb0\x00\x00', - b'{\xb0\x00\x01', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x00\x00c\x90\x1f@\x10\x0e', - b'\x00\x00c\x94\x00\x00\x00\x00', - b'\x00\x00c\x94\x1f@\x10\x08', - b'\x00\x00c\xb7\x1f@\x10\x16', - b'\x00\x00c\xd1\x1f@\x10\x17', - b'\x00\x00c\xec\x1f@ \x04', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xa0"@\x80\x07', - b'\xa0*@q\x07', - b'\xa0*@u\x07', - b'\xa0+@@\x07', - b'\xa0bAq\x07', - b'\xab"@@\x07', - b'\xab"@s\x07', - b'\xab*@@\x07', - b'\xab+@@\x07', - b'\xb4"@0\x07', - b'\xb4"@p\x07', - b'\xb4"@r\x07', - b'\xb4+@p\x07', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xbd\xf2@`\x00', - b'\xbd\xf2@\x81\x00', - b'\xbd\xfb\xe0\x80\x00', - b'\xbe\xf2@p\x00', - b'\xbe\xf2@\x80\x00', - b'\xbe\xfb\xe0p\x00', - b'\xbf\xe2@\x80\x00', - b'\xbf\xf2@\x80\x00', - b'\xbf\xfb\xe0b\x00', - ], - }, - CAR.SUBARU_OUTBACK_PREGLOBAL_2018: { - (Ecu.abs, 0x7b0, None): [ - b'\x8b\x97\xac\x00', - b'\x8b\x97\xbc\x00', - b'\x8b\x99\xac\x00', - b'\x8b\x9a\xac\x00', - b'\x9b\x97\xac\x00', - b'\x9b\x97\xbe\x10', - b'\x9b\x9a\xac\x00', - ], - (Ecu.eps, 0x746, None): [ - b'{\xb0\x00\x00', - b'{\xb0\x00\x01', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x00\x00df\x1f@ \n', - b'\x00\x00d\x95\x00\x00\x00\x00', - b'\x00\x00d\x95\x1f@ \x0f', - b'\x00\x00d\xfe\x00\x00\x00\x00', - b'\x00\x00d\xfe\x1f@ \x15', - b'\x00\x00e\x19\x1f@ \x15', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xb5"@P\x07', - b'\xb5"@p\x07', - b'\xb5+@@\x07', - b'\xb5b@1\x07', - b'\xb5q\xe0@\x07', - b'\xc4"@0\x07', - b'\xc4+@0\x07', - b'\xc4b@p\x07', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xbb\xf2@`\x00', - b'\xbb\xfb\xe0`\x00', - b'\xbc\xaf\xe0`\x00', - b'\xbc\xe2@\x80\x00', - b'\xbc\xf2@\x80\x00', - b'\xbc\xf2@\x81\x00', - b'\xbc\xfb\xe0`\x00', - b'\xbc\xfb\xe0\x80\x00', - ], - }, - CAR.SUBARU_OUTBACK: { - (Ecu.abs, 0x7b0, None): [ - b'\xa1 \x06\x00', - b'\xa1 \x06\x01', - b'\xa1 \x06\x02', - b'\xa1 \x07\x00', - b'\xa1 \x07\x02', - b'\xa1 \x07\x03', - b'\xa1 \x08\x00', - b'\xa1 \x08\x01', - b'\xa1 \x08\x02', - b'\xa1 "\t\x00', - b'\xa1 "\t\x01', - ], - (Ecu.eps, 0x746, None): [ - b'\x1b\xc0\x10\x00', - b'\x9b\xc0\x10\x00', - b'\x9b\xc0\x10\x02', - b'\x9b\xc0 \x00', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x00\x00eJ\x00\x00\x00\x00\x00\x00', - b'\x00\x00eJ\x00\x1f@ \x19\x00', - b'\x00\x00e\x80\x00\x1f@ \x19\x00', - b'\x00\x00e\x9a\x00\x00\x00\x00\x00\x00', - b'\x00\x00e\x9a\x00\x1f@ 1\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xbc"`@\x07', - b'\xbc"`q\x07', - b'\xbc,\xa0q\x07', - b'\xbc,\xa0u\x07', - b'\xde"`0\x07', - b'\xde,\xa0@\x07', - b'\xe2"`0\x07', - b'\xe2"`p\x07', - b'\xe2"`q\x07', - b'\xe3,\xa0@\x07', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xa5\xf6D@\x00', - b'\xa5\xfe\xf6@\x00', - b'\xa5\xfe\xf7@\x00', - b'\xa5\xfe\xf8@\x00', - b'\xa7\x8e\xf40\x00', - b'\xa7\xf6D@\x00', - b'\xa7\xfe\xf4@\x00', - ], - }, - CAR.SUBARU_FORESTER_2022: { - (Ecu.abs, 0x7b0, None): [ - b'\xa3 !v\x00', - b'\xa3 !x\x00', - b'\xa3 "v\x00', - b'\xa3 "x\x00', - ], - (Ecu.eps, 0x746, None): [ - b'-\xc0\x040', - b'-\xc0%0', - b'=\xc0%\x02', - b'=\xc04\x02', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\x04!\x01\x1eD\x07!\x00\x04,', - b'\x04!\x08\x01.\x07!\x08\x022', - b'\r!\x08\x017\n!\x08\x003', - ], - (Ecu.engine, 0x7e0, None): [ - b'\xd5"`0\x07', - b'\xd5"a0\x07', - b'\xf1"`q\x07', - b'\xf1"aq\x07', - b'\xfa"ap\x07', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\x1d\x86B0\x00', - b'\x1d\xf6B0\x00', - b'\x1e\x86B0\x00', - b'\x1e\x86F0\x00', - b'\x1e\xf6D0\x00', - ], - }, - CAR.SUBARU_OUTBACK_2023: { - (Ecu.abs, 0x7b0, None): [ - b'\xa1 #\x14\x00', - b'\xa1 #\x17\x00', - ], - (Ecu.eps, 0x746, None): [ - b'+\xc0\x10\x11\x00', - b'+\xc0\x12\x11\x00', - ], - (Ecu.fwdCamera, 0x787, None): [ - b'\t!\x08\x046\x05!\x08\x01/', - ], - (Ecu.engine, 0x7a2, None): [ - b'\xed,\xa0q\x07', - b'\xed,\xa2q\x07', - ], - (Ecu.transmission, 0x7a3, None): [ - b'\xa8\x8e\xf41\x00', - b'\xa8\xfe\xf41\x00', - ], - }, -} diff --git a/car/subaru/interface.py b/car/subaru/interface.py deleted file mode 100644 index 1aa4bd95ea..0000000000 --- a/car/subaru/interface.py +++ /dev/null @@ -1,116 +0,0 @@ -from cereal import car -from panda import Panda -from openpilot.selfdrive.car import get_safety_config -from openpilot.selfdrive.car.disable_ecu import disable_ecu -from openpilot.selfdrive.car.interfaces import CarInterfaceBase -from openpilot.selfdrive.car.subaru.values import CAR, GLOBAL_ES_ADDR, SubaruFlags - - -class CarInterface(CarInterfaceBase): - - @staticmethod - def _get_params(ret, candidate: CAR, fingerprint, car_fw, experimental_long, docs): - ret.carName = "subaru" - ret.radarUnavailable = True - # for HYBRID CARS to be upstreamed, we need: - # - replacement for ES_Distance so we can cancel the cruise control - # - to find the Cruise_Activated bit from the car - # - proper panda safety setup (use the correct cruise_activated bit, throttle from Throttle_Hybrid, etc) - ret.dashcamOnly = bool(ret.flags & (SubaruFlags.PREGLOBAL | SubaruFlags.LKAS_ANGLE | SubaruFlags.HYBRID)) - ret.autoResumeSng = False - - # Detect infotainment message sent from the camera - if not (ret.flags & SubaruFlags.PREGLOBAL) and 0x323 in fingerprint[2]: - ret.flags |= SubaruFlags.SEND_INFOTAINMENT.value - - if ret.flags & SubaruFlags.PREGLOBAL: - ret.enableBsm = 0x25c in fingerprint[0] - ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.subaruPreglobal)] - else: - ret.enableBsm = 0x228 in fingerprint[0] - ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.subaru)] - if ret.flags & SubaruFlags.GLOBAL_GEN2: - ret.safetyConfigs[0].safetyParam |= Panda.FLAG_SUBARU_GEN2 - - ret.steerLimitTimer = 0.4 - ret.steerActuatorDelay = 0.1 - - if ret.flags & SubaruFlags.LKAS_ANGLE: - ret.steerControlType = car.CarParams.SteerControlType.angle - else: - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) - - if candidate in (CAR.SUBARU_ASCENT, CAR.SUBARU_ASCENT_2023): - ret.steerActuatorDelay = 0.3 # end-to-end angle controller - ret.lateralTuning.init('pid') - ret.lateralTuning.pid.kf = 0.00003 - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0., 20.], [0., 20.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.0025, 0.1], [0.00025, 0.01]] - - elif candidate == CAR.SUBARU_IMPREZA: - ret.steerActuatorDelay = 0.4 # end-to-end angle controller - ret.lateralTuning.init('pid') - ret.lateralTuning.pid.kf = 0.00005 - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0., 20.], [0., 20.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2, 0.3], [0.02, 0.03]] - - elif candidate == CAR.SUBARU_IMPREZA_2020: - ret.lateralTuning.init('pid') - ret.lateralTuning.pid.kf = 0.00005 - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0., 14., 23.], [0., 14., 23.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.045, 0.042, 0.20], [0.04, 0.035, 0.045]] - - elif candidate == CAR.SUBARU_CROSSTREK_HYBRID: - ret.steerActuatorDelay = 0.1 - - elif candidate in (CAR.SUBARU_FORESTER, CAR.SUBARU_FORESTER_2022, CAR.SUBARU_FORESTER_HYBRID): - ret.lateralTuning.init('pid') - ret.lateralTuning.pid.kf = 0.000038 - ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0., 14., 23.], [0., 14., 23.]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.01, 0.065, 0.2], [0.001, 0.015, 0.025]] - - elif candidate in (CAR.SUBARU_OUTBACK, CAR.SUBARU_LEGACY, CAR.SUBARU_OUTBACK_2023): - ret.steerActuatorDelay = 0.1 - - elif candidate in (CAR.SUBARU_FORESTER_PREGLOBAL, CAR.SUBARU_OUTBACK_PREGLOBAL_2018): - ret.safetyConfigs[0].safetyParam = Panda.FLAG_SUBARU_PREGLOBAL_REVERSED_DRIVER_TORQUE # Outback 2018-2019 and Forester have reversed driver torque signal - - elif candidate == CAR.SUBARU_LEGACY_PREGLOBAL: - ret.steerActuatorDelay = 0.15 - - elif candidate == CAR.SUBARU_OUTBACK_PREGLOBAL: - pass - else: - raise ValueError(f"unknown car: {candidate}") - - ret.experimentalLongitudinalAvailable = not (ret.flags & (SubaruFlags.GLOBAL_GEN2 | SubaruFlags.PREGLOBAL | - SubaruFlags.LKAS_ANGLE | SubaruFlags.HYBRID)) - ret.openpilotLongitudinalControl = experimental_long and ret.experimentalLongitudinalAvailable - - if ret.flags & SubaruFlags.GLOBAL_GEN2 and ret.openpilotLongitudinalControl: - ret.flags |= SubaruFlags.DISABLE_EYESIGHT.value - - if ret.openpilotLongitudinalControl: - ret.longitudinalTuning.kpBP = [0., 5., 35.] - ret.longitudinalTuning.kpV = [0.8, 1.0, 1.5] - ret.longitudinalTuning.kiBP = [0., 35.] - ret.longitudinalTuning.kiV = [0.54, 0.36] - - ret.stoppingControl = True - ret.safetyConfigs[0].safetyParam |= Panda.FLAG_SUBARU_LONG - - return ret - - # returns a car.CarState - def _update(self, c): - - ret = self.CS.update(self.cp, self.cp_cam, self.cp_body) - - ret.events = self.create_common_events(ret).to_msg() - - return ret - - @staticmethod - def init(CP, logcan, sendcan): - if CP.flags & SubaruFlags.DISABLE_EYESIGHT: - disable_ecu(logcan, sendcan, bus=2, addr=GLOBAL_ES_ADDR, com_cont_req=b'\x28\x03\x01') diff --git a/car/subaru/radar_interface.py b/car/subaru/radar_interface.py deleted file mode 100644 index e654bd61fd..0000000000 --- a/car/subaru/radar_interface.py +++ /dev/null @@ -1,4 +0,0 @@ -from openpilot.selfdrive.car.interfaces import RadarInterfaceBase - -class RadarInterface(RadarInterfaceBase): - pass diff --git a/car/subaru/subarucan.py b/car/subaru/subarucan.py deleted file mode 100644 index 86d39ff885..0000000000 --- a/car/subaru/subarucan.py +++ /dev/null @@ -1,321 +0,0 @@ -from cereal import car -from openpilot.selfdrive.car.subaru.values import CanBus - -VisualAlert = car.CarControl.HUDControl.VisualAlert - - -def create_steering_control(packer, apply_steer, steer_req): - values = { - "LKAS_Output": apply_steer, - "LKAS_Request": steer_req, - "SET_1": 1 - } - return packer.make_can_msg("ES_LKAS", 0, values) - - -def create_steering_control_angle(packer, apply_steer, steer_req): - values = { - "LKAS_Output": apply_steer, - "LKAS_Request": steer_req, - "SET_3": 3 - } - return packer.make_can_msg("ES_LKAS_ANGLE", 0, values) - - -def create_steering_status(packer): - return packer.make_can_msg("ES_LKAS_State", 0, {}) - -def create_es_distance(packer, frame, es_distance_msg, bus, pcm_cancel_cmd, long_enabled = False, brake_cmd = False, cruise_throttle = 0): - values = {s: es_distance_msg[s] for s in [ - "CHECKSUM", - "Signal1", - "Cruise_Fault", - "Cruise_Throttle", - "Signal2", - "Car_Follow", - "Low_Speed_Follow", - "Cruise_Soft_Disable", - "Signal7", - "Cruise_Brake_Active", - "Distance_Swap", - "Cruise_EPB", - "Signal4", - "Close_Distance", - "Signal5", - "Cruise_Cancel", - "Cruise_Set", - "Cruise_Resume", - "Signal6", - ]} - - values["COUNTER"] = frame % 0x10 - - if long_enabled: - values["Cruise_Throttle"] = cruise_throttle - - # Do not disable openpilot on Eyesight Soft Disable, if openpilot is controlling long - values["Cruise_Soft_Disable"] = 0 - values["Cruise_Fault"] = 0 - - values["Cruise_Brake_Active"] = brake_cmd - - if pcm_cancel_cmd: - values["Cruise_Cancel"] = 1 - values["Cruise_Throttle"] = 1818 # inactive throttle - - return packer.make_can_msg("ES_Distance", bus, values) - - -def create_es_lkas_state(packer, frame, es_lkas_state_msg, enabled, visual_alert, left_line, right_line, left_lane_depart, right_lane_depart): - values = {s: es_lkas_state_msg[s] for s in [ - "CHECKSUM", - "LKAS_Alert_Msg", - "Signal1", - "LKAS_ACTIVE", - "LKAS_Dash_State", - "Signal2", - "Backward_Speed_Limit_Menu", - "LKAS_Left_Line_Enable", - "LKAS_Left_Line_Light_Blink", - "LKAS_Right_Line_Enable", - "LKAS_Right_Line_Light_Blink", - "LKAS_Left_Line_Visible", - "LKAS_Right_Line_Visible", - "LKAS_Alert", - "Signal3", - ]} - - values["COUNTER"] = frame % 0x10 - - # Filter the stock LKAS "Keep hands on wheel" alert - if values["LKAS_Alert_Msg"] == 1: - values["LKAS_Alert_Msg"] = 0 - - # Filter the stock LKAS sending an audible alert when it turns off LKAS - if values["LKAS_Alert"] == 27: - values["LKAS_Alert"] = 0 - - # Filter the stock LKAS sending an audible alert when "Keep hands on wheel" alert is active (2020+ models) - if values["LKAS_Alert"] == 28 and values["LKAS_Alert_Msg"] == 7: - values["LKAS_Alert"] = 0 - - # Filter the stock LKAS sending an audible alert when "Keep hands on wheel OFF" alert is active (2020+ models) - if values["LKAS_Alert"] == 30: - values["LKAS_Alert"] = 0 - - # Filter the stock LKAS sending "Keep hands on wheel OFF" alert (2020+ models) - if values["LKAS_Alert_Msg"] == 7: - values["LKAS_Alert_Msg"] = 0 - - # Show Keep hands on wheel alert for openpilot steerRequired alert - if visual_alert == VisualAlert.steerRequired: - values["LKAS_Alert_Msg"] = 1 - - # Ensure we don't overwrite potentially more important alerts from stock (e.g. FCW) - if visual_alert == VisualAlert.ldw and values["LKAS_Alert"] == 0: - if left_lane_depart: - values["LKAS_Alert"] = 12 # Left lane departure dash alert - elif right_lane_depart: - values["LKAS_Alert"] = 11 # Right lane departure dash alert - - if enabled: - values["LKAS_ACTIVE"] = 1 # Show LKAS lane lines - values["LKAS_Dash_State"] = 2 # Green enabled indicator - else: - values["LKAS_Dash_State"] = 0 # LKAS Not enabled - - values["LKAS_Left_Line_Visible"] = int(left_line) - values["LKAS_Right_Line_Visible"] = int(right_line) - - return packer.make_can_msg("ES_LKAS_State", CanBus.main, values) - -def create_es_dashstatus(packer, frame, dashstatus_msg, enabled, long_enabled, long_active, lead_visible): - values = {s: dashstatus_msg[s] for s in [ - "CHECKSUM", - "PCB_Off", - "LDW_Off", - "Signal1", - "Cruise_State_Msg", - "LKAS_State_Msg", - "Signal2", - "Cruise_Soft_Disable", - "Cruise_Status_Msg", - "Signal3", - "Cruise_Distance", - "Signal4", - "Conventional_Cruise", - "Signal5", - "Cruise_Disengaged", - "Cruise_Activated", - "Signal6", - "Cruise_Set_Speed", - "Cruise_Fault", - "Cruise_On", - "Display_Own_Car", - "Brake_Lights", - "Car_Follow", - "Signal7", - "Far_Distance", - "Cruise_State", - ]} - - values["COUNTER"] = frame % 0x10 - - if long_enabled: - values["Cruise_State"] = 0 - values["Cruise_Activated"] = enabled - values["Cruise_Disengaged"] = 0 - values["Car_Follow"] = int(lead_visible) - - values["PCB_Off"] = 1 # AEB is not presevered, so show the PCB_Off on dash - values["LDW_Off"] = 0 - values["Cruise_Fault"] = 0 - - # Filter stock LKAS disabled and Keep hands on steering wheel OFF alerts - if values["LKAS_State_Msg"] in (2, 3): - values["LKAS_State_Msg"] = 0 - - return packer.make_can_msg("ES_DashStatus", CanBus.main, values) - -def create_es_brake(packer, frame, es_brake_msg, long_enabled, long_active, brake_value): - values = {s: es_brake_msg[s] for s in [ - "CHECKSUM", - "Signal1", - "Brake_Pressure", - "AEB_Status", - "Cruise_Brake_Lights", - "Cruise_Brake_Fault", - "Cruise_Brake_Active", - "Cruise_Activated", - "Signal3", - ]} - - values["COUNTER"] = frame % 0x10 - - if long_enabled: - values["Cruise_Brake_Fault"] = 0 - values["Cruise_Activated"] = long_active - - values["Brake_Pressure"] = brake_value - - values["Cruise_Brake_Active"] = brake_value > 0 - values["Cruise_Brake_Lights"] = brake_value >= 70 - - return packer.make_can_msg("ES_Brake", CanBus.main, values) - -def create_es_status(packer, frame, es_status_msg, long_enabled, long_active, cruise_rpm): - values = {s: es_status_msg[s] for s in [ - "CHECKSUM", - "Signal1", - "Cruise_Fault", - "Cruise_RPM", - "Cruise_Activated", - "Brake_Lights", - "Cruise_Hold", - "Signal3", - ]} - - values["COUNTER"] = frame % 0x10 - - if long_enabled: - values["Cruise_RPM"] = cruise_rpm - values["Cruise_Fault"] = 0 - - values["Cruise_Activated"] = long_active - - return packer.make_can_msg("ES_Status", CanBus.main, values) - - -def create_es_infotainment(packer, frame, es_infotainment_msg, visual_alert): - # Filter stock LKAS disabled and Keep hands on steering wheel OFF alerts - values = {s: es_infotainment_msg[s] for s in [ - "CHECKSUM", - "LKAS_State_Infotainment", - "LKAS_Blue_Lines", - "Signal1", - "Signal2", - ]} - - values["COUNTER"] = frame % 0x10 - - if values["LKAS_State_Infotainment"] in (3, 4): - values["LKAS_State_Infotainment"] = 0 - - # Show Keep hands on wheel alert for openpilot steerRequired alert - if visual_alert == VisualAlert.steerRequired: - values["LKAS_State_Infotainment"] = 3 - - # Show Obstacle Detected for fcw - if visual_alert == VisualAlert.fcw: - values["LKAS_State_Infotainment"] = 2 - - return packer.make_can_msg("ES_Infotainment", CanBus.main, values) - - -def create_es_highbeamassist(packer): - values = { - "HBA_Available": False, - } - - return packer.make_can_msg("ES_HighBeamAssist", CanBus.main, values) - - -def create_es_static_1(packer): - values = { - "SET_3": 3, - } - - return packer.make_can_msg("ES_STATIC_1", CanBus.main, values) - - -def create_es_static_2(packer): - values = { - "SET_3": 3, - } - - return packer.make_can_msg("ES_STATIC_2", CanBus.main, values) - - -# *** Subaru Pre-global *** - -def subaru_preglobal_checksum(packer, values, addr, checksum_byte=7): - dat = packer.make_can_msg(addr, 0, values)[2] - return (sum(dat[:checksum_byte]) + sum(dat[checksum_byte+1:])) % 256 - - -def create_preglobal_steering_control(packer, frame, apply_steer, steer_req): - values = { - "COUNTER": frame % 0x08, - "LKAS_Command": apply_steer, - "LKAS_Active": steer_req, - } - values["Checksum"] = subaru_preglobal_checksum(packer, values, "ES_LKAS") - - return packer.make_can_msg("ES_LKAS", CanBus.main, values) - - -def create_preglobal_es_distance(packer, cruise_button, es_distance_msg): - values = {s: es_distance_msg[s] for s in [ - "Cruise_Throttle", - "Signal1", - "Car_Follow", - "Signal2", - "Cruise_Brake_Active", - "Distance_Swap", - "Standstill", - "Signal3", - "Close_Distance", - "Signal4", - "Standstill_2", - "Cruise_Fault", - "Signal5", - "COUNTER", - "Signal6", - "Cruise_Button", - "Signal7", - ]} - - values["Cruise_Button"] = cruise_button - values["Checksum"] = subaru_preglobal_checksum(packer, values, "ES_Distance") - - return packer.make_can_msg("ES_Distance", CanBus.main, values) diff --git a/car/subaru/tests/test_subaru.py b/car/subaru/tests/test_subaru.py deleted file mode 100644 index 33040442b6..0000000000 --- a/car/subaru/tests/test_subaru.py +++ /dev/null @@ -1,16 +0,0 @@ -from cereal import car -from openpilot.selfdrive.car.subaru.fingerprints import FW_VERSIONS - -Ecu = car.CarParams.Ecu - -ECU_NAME = {v: k for k, v in Ecu.schema.enumerants.items()} - - -class TestSubaruFingerprint: - def test_fw_version_format(self): - for platform, fws_per_ecu in FW_VERSIONS.items(): - for (ecu, _, _), fws in fws_per_ecu.items(): - fw_size = len(fws[0]) - for fw in fws: - assert len(fw) == fw_size, f"{platform} {ecu}: {len(fw)} {fw_size}" - diff --git a/car/subaru/values.py b/car/subaru/values.py deleted file mode 100644 index dcbea1979f..0000000000 --- a/car/subaru/values.py +++ /dev/null @@ -1,275 +0,0 @@ -from dataclasses import dataclass, field -from enum import Enum, IntFlag - -from cereal import car -from panda.python import uds -from openpilot.selfdrive.car import CarSpecs, DbcDict, PlatformConfig, Platforms, dbc_dict -from openpilot.selfdrive.car.docs_definitions import CarFootnote, CarHarness, CarDocs, CarParts, Tool, Column -from openpilot.selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries, p16 - -Ecu = car.CarParams.Ecu - - -class CarControllerParams: - def __init__(self, CP): - self.STEER_STEP = 2 # how often we update the steer cmd - self.STEER_DELTA_UP = 50 # torque increase per refresh, 0.8s to max - self.STEER_DELTA_DOWN = 70 # torque decrease per refresh - self.STEER_DRIVER_ALLOWANCE = 60 # allowed driver torque before start limiting - self.STEER_DRIVER_MULTIPLIER = 50 # weight driver torque heavily - self.STEER_DRIVER_FACTOR = 1 # from dbc - - if CP.flags & SubaruFlags.GLOBAL_GEN2: - self.STEER_MAX = 1000 - self.STEER_DELTA_UP = 40 - self.STEER_DELTA_DOWN = 40 - elif CP.carFingerprint == CAR.SUBARU_IMPREZA_2020: - self.STEER_MAX = 1439 - else: - self.STEER_MAX = 2047 - - THROTTLE_MIN = 808 - THROTTLE_MAX = 3400 - - THROTTLE_INACTIVE = 1818 # corresponds to zero acceleration - THROTTLE_ENGINE_BRAKE = 808 # while braking, eyesight sets throttle to this, probably for engine braking - - BRAKE_MIN = 0 - BRAKE_MAX = 600 # about -3.5m/s2 from testing - - RPM_MIN = 0 - RPM_MAX = 3600 - - RPM_INACTIVE = 600 # a good base rpm for zero acceleration - - THROTTLE_LOOKUP_BP = [0, 2] - THROTTLE_LOOKUP_V = [THROTTLE_INACTIVE, THROTTLE_MAX] - - RPM_LOOKUP_BP = [0, 2] - RPM_LOOKUP_V = [RPM_INACTIVE, RPM_MAX] - - BRAKE_LOOKUP_BP = [-3.5, 0] - BRAKE_LOOKUP_V = [BRAKE_MAX, BRAKE_MIN] - - -class SubaruFlags(IntFlag): - # Detected flags - SEND_INFOTAINMENT = 1 - DISABLE_EYESIGHT = 2 - - # Static flags - GLOBAL_GEN2 = 4 - - # Cars that temporarily fault when steering angle rate is greater than some threshold. - # Appears to be all torque-based cars produced around 2019 - present - STEER_RATE_LIMITED = 8 - PREGLOBAL = 16 - HYBRID = 32 - LKAS_ANGLE = 64 - - -GLOBAL_ES_ADDR = 0x787 -GEN2_ES_BUTTONS_DID = b'\x11\x30' - - -class CanBus: - main = 0 - alt = 1 - camera = 2 - - -class Footnote(Enum): - GLOBAL = CarFootnote( - "In the non-US market, openpilot requires the car to come equipped with EyeSight with Lane Keep Assistance.", - Column.PACKAGE) - EXP_LONG = CarFootnote( - "Enabling longitudinal control (alpha) will disable all EyeSight functionality, including AEB, LDW, and RAB.", - Column.LONGITUDINAL) - - -@dataclass -class SubaruCarDocs(CarDocs): - package: str = "EyeSight Driver Assistance" - car_parts: CarParts = field(default_factory=CarParts.common([CarHarness.subaru_a])) - footnotes: list[Enum] = field(default_factory=lambda: [Footnote.GLOBAL]) - - def init_make(self, CP: car.CarParams): - self.car_parts.parts.extend([Tool.socket_8mm_deep, Tool.pry_tool]) - - if CP.experimentalLongitudinalAvailable: - self.footnotes.append(Footnote.EXP_LONG) - - -@dataclass -class SubaruPlatformConfig(PlatformConfig): - dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict('subaru_global_2017_generated', None)) - - def init(self): - if self.flags & SubaruFlags.HYBRID: - self.dbc_dict = dbc_dict('subaru_global_2020_hybrid_generated', None) - - -@dataclass -class SubaruGen2PlatformConfig(SubaruPlatformConfig): - def init(self): - super().init() - self.flags |= SubaruFlags.GLOBAL_GEN2 - if not (self.flags & SubaruFlags.LKAS_ANGLE): - self.flags |= SubaruFlags.STEER_RATE_LIMITED - - -class CAR(Platforms): - # Global platform - SUBARU_ASCENT = SubaruPlatformConfig( - [SubaruCarDocs("Subaru Ascent 2019-21", "All")], - CarSpecs(mass=2031, wheelbase=2.89, steerRatio=13.5), - ) - SUBARU_OUTBACK = SubaruGen2PlatformConfig( - [SubaruCarDocs("Subaru Outback 2020-22", "All", car_parts=CarParts.common([CarHarness.subaru_b]))], - CarSpecs(mass=1568, wheelbase=2.67, steerRatio=17), - ) - SUBARU_LEGACY = SubaruGen2PlatformConfig( - [SubaruCarDocs("Subaru Legacy 2020-22", "All", car_parts=CarParts.common([CarHarness.subaru_b]))], - SUBARU_OUTBACK.specs, - ) - SUBARU_IMPREZA = SubaruPlatformConfig( - [ - SubaruCarDocs("Subaru Impreza 2017-19"), - SubaruCarDocs("Subaru Crosstrek 2018-19", video_link="https://youtu.be/Agww7oE1k-s?t=26"), - SubaruCarDocs("Subaru XV 2018-19", video_link="https://youtu.be/Agww7oE1k-s?t=26"), - ], - CarSpecs(mass=1568, wheelbase=2.67, steerRatio=15), - ) - SUBARU_IMPREZA_2020 = SubaruPlatformConfig( - [ - SubaruCarDocs("Subaru Impreza 2020-22"), - SubaruCarDocs("Subaru Crosstrek 2020-23"), - SubaruCarDocs("Subaru XV 2020-21"), - ], - CarSpecs(mass=1480, wheelbase=2.67, steerRatio=17), - flags=SubaruFlags.STEER_RATE_LIMITED, - ) - # TODO: is there an XV and Impreza too? - SUBARU_CROSSTREK_HYBRID = SubaruPlatformConfig( - [SubaruCarDocs("Subaru Crosstrek Hybrid 2020", car_parts=CarParts.common([CarHarness.subaru_b]))], - CarSpecs(mass=1668, wheelbase=2.67, steerRatio=17), - flags=SubaruFlags.HYBRID, - ) - SUBARU_FORESTER = SubaruPlatformConfig( - [SubaruCarDocs("Subaru Forester 2019-21", "All")], - CarSpecs(mass=1568, wheelbase=2.67, steerRatio=17), - flags=SubaruFlags.STEER_RATE_LIMITED, - ) - SUBARU_FORESTER_HYBRID = SubaruPlatformConfig( - [SubaruCarDocs("Subaru Forester Hybrid 2020")], - SUBARU_FORESTER.specs, - flags=SubaruFlags.HYBRID, - ) - # Pre-global - SUBARU_FORESTER_PREGLOBAL = SubaruPlatformConfig( - [SubaruCarDocs("Subaru Forester 2017-18")], - CarSpecs(mass=1568, wheelbase=2.67, steerRatio=20), - dbc_dict('subaru_forester_2017_generated', None), - flags=SubaruFlags.PREGLOBAL, - ) - SUBARU_LEGACY_PREGLOBAL = SubaruPlatformConfig( - [SubaruCarDocs("Subaru Legacy 2015-18")], - CarSpecs(mass=1568, wheelbase=2.67, steerRatio=12.5), - dbc_dict('subaru_outback_2015_generated', None), - flags=SubaruFlags.PREGLOBAL, - ) - SUBARU_OUTBACK_PREGLOBAL = SubaruPlatformConfig( - [SubaruCarDocs("Subaru Outback 2015-17")], - SUBARU_FORESTER_PREGLOBAL.specs, - dbc_dict('subaru_outback_2015_generated', None), - flags=SubaruFlags.PREGLOBAL, - ) - SUBARU_OUTBACK_PREGLOBAL_2018 = SubaruPlatformConfig( - [SubaruCarDocs("Subaru Outback 2018-19")], - SUBARU_FORESTER_PREGLOBAL.specs, - dbc_dict('subaru_outback_2019_generated', None), - flags=SubaruFlags.PREGLOBAL, - ) - # Angle LKAS - SUBARU_FORESTER_2022 = SubaruPlatformConfig( - [SubaruCarDocs("Subaru Forester 2022-24", "All", car_parts=CarParts.common([CarHarness.subaru_c]))], - SUBARU_FORESTER.specs, - flags=SubaruFlags.LKAS_ANGLE, - ) - SUBARU_OUTBACK_2023 = SubaruGen2PlatformConfig( - [SubaruCarDocs("Subaru Outback 2023", "All", car_parts=CarParts.common([CarHarness.subaru_d]))], - SUBARU_OUTBACK.specs, - flags=SubaruFlags.LKAS_ANGLE, - ) - SUBARU_ASCENT_2023 = SubaruGen2PlatformConfig( - [SubaruCarDocs("Subaru Ascent 2023", "All", car_parts=CarParts.common([CarHarness.subaru_d]))], - SUBARU_ASCENT.specs, - flags=SubaruFlags.LKAS_ANGLE, - ) - - -SUBARU_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ - p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_DATA_IDENTIFICATION) -SUBARU_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ - p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_DATA_IDENTIFICATION) - -# The EyeSight ECU takes 10s to respond to SUBARU_VERSION_REQUEST properly, -# log this alternate manufacturer-specific query -SUBARU_ALT_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ - p16(0xf100) -SUBARU_ALT_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ - p16(0xf100) - -FW_QUERY_CONFIG = FwQueryConfig( - requests=[ - Request( - [StdQueries.TESTER_PRESENT_REQUEST, SUBARU_VERSION_REQUEST], - [StdQueries.TESTER_PRESENT_RESPONSE, SUBARU_VERSION_RESPONSE], - whitelist_ecus=[Ecu.abs, Ecu.eps, Ecu.fwdCamera, Ecu.engine, Ecu.transmission], - logging=True, - ), - # Non-OBD requests - # Some Eyesight modules fail on TESTER_PRESENT_REQUEST - # TODO: check if this resolves the fingerprinting issue for the 2023 Ascent and other new Subaru cars - Request( - [SUBARU_VERSION_REQUEST], - [SUBARU_VERSION_RESPONSE], - whitelist_ecus=[Ecu.fwdCamera], - bus=0, - ), - Request( - [SUBARU_ALT_VERSION_REQUEST], - [SUBARU_ALT_VERSION_RESPONSE], - whitelist_ecus=[Ecu.fwdCamera], - bus=0, - logging=True, - ), - Request( - [StdQueries.DEFAULT_DIAGNOSTIC_REQUEST, StdQueries.TESTER_PRESENT_REQUEST, SUBARU_VERSION_REQUEST], - [StdQueries.DEFAULT_DIAGNOSTIC_RESPONSE, StdQueries.TESTER_PRESENT_RESPONSE, SUBARU_VERSION_RESPONSE], - whitelist_ecus=[Ecu.fwdCamera], - bus=0, - logging=True, - ), - Request( - [StdQueries.TESTER_PRESENT_REQUEST, SUBARU_VERSION_REQUEST], - [StdQueries.TESTER_PRESENT_RESPONSE, SUBARU_VERSION_RESPONSE], - whitelist_ecus=[Ecu.abs, Ecu.eps, Ecu.fwdCamera, Ecu.engine, Ecu.transmission], - bus=0, - ), - # GEN2 powertrain bus query - Request( - [StdQueries.TESTER_PRESENT_REQUEST, SUBARU_VERSION_REQUEST], - [StdQueries.TESTER_PRESENT_RESPONSE, SUBARU_VERSION_RESPONSE], - whitelist_ecus=[Ecu.abs, Ecu.eps, Ecu.fwdCamera, Ecu.engine, Ecu.transmission], - bus=1, - obd_multiplexing=False, - ), - ], - # We don't get the EPS from non-OBD queries on GEN2 cars. Note that we still attempt to match when it exists - non_essential_ecus={ - Ecu.eps: list(CAR.with_flags(SubaruFlags.GLOBAL_GEN2)), - } -) - -DBC = CAR.create_dbc_map() diff --git a/car/tesla/__init__.py b/car/tesla/__init__.py deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/car/tesla/carcontroller.py b/car/tesla/carcontroller.py deleted file mode 100644 index e460111e32..0000000000 --- a/car/tesla/carcontroller.py +++ /dev/null @@ -1,67 +0,0 @@ -from openpilot.common.numpy_fast import clip -from opendbc.can.packer import CANPacker -from openpilot.selfdrive.car import apply_std_steer_angle_limits -from openpilot.selfdrive.car.interfaces import CarControllerBase -from openpilot.selfdrive.car.tesla.teslacan import TeslaCAN -from openpilot.selfdrive.car.tesla.values import DBC, CANBUS, CarControllerParams - - -class CarController(CarControllerBase): - def __init__(self, dbc_name, CP, VM): - self.CP = CP - self.frame = 0 - self.apply_angle_last = 0 - self.packer = CANPacker(dbc_name) - self.pt_packer = CANPacker(DBC[CP.carFingerprint]['pt']) - self.tesla_can = TeslaCAN(self.packer, self.pt_packer) - - def update(self, CC, CS, now_nanos): - actuators = CC.actuators - pcm_cancel_cmd = CC.cruiseControl.cancel - - can_sends = [] - - # Temp disable steering on a hands_on_fault, and allow for user override - hands_on_fault = CS.steer_warning == "EAC_ERROR_HANDS_ON" and CS.hands_on_level >= 3 - lkas_enabled = CC.latActive and not hands_on_fault - - if self.frame % 2 == 0: - if lkas_enabled: - # Angular rate limit based on speed - apply_angle = apply_std_steer_angle_limits(actuators.steeringAngleDeg, self.apply_angle_last, CS.out.vEgo, CarControllerParams) - - # To not fault the EPS - apply_angle = clip(apply_angle, CS.out.steeringAngleDeg - 20, CS.out.steeringAngleDeg + 20) - else: - apply_angle = CS.out.steeringAngleDeg - - self.apply_angle_last = apply_angle - can_sends.append(self.tesla_can.create_steering_control(apply_angle, lkas_enabled, (self.frame // 2) % 16)) - - # Longitudinal control (in sync with stock message, about 40Hz) - if self.CP.openpilotLongitudinalControl: - target_accel = actuators.accel - target_speed = max(CS.out.vEgo + (target_accel * CarControllerParams.ACCEL_TO_SPEED_MULTIPLIER), 0) - max_accel = 0 if target_accel < 0 else target_accel - min_accel = 0 if target_accel > 0 else target_accel - - while len(CS.das_control_counters) > 0: - can_sends.extend(self.tesla_can.create_longitudinal_commands(CS.acc_state, target_speed, min_accel, max_accel, CS.das_control_counters.popleft())) - - # Cancel on user steering override, since there is no steering torque blending - if hands_on_fault: - pcm_cancel_cmd = True - - if self.frame % 10 == 0 and pcm_cancel_cmd: - # Spam every possible counter value, otherwise it might not be accepted - for counter in range(16): - can_sends.append(self.tesla_can.create_action_request(CS.msg_stw_actn_req, pcm_cancel_cmd, CANBUS.chassis, counter)) - can_sends.append(self.tesla_can.create_action_request(CS.msg_stw_actn_req, pcm_cancel_cmd, CANBUS.autopilot_chassis, counter)) - - # TODO: HUD control - - new_actuators = actuators.as_builder() - new_actuators.steeringAngleDeg = self.apply_angle_last - - self.frame += 1 - return new_actuators, can_sends diff --git a/car/tesla/carstate.py b/car/tesla/carstate.py deleted file mode 100644 index 645ea46014..0000000000 --- a/car/tesla/carstate.py +++ /dev/null @@ -1,139 +0,0 @@ -import copy -from collections import deque -from cereal import car -from openpilot.common.conversions import Conversions as CV -from openpilot.selfdrive.car.tesla.values import CAR, DBC, CANBUS, GEAR_MAP, DOORS, BUTTONS -from openpilot.selfdrive.car.interfaces import CarStateBase -from opendbc.can.parser import CANParser -from opendbc.can.can_define import CANDefine - -class CarState(CarStateBase): - def __init__(self, CP): - super().__init__(CP) - self.button_states = {button.event_type: False for button in BUTTONS} - self.can_define = CANDefine(DBC[CP.carFingerprint]['chassis']) - - # Needed by carcontroller - self.msg_stw_actn_req = None - self.hands_on_level = 0 - self.steer_warning = None - self.acc_state = 0 - self.das_control_counters = deque(maxlen=32) - - def update(self, cp, cp_cam): - ret = car.CarState.new_message() - - # Vehicle speed - ret.vEgoRaw = cp.vl["ESP_B"]["ESP_vehicleSpeed"] * CV.KPH_TO_MS - ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) - ret.standstill = (ret.vEgo < 0.1) - - # Gas pedal - ret.gas = cp.vl["DI_torque1"]["DI_pedalPos"] / 100.0 - ret.gasPressed = (ret.gas > 0) - - # Brake pedal - ret.brake = 0 - ret.brakePressed = bool(cp.vl["BrakeMessage"]["driverBrakeStatus"] != 1) - - # Steering wheel - epas_status = cp_cam.vl["EPAS3P_sysStatus"] if self.CP.carFingerprint == CAR.TESLA_MODELS_RAVEN else cp.vl["EPAS_sysStatus"] - - self.hands_on_level = epas_status["EPAS_handsOnLevel"] - self.steer_warning = self.can_define.dv["EPAS_sysStatus"]["EPAS_eacErrorCode"].get(int(epas_status["EPAS_eacErrorCode"]), None) - steer_status = self.can_define.dv["EPAS_sysStatus"]["EPAS_eacStatus"].get(int(epas_status["EPAS_eacStatus"]), None) - - ret.steeringAngleDeg = -epas_status["EPAS_internalSAS"] - ret.steeringRateDeg = -cp.vl["STW_ANGLHP_STAT"]["StW_AnglHP_Spd"] # This is from a different angle sensor, and at different rate - ret.steeringTorque = -epas_status["EPAS_torsionBarTorque"] - ret.steeringPressed = (self.hands_on_level > 0) - ret.steerFaultPermanent = steer_status == "EAC_FAULT" - ret.steerFaultTemporary = (self.steer_warning not in ("EAC_ERROR_IDLE", "EAC_ERROR_HANDS_ON")) - - # Cruise state - cruise_state = self.can_define.dv["DI_state"]["DI_cruiseState"].get(int(cp.vl["DI_state"]["DI_cruiseState"]), None) - speed_units = self.can_define.dv["DI_state"]["DI_speedUnits"].get(int(cp.vl["DI_state"]["DI_speedUnits"]), None) - - acc_enabled = (cruise_state in ("ENABLED", "STANDSTILL", "OVERRIDE", "PRE_FAULT", "PRE_CANCEL")) - - ret.cruiseState.enabled = acc_enabled - if speed_units == "KPH": - ret.cruiseState.speed = cp.vl["DI_state"]["DI_digitalSpeed"] * CV.KPH_TO_MS - elif speed_units == "MPH": - ret.cruiseState.speed = cp.vl["DI_state"]["DI_digitalSpeed"] * CV.MPH_TO_MS - ret.cruiseState.available = ((cruise_state == "STANDBY") or ret.cruiseState.enabled) - ret.cruiseState.standstill = False # This needs to be false, since we can resume from stop without sending anything special - - # Gear - ret.gearShifter = GEAR_MAP[self.can_define.dv["DI_torque2"]["DI_gear"].get(int(cp.vl["DI_torque2"]["DI_gear"]), "DI_GEAR_INVALID")] - - # Buttons - buttonEvents = [] - for button in BUTTONS: - state = (cp.vl[button.can_addr][button.can_msg] in button.values) - if self.button_states[button.event_type] != state: - event = car.CarState.ButtonEvent.new_message() - event.type = button.event_type - event.pressed = state - buttonEvents.append(event) - self.button_states[button.event_type] = state - ret.buttonEvents = buttonEvents - - # Doors - ret.doorOpen = any((self.can_define.dv["GTW_carState"][door].get(int(cp.vl["GTW_carState"][door]), "OPEN") == "OPEN") for door in DOORS) - - # Blinkers - ret.leftBlinker = (cp.vl["GTW_carState"]["BC_indicatorLStatus"] == 1) - ret.rightBlinker = (cp.vl["GTW_carState"]["BC_indicatorRStatus"] == 1) - - # Seatbelt - if self.CP.carFingerprint == CAR.TESLA_MODELS_RAVEN: - ret.seatbeltUnlatched = (cp.vl["DriverSeat"]["buckleStatus"] != 1) - else: - ret.seatbeltUnlatched = (cp.vl["SDM1"]["SDM_bcklDrivStatus"] != 1) - - # TODO: blindspot - - # AEB - ret.stockAeb = (cp_cam.vl["DAS_control"]["DAS_aebEvent"] == 1) - - # Messages needed by carcontroller - self.msg_stw_actn_req = copy.copy(cp.vl["STW_ACTN_RQ"]) - self.acc_state = cp_cam.vl["DAS_control"]["DAS_accState"] - self.das_control_counters.extend(cp_cam.vl_all["DAS_control"]["DAS_controlCounter"]) - - return ret - - @staticmethod - def get_can_parser(CP): - messages = [ - # sig_address, frequency - ("ESP_B", 50), - ("DI_torque1", 100), - ("DI_torque2", 100), - ("STW_ANGLHP_STAT", 100), - ("EPAS_sysStatus", 25), - ("DI_state", 10), - ("STW_ACTN_RQ", 10), - ("GTW_carState", 10), - ("BrakeMessage", 50), - ] - - if CP.carFingerprint == CAR.TESLA_MODELS_RAVEN: - messages.append(("DriverSeat", 20)) - else: - messages.append(("SDM1", 10)) - - return CANParser(DBC[CP.carFingerprint]['chassis'], messages, CANBUS.chassis) - - @staticmethod - def get_cam_can_parser(CP): - messages = [ - # sig_address, frequency - ("DAS_control", 40), - ] - - if CP.carFingerprint == CAR.TESLA_MODELS_RAVEN: - messages.append(("EPAS3P_sysStatus", 100)) - - return CANParser(DBC[CP.carFingerprint]['chassis'], messages, CANBUS.autopilot_chassis) diff --git a/car/tesla/fingerprints.py b/car/tesla/fingerprints.py deleted file mode 100644 index 68c50a62ed..0000000000 --- a/car/tesla/fingerprints.py +++ /dev/null @@ -1,32 +0,0 @@ -from cereal import car -from openpilot.selfdrive.car.tesla.values import CAR - -Ecu = car.CarParams.Ecu - -FW_VERSIONS = { - CAR.TESLA_AP2_MODELS: { - (Ecu.adas, 0x649, None): [ - b'\x01\x00\x8b\x07\x01\x00\x01\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x11', - ], - (Ecu.electricBrakeBooster, 0x64d, None): [ - b'1037123-00-A', - ], - (Ecu.fwdRadar, 0x671, None): [ - b'\x01\x00W\x00\x00\x00\x07\x00\x00\x00\x00\x08\x01\x00\x00\x00\x07\xff\xfe', - ], - (Ecu.eps, 0x730, None): [ - b'\x10#\x01', - ], - }, - CAR.TESLA_MODELS_RAVEN: { - (Ecu.electricBrakeBooster, 0x64d, None): [ - b'1037123-00-A', - ], - (Ecu.fwdRadar, 0x671, None): [ - b'\x01\x00\x99\x02\x01\x00\x10\x00\x00AP8.3.03\x00\x10', - ], - (Ecu.eps, 0x730, None): [ - b'SX_0.0.0 (99),SR013.7', - ], - }, -} diff --git a/car/tesla/interface.py b/car/tesla/interface.py deleted file mode 100755 index e039859263..0000000000 --- a/car/tesla/interface.py +++ /dev/null @@ -1,52 +0,0 @@ -#!/usr/bin/env python3 -from cereal import car -from panda import Panda -from openpilot.selfdrive.car.tesla.values import CANBUS, CAR -from openpilot.selfdrive.car import get_safety_config -from openpilot.selfdrive.car.interfaces import CarInterfaceBase - - -class CarInterface(CarInterfaceBase): - @staticmethod - def _get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs): - ret.carName = "tesla" - - # There is no safe way to do steer blending with user torque, - # so the steering behaves like autopilot. This is not - # how openpilot should be, hence dashcamOnly - ret.dashcamOnly = True - - ret.steerControlType = car.CarParams.SteerControlType.angle - - # Set kP and kI to 0 over the whole speed range to have the planner accel as actuator command - ret.longitudinalTuning.kpBP = [0] - ret.longitudinalTuning.kpV = [0] - ret.longitudinalTuning.kiBP = [0] - ret.longitudinalTuning.kiV = [0] - ret.longitudinalActuatorDelayUpperBound = 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 - # If so, we assume that it is connected to the longitudinal harness. - flags = (Panda.FLAG_TESLA_RAVEN if candidate == CAR.TESLA_MODELS_RAVEN else 0) - if (CANBUS.autopilot_powertrain in fingerprint.keys()) and (0x2bf in fingerprint[CANBUS.autopilot_powertrain].keys()): - ret.openpilotLongitudinalControl = True - flags |= Panda.FLAG_TESLA_LONG_CONTROL - ret.safetyConfigs = [ - get_safety_config(car.CarParams.SafetyModel.tesla, flags), - get_safety_config(car.CarParams.SafetyModel.tesla, flags | Panda.FLAG_TESLA_POWERTRAIN), - ] - else: - ret.openpilotLongitudinalControl = False - ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.tesla, flags)] - - ret.steerLimitTimer = 1.0 - ret.steerActuatorDelay = 0.25 - return ret - - def _update(self, c): - ret = self.CS.update(self.cp, self.cp_cam) - - ret.events = self.create_common_events(ret).to_msg() - - return ret diff --git a/car/tesla/radar_interface.py b/car/tesla/radar_interface.py deleted file mode 100755 index ae5077824b..0000000000 --- a/car/tesla/radar_interface.py +++ /dev/null @@ -1,91 +0,0 @@ -#!/usr/bin/env python3 -from cereal import car -from opendbc.can.parser import CANParser -from openpilot.selfdrive.car.tesla.values import CAR, DBC, CANBUS -from openpilot.selfdrive.car.interfaces import RadarInterfaceBase - - -class RadarInterface(RadarInterfaceBase): - def __init__(self, CP): - super().__init__(CP) - self.CP = CP - - if CP.carFingerprint == CAR.TESLA_MODELS_RAVEN: - messages = [('RadarStatus', 16)] - self.num_points = 40 - self.trigger_msg = 1119 - else: - messages = [('TeslaRadarSguInfo', 10)] - self.num_points = 32 - self.trigger_msg = 878 - - for i in range(self.num_points): - messages.extend([ - (f'RadarPoint{i}_A', 16), - (f'RadarPoint{i}_B', 16), - ]) - - self.rcp = CANParser(DBC[CP.carFingerprint]['radar'], messages, CANBUS.radar) - self.updated_messages = set() - self.track_id = 0 - - def update(self, can_strings): - if self.rcp is None: - return super().update(None) - - values = self.rcp.update_strings(can_strings) - self.updated_messages.update(values) - - if self.trigger_msg not in self.updated_messages: - return None - - ret = car.RadarData.new_message() - - # Errors - errors = [] - if not self.rcp.can_valid: - errors.append('canError') - - if self.CP.carFingerprint == CAR.TESLA_MODELS_RAVEN: - radar_status = self.rcp.vl['RadarStatus'] - if radar_status['sensorBlocked'] or radar_status['shortTermUnavailable'] or radar_status['vehDynamicsError']: - errors.append('fault') - else: - radar_status = self.rcp.vl['TeslaRadarSguInfo'] - if radar_status['RADC_HWFail'] or radar_status['RADC_SGUFail'] or radar_status['RADC_SensorDirty']: - errors.append('fault') - - ret.errors = errors - - # Radar tracks - for i in range(self.num_points): - msg_a = self.rcp.vl[f'RadarPoint{i}_A'] - msg_b = self.rcp.vl[f'RadarPoint{i}_B'] - - # Make sure msg A and B are together - if msg_a['Index'] != msg_b['Index2']: - continue - - # Check if it's a valid track - if not msg_a['Tracked']: - if i in self.pts: - del self.pts[i] - continue - - # New track! - if i not in self.pts: - self.pts[i] = car.RadarData.RadarPoint.new_message() - self.pts[i].trackId = self.track_id - self.track_id += 1 - - # Parse track data - self.pts[i].dRel = msg_a['LongDist'] - self.pts[i].yRel = msg_a['LatDist'] - self.pts[i].vRel = msg_a['LongSpeed'] - self.pts[i].aRel = msg_a['LongAccel'] - self.pts[i].yvRel = msg_b['LatSpeed'] - self.pts[i].measured = bool(msg_a['Meas']) - - ret.points = list(self.pts.values()) - self.updated_messages.clear() - return ret diff --git a/car/tesla/teslacan.py b/car/tesla/teslacan.py deleted file mode 100644 index 6bb27b995f..0000000000 --- a/car/tesla/teslacan.py +++ /dev/null @@ -1,94 +0,0 @@ -import crcmod - -from openpilot.common.conversions import Conversions as CV -from openpilot.selfdrive.car.tesla.values import CANBUS, CarControllerParams - - -class TeslaCAN: - def __init__(self, packer, pt_packer): - self.packer = packer - self.pt_packer = pt_packer - self.crc = crcmod.mkCrcFun(0x11d, initCrc=0x00, rev=False, xorOut=0xff) - - @staticmethod - def checksum(msg_id, dat): - # TODO: get message ID from name instead - ret = (msg_id & 0xFF) + ((msg_id >> 8) & 0xFF) - ret += sum(dat) - return ret & 0xFF - - def create_steering_control(self, angle, enabled, counter): - values = { - "DAS_steeringAngleRequest": -angle, - "DAS_steeringHapticRequest": 0, - "DAS_steeringControlType": 1 if enabled else 0, - "DAS_steeringControlCounter": counter, - } - - data = self.packer.make_can_msg("DAS_steeringControl", CANBUS.chassis, values)[2] - values["DAS_steeringControlChecksum"] = self.checksum(0x488, data[:3]) - return self.packer.make_can_msg("DAS_steeringControl", CANBUS.chassis, values) - - def create_action_request(self, msg_stw_actn_req, cancel, bus, counter): - # We copy this whole message when spamming cancel - values = {s: msg_stw_actn_req[s] for s in [ - "SpdCtrlLvr_Stat", - "VSL_Enbl_Rq", - "SpdCtrlLvrStat_Inv", - "DTR_Dist_Rq", - "TurnIndLvr_Stat", - "HiBmLvr_Stat", - "WprWashSw_Psd", - "WprWash_R_Sw_Posn_V2", - "StW_Lvr_Stat", - "StW_Cond_Flt", - "StW_Cond_Psd", - "HrnSw_Psd", - "StW_Sw00_Psd", - "StW_Sw01_Psd", - "StW_Sw02_Psd", - "StW_Sw03_Psd", - "StW_Sw04_Psd", - "StW_Sw05_Psd", - "StW_Sw06_Psd", - "StW_Sw07_Psd", - "StW_Sw08_Psd", - "StW_Sw09_Psd", - "StW_Sw10_Psd", - "StW_Sw11_Psd", - "StW_Sw12_Psd", - "StW_Sw13_Psd", - "StW_Sw14_Psd", - "StW_Sw15_Psd", - "WprSw6Posn", - "MC_STW_ACTN_RQ", - "CRC_STW_ACTN_RQ", - ]} - - if cancel: - values["SpdCtrlLvr_Stat"] = 1 - values["MC_STW_ACTN_RQ"] = counter - - data = self.packer.make_can_msg("STW_ACTN_RQ", bus, values)[2] - values["CRC_STW_ACTN_RQ"] = self.crc(data[:7]) - return self.packer.make_can_msg("STW_ACTN_RQ", bus, values) - - def create_longitudinal_commands(self, acc_state, speed, min_accel, max_accel, cnt): - messages = [] - values = { - "DAS_setSpeed": speed * CV.MS_TO_KPH, - "DAS_accState": acc_state, - "DAS_aebEvent": 0, - "DAS_jerkMin": CarControllerParams.JERK_LIMIT_MIN, - "DAS_jerkMax": CarControllerParams.JERK_LIMIT_MAX, - "DAS_accelMin": min_accel, - "DAS_accelMax": max_accel, - "DAS_controlCounter": cnt, - "DAS_controlChecksum": 0, - } - - for packer, bus in [(self.packer, CANBUS.chassis), (self.pt_packer, CANBUS.powertrain)]: - data = packer.make_can_msg("DAS_control", bus, values)[2] - values["DAS_controlChecksum"] = self.checksum(0x2b9, data[:7]) - messages.append(packer.make_can_msg("DAS_control", bus, values)) - return messages diff --git a/car/tesla/values.py b/car/tesla/values.py deleted file mode 100644 index 0f9cd00f63..0000000000 --- a/car/tesla/values.py +++ /dev/null @@ -1,98 +0,0 @@ -from collections import namedtuple - -from cereal import car -from openpilot.selfdrive.car import AngleRateLimit, CarSpecs, PlatformConfig, Platforms, dbc_dict -from openpilot.selfdrive.car.docs_definitions import CarDocs -from openpilot.selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries - -Ecu = car.CarParams.Ecu - -Button = namedtuple('Button', ['event_type', 'can_addr', 'can_msg', 'values']) - -class CAR(Platforms): - TESLA_AP1_MODELS = PlatformConfig( - [CarDocs("Tesla AP1 Model S", "All")], - CarSpecs(mass=2100., wheelbase=2.959, steerRatio=15.0), - dbc_dict('tesla_powertrain', 'tesla_radar_bosch_generated', chassis_dbc='tesla_can') - ) - TESLA_AP2_MODELS = PlatformConfig( - [CarDocs("Tesla AP2 Model S", "All")], - TESLA_AP1_MODELS.specs, - TESLA_AP1_MODELS.dbc_dict - ) - TESLA_MODELS_RAVEN = PlatformConfig( - [CarDocs("Tesla Model S Raven", "All")], - TESLA_AP1_MODELS.specs, - dbc_dict('tesla_powertrain', 'tesla_radar_continental_generated', chassis_dbc='tesla_can') - ) - -FW_QUERY_CONFIG = FwQueryConfig( - requests=[ - Request( - [StdQueries.TESTER_PRESENT_REQUEST, StdQueries.UDS_VERSION_REQUEST], - [StdQueries.TESTER_PRESENT_RESPONSE, StdQueries.UDS_VERSION_RESPONSE], - whitelist_ecus=[Ecu.eps], - rx_offset=0x08, - bus=0, - ), - Request( - [StdQueries.TESTER_PRESENT_REQUEST, StdQueries.SUPPLIER_SOFTWARE_VERSION_REQUEST], - [StdQueries.TESTER_PRESENT_RESPONSE, StdQueries.SUPPLIER_SOFTWARE_VERSION_RESPONSE], - whitelist_ecus=[Ecu.eps], - rx_offset=0x08, - bus=0, - ), - Request( - [StdQueries.TESTER_PRESENT_REQUEST, StdQueries.UDS_VERSION_REQUEST], - [StdQueries.TESTER_PRESENT_RESPONSE, StdQueries.UDS_VERSION_RESPONSE], - whitelist_ecus=[Ecu.adas, Ecu.electricBrakeBooster, Ecu.fwdRadar], - rx_offset=0x10, - bus=0, - ), - ] -) - -class CANBUS: - # Lateral harness - chassis = 0 - radar = 1 - autopilot_chassis = 2 - - # Longitudinal harness - powertrain = 4 - private = 5 - autopilot_powertrain = 6 - -GEAR_MAP = { - "DI_GEAR_INVALID": car.CarState.GearShifter.unknown, - "DI_GEAR_P": car.CarState.GearShifter.park, - "DI_GEAR_R": car.CarState.GearShifter.reverse, - "DI_GEAR_N": car.CarState.GearShifter.neutral, - "DI_GEAR_D": car.CarState.GearShifter.drive, - "DI_GEAR_SNA": car.CarState.GearShifter.unknown, -} - -DOORS = ["DOOR_STATE_FL", "DOOR_STATE_FR", "DOOR_STATE_RL", "DOOR_STATE_RR", "DOOR_STATE_FrontTrunk", "BOOT_STATE"] - -# Make sure the message and addr is also in the CAN parser! -BUTTONS = [ - Button(car.CarState.ButtonEvent.Type.leftBlinker, "STW_ACTN_RQ", "TurnIndLvr_Stat", [1]), - Button(car.CarState.ButtonEvent.Type.rightBlinker, "STW_ACTN_RQ", "TurnIndLvr_Stat", [2]), - Button(car.CarState.ButtonEvent.Type.accelCruise, "STW_ACTN_RQ", "SpdCtrlLvr_Stat", [4, 16]), - Button(car.CarState.ButtonEvent.Type.decelCruise, "STW_ACTN_RQ", "SpdCtrlLvr_Stat", [8, 32]), - Button(car.CarState.ButtonEvent.Type.cancel, "STW_ACTN_RQ", "SpdCtrlLvr_Stat", [1]), - Button(car.CarState.ButtonEvent.Type.resumeCruise, "STW_ACTN_RQ", "SpdCtrlLvr_Stat", [2]), -] - -class CarControllerParams: - ANGLE_RATE_LIMIT_UP = AngleRateLimit(speed_bp=[0., 5., 15.], angle_v=[10., 1.6, .3]) - ANGLE_RATE_LIMIT_DOWN = AngleRateLimit(speed_bp=[0., 5., 15.], angle_v=[10., 7.0, 0.8]) - JERK_LIMIT_MAX = 8 - JERK_LIMIT_MIN = -8 - ACCEL_TO_SPEED_MULTIPLIER = 3 - - def __init__(self, CP): - pass - - -DBC = CAR.create_dbc_map() diff --git a/car/toyota/__init__.py b/car/toyota/__init__.py deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/car/toyota/carcontroller.py b/car/toyota/carcontroller.py deleted file mode 100644 index f9b7a478e0..0000000000 --- a/car/toyota/carcontroller.py +++ /dev/null @@ -1,179 +0,0 @@ -from cereal import car -from openpilot.common.numpy_fast import clip -from openpilot.selfdrive.car import apply_meas_steer_torque_limits, apply_std_steer_angle_limits, common_fault_avoidance, make_can_msg -from openpilot.selfdrive.car.interfaces import CarControllerBase -from openpilot.selfdrive.car.toyota import toyotacan -from openpilot.selfdrive.car.toyota.values import CAR, STATIC_DSU_MSGS, NO_STOP_TIMER_CAR, TSS2_CAR, \ - CarControllerParams, ToyotaFlags, \ - UNSUPPORTED_DSU_CAR -from opendbc.can.packer import CANPacker - -SteerControlType = car.CarParams.SteerControlType -VisualAlert = car.CarControl.HUDControl.VisualAlert - -# LKA limits -# EPS faults if you apply torque while the steering rate is above 100 deg/s for too long -MAX_STEER_RATE = 100 # deg/s -MAX_STEER_RATE_FRAMES = 18 # tx control frames needed before torque can be cut - -# EPS allows user torque above threshold for 50 frames before permanently faulting -MAX_USER_TORQUE = 500 - -# LTA limits -# EPS ignores commands above this angle and causes PCS to fault -MAX_LTA_ANGLE = 94.9461 # deg -MAX_LTA_DRIVER_TORQUE_ALLOWANCE = 150 # slightly above steering pressed allows some resistance when changing lanes - - -class CarController(CarControllerBase): - def __init__(self, dbc_name, CP, VM): - self.CP = CP - self.params = CarControllerParams(self.CP) - self.frame = 0 - self.last_steer = 0 - self.last_angle = 0 - self.alert_active = False - self.last_standstill = False - self.standstill_req = False - self.steer_rate_counter = 0 - self.distance_button = 0 - - self.packer = CANPacker(dbc_name) - self.gas = 0 - self.accel = 0 - - def update(self, CC, CS, now_nanos): - actuators = CC.actuators - hud_control = CC.hudControl - pcm_cancel_cmd = CC.cruiseControl.cancel - lat_active = CC.latActive and abs(CS.out.steeringTorque) < MAX_USER_TORQUE - - # *** control msgs *** - can_sends = [] - - # *** steer torque *** - new_steer = int(round(actuators.steer * self.params.STEER_MAX)) - apply_steer = apply_meas_steer_torque_limits(new_steer, self.last_steer, CS.out.steeringTorqueEps, self.params) - - # >100 degree/sec steering fault prevention - self.steer_rate_counter, apply_steer_req = common_fault_avoidance(abs(CS.out.steeringRateDeg) >= MAX_STEER_RATE, lat_active, - self.steer_rate_counter, MAX_STEER_RATE_FRAMES) - - if not lat_active: - apply_steer = 0 - - # *** steer angle *** - if self.CP.steerControlType == SteerControlType.angle: - # If using LTA control, disable LKA and set steering angle command - apply_steer = 0 - apply_steer_req = False - if self.frame % 2 == 0: - # EPS uses the torque sensor angle to control with, offset to compensate - apply_angle = actuators.steeringAngleDeg + CS.out.steeringAngleOffsetDeg - - # Angular rate limit based on speed - apply_angle = apply_std_steer_angle_limits(apply_angle, self.last_angle, CS.out.vEgoRaw, self.params) - - if not lat_active: - apply_angle = CS.out.steeringAngleDeg + CS.out.steeringAngleOffsetDeg - - self.last_angle = clip(apply_angle, -MAX_LTA_ANGLE, MAX_LTA_ANGLE) - - self.last_steer = apply_steer - - # toyota can trace shows STEERING_LKA at 42Hz, with counter adding alternatively 1 and 2; - # sending it at 100Hz seem to allow a higher rate limit, as the rate limit seems imposed - # on consecutive messages - can_sends.append(toyotacan.create_steer_command(self.packer, apply_steer, apply_steer_req)) - - # STEERING_LTA does not seem to allow more rate by sending faster, and may wind up easier - if self.frame % 2 == 0 and self.CP.carFingerprint in TSS2_CAR: - lta_active = lat_active and self.CP.steerControlType == SteerControlType.angle - # cut steering torque with TORQUE_WIND_DOWN when either EPS torque or driver torque is above - # the threshold, to limit max lateral acceleration and for driver torque blending respectively. - full_torque_condition = (abs(CS.out.steeringTorqueEps) < self.params.STEER_MAX and - abs(CS.out.steeringTorque) < MAX_LTA_DRIVER_TORQUE_ALLOWANCE) - - # TORQUE_WIND_DOWN at 0 ramps down torque at roughly the max down rate of 1500 units/sec - torque_wind_down = 100 if lta_active and full_torque_condition else 0 - can_sends.append(toyotacan.create_lta_steer_command(self.packer, self.CP.steerControlType, self.last_angle, - lta_active, self.frame // 2, torque_wind_down)) - - # *** gas and brake *** - pcm_accel_cmd = clip(actuators.accel, self.params.ACCEL_MIN, self.params.ACCEL_MAX) - - # on entering standstill, send standstill request - if CS.out.standstill and not self.last_standstill and (self.CP.carFingerprint not in NO_STOP_TIMER_CAR): - self.standstill_req = True - if CS.pcm_acc_status != 8: - # pcm entered standstill or it's disabled - self.standstill_req = False - - self.last_standstill = CS.out.standstill - - # handle UI messages - fcw_alert = hud_control.visualAlert == VisualAlert.fcw - steer_alert = hud_control.visualAlert in (VisualAlert.steerRequired, VisualAlert.ldw) - - # we can spam can to cancel the system even if we are using lat only control - if (self.frame % 3 == 0 and self.CP.openpilotLongitudinalControl) or pcm_cancel_cmd: - lead = hud_control.leadVisible or CS.out.vEgo < 12. # at low speed we always assume the lead is present so ACC can be engaged - - # Press distance button until we are at the correct bar length. Only change while enabled to avoid skipping startup popup - if self.frame % 6 == 0 and self.CP.openpilotLongitudinalControl: - desired_distance = 4 - hud_control.leadDistanceBars - if CS.out.cruiseState.enabled and CS.pcm_follow_distance != desired_distance: - self.distance_button = not self.distance_button - else: - self.distance_button = 0 - - # Lexus IS uses a different cancellation message - if pcm_cancel_cmd and self.CP.carFingerprint in UNSUPPORTED_DSU_CAR: - can_sends.append(toyotacan.create_acc_cancel_command(self.packer)) - elif self.CP.openpilotLongitudinalControl: - can_sends.append(toyotacan.create_accel_command(self.packer, pcm_accel_cmd, pcm_cancel_cmd, self.standstill_req, lead, CS.acc_type, fcw_alert, - self.distance_button)) - self.accel = pcm_accel_cmd - else: - can_sends.append(toyotacan.create_accel_command(self.packer, 0, pcm_cancel_cmd, False, lead, CS.acc_type, False, self.distance_button)) - - # *** hud ui *** - if self.CP.carFingerprint != CAR.TOYOTA_PRIUS_V: - # ui mesg is at 1Hz but we send asap if: - # - there is something to display - # - there is something to stop displaying - send_ui = False - if ((fcw_alert or steer_alert) and not self.alert_active) or \ - (not (fcw_alert or steer_alert) and self.alert_active): - send_ui = True - self.alert_active = not self.alert_active - elif pcm_cancel_cmd: - # forcing the pcm to disengage causes a bad fault sound so play a good sound instead - send_ui = True - - if self.frame % 20 == 0 or send_ui: - can_sends.append(toyotacan.create_ui_command(self.packer, steer_alert, pcm_cancel_cmd, hud_control.leftLaneVisible, - hud_control.rightLaneVisible, hud_control.leftLaneDepart, - hud_control.rightLaneDepart, CC.enabled, CS.lkas_hud)) - - if (self.frame % 100 == 0 or send_ui) and (self.CP.enableDsu or self.CP.flags & ToyotaFlags.DISABLE_RADAR.value): - can_sends.append(toyotacan.create_fcw_command(self.packer, fcw_alert)) - - # *** static msgs *** - for addr, cars, bus, fr_step, vl in STATIC_DSU_MSGS: - if self.frame % fr_step == 0 and self.CP.enableDsu and self.CP.carFingerprint in cars: - can_sends.append(make_can_msg(addr, vl, bus)) - - # keep radar disabled - if self.frame % 20 == 0 and self.CP.flags & ToyotaFlags.DISABLE_RADAR.value: - can_sends.append([0x750, 0, b"\x0F\x02\x3E\x00\x00\x00\x00\x00", 0]) - - new_actuators = actuators.as_builder() - new_actuators.steer = apply_steer / self.params.STEER_MAX - new_actuators.steerOutputCan = apply_steer - new_actuators.steeringAngleDeg = self.last_angle - new_actuators.accel = self.accel - new_actuators.gas = self.gas - - self.frame += 1 - return new_actuators, can_sends diff --git a/car/toyota/carstate.py b/car/toyota/carstate.py deleted file mode 100644 index 8315f24ae4..0000000000 --- a/car/toyota/carstate.py +++ /dev/null @@ -1,247 +0,0 @@ -import copy - -from cereal import car -from openpilot.common.conversions import Conversions as CV -from openpilot.common.numpy_fast import mean -from openpilot.common.filter_simple import FirstOrderFilter -from openpilot.common.realtime import DT_CTRL -from opendbc.can.can_define import CANDefine -from opendbc.can.parser import CANParser -from openpilot.selfdrive.car.interfaces import CarStateBase -from openpilot.selfdrive.car.toyota.values import ToyotaFlags, CAR, DBC, STEER_THRESHOLD, NO_STOP_TIMER_CAR, \ - TSS2_CAR, RADAR_ACC_CAR, EPS_SCALE, UNSUPPORTED_DSU_CAR - -SteerControlType = car.CarParams.SteerControlType - -# These steering fault definitions seem to be common across LKA (torque) and LTA (angle): -# - high steer rate fault: goes to 21 or 25 for 1 frame, then 9 for 2 seconds -# - lka/lta msg drop out: goes to 9 then 11 for a combined total of 2 seconds, then 3. -# if using the other control command, goes directly to 3 after 1.5 seconds -# - initializing: LTA can report 0 as long as STEER_TORQUE_SENSOR->STEER_ANGLE_INITIALIZING is 1, -# and is a catch-all for LKA -TEMP_STEER_FAULTS = (0, 9, 11, 21, 25) -# - lka/lta msg drop out: 3 (recoverable) -# - prolonged high driver torque: 17 (permanent) -PERM_STEER_FAULTS = (3, 17) - - -class CarState(CarStateBase): - def __init__(self, CP): - super().__init__(CP) - can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) - self.shifter_values = can_define.dv["GEAR_PACKET"]["GEAR"] - self.eps_torque_scale = EPS_SCALE[CP.carFingerprint] / 100. - self.cluster_speed_hyst_gap = CV.KPH_TO_MS / 2. - self.cluster_min_speed = CV.KPH_TO_MS / 2. - - # On cars with cp.vl["STEER_TORQUE_SENSOR"]["STEER_ANGLE"] - # the signal is zeroed to where the steering angle is at start. - # Need to apply an offset as soon as the steering angle measurements are both received - self.accurate_steer_angle_seen = False - self.angle_offset = FirstOrderFilter(None, 60.0, DT_CTRL, initialized=False) - - self.prev_distance_button = 0 - self.distance_button = 0 - - self.pcm_follow_distance = 0 - - self.low_speed_lockout = False - self.acc_type = 1 - self.lkas_hud = {} - - def update(self, cp, cp_cam): - ret = car.CarState.new_message() - - ret.doorOpen = any([cp.vl["BODY_CONTROL_STATE"]["DOOR_OPEN_FL"], cp.vl["BODY_CONTROL_STATE"]["DOOR_OPEN_FR"], - cp.vl["BODY_CONTROL_STATE"]["DOOR_OPEN_RL"], cp.vl["BODY_CONTROL_STATE"]["DOOR_OPEN_RR"]]) - ret.seatbeltUnlatched = cp.vl["BODY_CONTROL_STATE"]["SEATBELT_DRIVER_UNLATCHED"] != 0 - ret.parkingBrake = cp.vl["BODY_CONTROL_STATE"]["PARKING_BRAKE"] == 1 - - ret.brakePressed = cp.vl["BRAKE_MODULE"]["BRAKE_PRESSED"] != 0 - ret.brakeHoldActive = cp.vl["ESP_CONTROL"]["BRAKE_HOLD_ACTIVE"] == 1 - - ret.gasPressed = cp.vl["PCM_CRUISE"]["GAS_RELEASED"] == 0 - - ret.wheelSpeeds = self.get_wheel_speeds( - cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_FL"], - cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_FR"], - cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_RL"], - cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_RR"], - ) - 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.vEgoCluster = ret.vEgo * 1.015 # minimum of all the cars - - ret.standstill = abs(ret.vEgoRaw) < 1e-3 - - ret.steeringAngleDeg = cp.vl["STEER_ANGLE_SENSOR"]["STEER_ANGLE"] + cp.vl["STEER_ANGLE_SENSOR"]["STEER_FRACTION"] - ret.steeringRateDeg = cp.vl["STEER_ANGLE_SENSOR"]["STEER_RATE"] - torque_sensor_angle_deg = cp.vl["STEER_TORQUE_SENSOR"]["STEER_ANGLE"] - - # On some cars, the angle measurement is non-zero while initializing - if abs(torque_sensor_angle_deg) > 1e-3 and not bool(cp.vl["STEER_TORQUE_SENSOR"]["STEER_ANGLE_INITIALIZING"]): - self.accurate_steer_angle_seen = True - - if self.accurate_steer_angle_seen: - # Offset seems to be invalid for large steering angles and high angle rates - if abs(ret.steeringAngleDeg) < 90 and abs(ret.steeringRateDeg) < 100 and cp.can_valid: - self.angle_offset.update(torque_sensor_angle_deg - ret.steeringAngleDeg) - - if self.angle_offset.initialized: - ret.steeringAngleOffsetDeg = self.angle_offset.x - ret.steeringAngleDeg = torque_sensor_angle_deg - self.angle_offset.x - - can_gear = int(cp.vl["GEAR_PACKET"]["GEAR"]) - ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(can_gear, None)) - ret.leftBlinker = cp.vl["BLINKERS_STATE"]["TURN_SIGNALS"] == 1 - ret.rightBlinker = cp.vl["BLINKERS_STATE"]["TURN_SIGNALS"] == 2 - - if self.CP.carFingerprint != CAR.TOYOTA_MIRAI: - ret.engineRpm = cp.vl["ENGINE_RPM"]["RPM"] - - ret.steeringTorque = cp.vl["STEER_TORQUE_SENSOR"]["STEER_TORQUE_DRIVER"] - ret.steeringTorqueEps = cp.vl["STEER_TORQUE_SENSOR"]["STEER_TORQUE_EPS"] * self.eps_torque_scale - # we could use the override bit from dbc, but it's triggered at too high torque values - ret.steeringPressed = abs(ret.steeringTorque) > STEER_THRESHOLD - - # Check EPS LKA/LTA fault status - ret.steerFaultTemporary = cp.vl["EPS_STATUS"]["LKA_STATE"] in TEMP_STEER_FAULTS - ret.steerFaultPermanent = cp.vl["EPS_STATUS"]["LKA_STATE"] in PERM_STEER_FAULTS - - if self.CP.steerControlType == SteerControlType.angle: - ret.steerFaultTemporary = ret.steerFaultTemporary or cp.vl["EPS_STATUS"]["LTA_STATE"] in TEMP_STEER_FAULTS - ret.steerFaultPermanent = ret.steerFaultPermanent or cp.vl["EPS_STATUS"]["LTA_STATE"] in PERM_STEER_FAULTS - - if self.CP.carFingerprint in UNSUPPORTED_DSU_CAR: - # TODO: find the bit likely in DSU_CRUISE that describes an ACC fault. one may also exist in CLUTCH - ret.cruiseState.available = cp.vl["DSU_CRUISE"]["MAIN_ON"] != 0 - ret.cruiseState.speed = cp.vl["DSU_CRUISE"]["SET_SPEED"] * CV.KPH_TO_MS - cluster_set_speed = cp.vl["PCM_CRUISE_ALT"]["UI_SET_SPEED"] - else: - ret.accFaulted = cp.vl["PCM_CRUISE_2"]["ACC_FAULTED"] != 0 - ret.cruiseState.available = cp.vl["PCM_CRUISE_2"]["MAIN_ON"] != 0 - ret.cruiseState.speed = cp.vl["PCM_CRUISE_2"]["SET_SPEED"] * CV.KPH_TO_MS - cluster_set_speed = cp.vl["PCM_CRUISE_SM"]["UI_SET_SPEED"] - - # UI_SET_SPEED is always non-zero when main is on, hide until first enable - if ret.cruiseState.speed != 0: - is_metric = cp.vl["BODY_CONTROL_STATE_2"]["UNITS"] in (1, 2) - conversion_factor = CV.KPH_TO_MS if is_metric else CV.MPH_TO_MS - ret.cruiseState.speedCluster = cluster_set_speed * conversion_factor - - cp_acc = cp_cam if self.CP.carFingerprint in (TSS2_CAR - RADAR_ACC_CAR) else cp - - if self.CP.carFingerprint in TSS2_CAR and not self.CP.flags & ToyotaFlags.DISABLE_RADAR.value: - if not (self.CP.flags & ToyotaFlags.SMART_DSU.value): - self.acc_type = cp_acc.vl["ACC_CONTROL"]["ACC_TYPE"] - ret.stockFcw = bool(cp_acc.vl["PCS_HUD"]["FCW"]) - - # some TSS2 cars have low speed lockout permanently set, so ignore on those cars - # these cars are identified by an ACC_TYPE value of 2. - # TODO: it is possible to avoid the lockout and gain stop and go if you - # send your own ACC_CONTROL msg on startup with ACC_TYPE set to 1 - if (self.CP.carFingerprint not in TSS2_CAR and self.CP.carFingerprint not in UNSUPPORTED_DSU_CAR) or \ - (self.CP.carFingerprint in TSS2_CAR and self.acc_type == 1): - self.low_speed_lockout = cp.vl["PCM_CRUISE_2"]["LOW_SPEED_LOCKOUT"] == 2 - - self.pcm_acc_status = cp.vl["PCM_CRUISE"]["CRUISE_STATE"] - if self.CP.carFingerprint not in (NO_STOP_TIMER_CAR - TSS2_CAR): - # ignore standstill state in certain vehicles, since pcm allows to restart with just an acceleration request - ret.cruiseState.standstill = self.pcm_acc_status == 7 - ret.cruiseState.enabled = bool(cp.vl["PCM_CRUISE"]["CRUISE_ACTIVE"]) - ret.cruiseState.nonAdaptive = self.pcm_acc_status in (1, 2, 3, 4, 5, 6) - - ret.genericToggle = bool(cp.vl["LIGHT_STALK"]["AUTO_HIGH_BEAM"]) - ret.espDisabled = cp.vl["ESP_CONTROL"]["TC_DISABLED"] != 0 - - if not self.CP.enableDsu and not self.CP.flags & ToyotaFlags.DISABLE_RADAR.value: - ret.stockAeb = bool(cp_acc.vl["PRE_COLLISION"]["PRECOLLISION_ACTIVE"] and cp_acc.vl["PRE_COLLISION"]["FORCE"] < -1e-5) - - if self.CP.enableBsm: - ret.leftBlindspot = (cp.vl["BSM"]["L_ADJACENT"] == 1) or (cp.vl["BSM"]["L_APPROACHING"] == 1) - ret.rightBlindspot = (cp.vl["BSM"]["R_ADJACENT"] == 1) or (cp.vl["BSM"]["R_APPROACHING"] == 1) - - if self.CP.carFingerprint != CAR.TOYOTA_PRIUS_V: - self.lkas_hud = copy.copy(cp_cam.vl["LKAS_HUD"]) - - if self.CP.carFingerprint not in UNSUPPORTED_DSU_CAR: - self.pcm_follow_distance = cp.vl["PCM_CRUISE_2"]["PCM_FOLLOW_DISTANCE"] - - if self.CP.carFingerprint in (TSS2_CAR - RADAR_ACC_CAR) or (self.CP.flags & ToyotaFlags.SMART_DSU and not self.CP.flags & ToyotaFlags.RADAR_CAN_FILTER): - # distance button is wired to the ACC module (camera or radar) - self.prev_distance_button = self.distance_button - if self.CP.carFingerprint in (TSS2_CAR - RADAR_ACC_CAR): - self.distance_button = cp_acc.vl["ACC_CONTROL"]["DISTANCE"] - else: - self.distance_button = cp.vl["SDSU"]["FD_BUTTON"] - - return ret - - @staticmethod - def get_can_parser(CP): - messages = [ - ("GEAR_PACKET", 1), - ("LIGHT_STALK", 1), - ("BLINKERS_STATE", 0.15), - ("BODY_CONTROL_STATE", 3), - ("BODY_CONTROL_STATE_2", 2), - ("ESP_CONTROL", 3), - ("EPS_STATUS", 25), - ("BRAKE_MODULE", 40), - ("WHEEL_SPEEDS", 80), - ("STEER_ANGLE_SENSOR", 80), - ("PCM_CRUISE", 33), - ("PCM_CRUISE_SM", 1), - ("STEER_TORQUE_SENSOR", 50), - ] - - if CP.carFingerprint != CAR.TOYOTA_MIRAI: - messages.append(("ENGINE_RPM", 42)) - - if CP.carFingerprint in UNSUPPORTED_DSU_CAR: - messages.append(("DSU_CRUISE", 5)) - messages.append(("PCM_CRUISE_ALT", 1)) - else: - messages.append(("PCM_CRUISE_2", 33)) - - if CP.enableBsm: - messages.append(("BSM", 1)) - - if CP.carFingerprint in RADAR_ACC_CAR and not CP.flags & ToyotaFlags.DISABLE_RADAR.value: - if not CP.flags & ToyotaFlags.SMART_DSU.value: - messages += [ - ("ACC_CONTROL", 33), - ] - messages += [ - ("PCS_HUD", 1), - ] - - if CP.carFingerprint not in (TSS2_CAR - RADAR_ACC_CAR) and not CP.enableDsu and not CP.flags & ToyotaFlags.DISABLE_RADAR.value: - messages += [ - ("PRE_COLLISION", 33), - ] - - if CP.flags & ToyotaFlags.SMART_DSU and not CP.flags & ToyotaFlags.RADAR_CAN_FILTER: - messages += [ - ("SDSU", 100), - ] - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, 0) - - @staticmethod - def get_cam_can_parser(CP): - messages = [] - - if CP.carFingerprint != CAR.TOYOTA_PRIUS_V: - messages += [ - ("LKAS_HUD", 1), - ] - - if CP.carFingerprint in (TSS2_CAR - RADAR_ACC_CAR): - messages += [ - ("PRE_COLLISION", 33), - ("ACC_CONTROL", 33), - ("PCS_HUD", 1), - ] - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, 2) diff --git a/car/toyota/fingerprints.py b/car/toyota/fingerprints.py deleted file mode 100644 index 0866a4d43c..0000000000 --- a/car/toyota/fingerprints.py +++ /dev/null @@ -1,1681 +0,0 @@ -from cereal import car -from openpilot.selfdrive.car.toyota.values import CAR - -Ecu = car.CarParams.Ecu - -FW_VERSIONS = { - CAR.TOYOTA_AVALON: { - (Ecu.abs, 0x7b0, None): [ - b'F152607060\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881510701300\x00\x00\x00\x00', - b'881510705100\x00\x00\x00\x00', - b'881510705200\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B41051\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x0230721100\x00\x00\x00\x00\x00\x00\x00\x00A0C01000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230721200\x00\x00\x00\x00\x00\x00\x00\x00A0C01000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702000\x00\x00\x00\x00', - b'8821F4702100\x00\x00\x00\x00', - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F0701100\x00\x00\x00\x00', - b'8646F0703000\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_AVALON_2019: { - (Ecu.abs, 0x7b0, None): [ - b'F152607110\x00\x00\x00\x00\x00\x00', - b'F152607140\x00\x00\x00\x00\x00\x00', - b'F152607171\x00\x00\x00\x00\x00\x00', - b'F152607180\x00\x00\x00\x00\x00\x00', - b'F152641040\x00\x00\x00\x00\x00\x00', - b'F152641050\x00\x00\x00\x00\x00\x00', - b'F152641060\x00\x00\x00\x00\x00\x00', - b'F152641061\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881510703200\x00\x00\x00\x00', - b'881510704200\x00\x00\x00\x00', - b'881514107100\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B07010\x00\x00\x00\x00\x00\x00', - b'8965B41070\x00\x00\x00\x00\x00\x00', - b'8965B41080\x00\x00\x00\x00\x00\x00', - b'8965B41090\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x700, None): [ - b'\x01896630725100\x00\x00\x00\x00', - b'\x01896630725200\x00\x00\x00\x00', - b'\x01896630725300\x00\x00\x00\x00', - b'\x01896630725400\x00\x00\x00\x00', - b'\x01896630735100\x00\x00\x00\x00', - b'\x01896630738000\x00\x00\x00\x00', - b'\x02896630724000\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', - b'\x02896630728000\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', - b'\x02896630734000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', - b'\x02896630737000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F0702100\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_AVALON_TSS2: { - (Ecu.abs, 0x7b0, None): [ - b'\x01F152607240\x00\x00\x00\x00\x00\x00', - b'\x01F152607250\x00\x00\x00\x00\x00\x00', - b'\x01F152607280\x00\x00\x00\x00\x00\x00', - b'F152641080\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B41110\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x700, None): [ - b'\x018966306Q6000\x00\x00\x00\x00', - b'\x01896630742000\x00\x00\x00\x00', - b'\x01896630743000\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F6201200\x00\x00\x00\x00', - b'\x018821F6201300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F4104100\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', - b'\x028646F4104100\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_CAMRY: { - (Ecu.engine, 0x700, None): [ - b'\x018966306L3100\x00\x00\x00\x00', - b'\x018966306L4200\x00\x00\x00\x00', - b'\x018966306L5200\x00\x00\x00\x00', - b'\x018966306L9000\x00\x00\x00\x00', - b'\x018966306P8000\x00\x00\x00\x00', - b'\x018966306Q3100\x00\x00\x00\x00', - b'\x018966306Q4000\x00\x00\x00\x00', - b'\x018966306Q4100\x00\x00\x00\x00', - b'\x018966306Q4200\x00\x00\x00\x00', - b'\x018966306Q6000\x00\x00\x00\x00', - b'\x018966333N1100\x00\x00\x00\x00', - b'\x018966333N4300\x00\x00\x00\x00', - b'\x018966333P3100\x00\x00\x00\x00', - b'\x018966333P3200\x00\x00\x00\x00', - b'\x018966333P4200\x00\x00\x00\x00', - b'\x018966333P4300\x00\x00\x00\x00', - b'\x018966333P4400\x00\x00\x00\x00', - b'\x018966333P4500\x00\x00\x00\x00', - b'\x018966333P4700\x00\x00\x00\x00', - b'\x018966333P4900\x00\x00\x00\x00', - b'\x018966333Q6000\x00\x00\x00\x00', - b'\x018966333Q6200\x00\x00\x00\x00', - b'\x018966333Q6300\x00\x00\x00\x00', - b'\x018966333Q6500\x00\x00\x00\x00', - b'\x018966333Q9200\x00\x00\x00\x00', - b'\x018966333W6000\x00\x00\x00\x00', - b'\x018966333X0000\x00\x00\x00\x00', - b'\x018966333X4000\x00\x00\x00\x00', - b'\x01896633T16000\x00\x00\x00\x00', - b'\x028966306B2100\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', - b'\x028966306B2300\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', - b'\x028966306B2500\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', - b'\x028966306N8100\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', - b'\x028966306N8200\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', - b'\x028966306N8300\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', - b'\x028966306N8400\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', - b'\x028966306R5000\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', - b'\x028966306R5000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', - b'\x028966306R6000\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', - b'\x028966306R6000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', - b'\x028966306S0000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', - b'\x028966306S0100\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', - b'\x028966306S1100\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x02333P1100\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'8821F0601200 ', - b'8821F0601300 ', - b'8821F0601400 ', - b'8821F0601500 ', - b'8821F0602000 ', - b'8821F0603300 ', - b'8821F0603400 ', - b'8821F0604000 ', - b'8821F0604100 ', - b'8821F0604200 ', - b'8821F0605200 ', - b'8821F0606200 ', - b'8821F0607200 ', - b'8821F0608000 ', - b'8821F0608200 ', - b'8821F0609000 ', - b'8821F0609100 ', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152606210\x00\x00\x00\x00\x00\x00', - b'F152606230\x00\x00\x00\x00\x00\x00', - b'F152606270\x00\x00\x00\x00\x00\x00', - b'F152606290\x00\x00\x00\x00\x00\x00', - b'F152606410\x00\x00\x00\x00\x00\x00', - b'F152633214\x00\x00\x00\x00\x00\x00', - b'F152633540\x00\x00\x00\x00\x00\x00', - b'F152633660\x00\x00\x00\x00\x00\x00', - b'F152633712\x00\x00\x00\x00\x00\x00', - b'F152633713\x00\x00\x00\x00\x00\x00', - b'F152633A10\x00\x00\x00\x00\x00\x00', - b'F152633A20\x00\x00\x00\x00\x00\x00', - b'F152633B51\x00\x00\x00\x00\x00\x00', - b'F152633B60\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B33540\x00\x00\x00\x00\x00\x00', - b'8965B33542\x00\x00\x00\x00\x00\x00', - b'8965B33550\x00\x00\x00\x00\x00\x00', - b'8965B33551\x00\x00\x00\x00\x00\x00', - b'8965B33580\x00\x00\x00\x00\x00\x00', - b'8965B33581\x00\x00\x00\x00\x00\x00', - b'8965B33611\x00\x00\x00\x00\x00\x00', - b'8965B33621\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F0601200 ', - b'8821F0601300 ', - b'8821F0601400 ', - b'8821F0601500 ', - b'8821F0602000 ', - b'8821F0603300 ', - b'8821F0603400 ', - b'8821F0604000 ', - b'8821F0604100 ', - b'8821F0604200 ', - b'8821F0605200 ', - b'8821F0606200 ', - b'8821F0607200 ', - b'8821F0608000 ', - b'8821F0608200 ', - b'8821F0609000 ', - b'8821F0609100 ', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F0601200 ', - b'8646F0601300 ', - b'8646F0601400 ', - b'8646F0603400 ', - b'8646F0603500 ', - b'8646F0604000 ', - b'8646F0604100 ', - b'8646F0605000 ', - b'8646F0606000 ', - b'8646F0606100 ', - b'8646F0607000 ', - b'8646F0607100 ', - ], - }, - CAR.TOYOTA_CAMRY_TSS2: { - (Ecu.eps, 0x7a1, None): [ - b'8965B33630\x00\x00\x00\x00\x00\x00', - b'8965B33640\x00\x00\x00\x00\x00\x00', - b'8965B33650\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'\x01F152606370\x00\x00\x00\x00\x00\x00', - b'\x01F152606390\x00\x00\x00\x00\x00\x00', - b'\x01F152606400\x00\x00\x00\x00\x00\x00', - b'\x01F152606431\x00\x00\x00\x00\x00\x00', - b'F152633310\x00\x00\x00\x00\x00\x00', - b'F152633D00\x00\x00\x00\x00\x00\x00', - b'F152633D60\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x700, None): [ - b'\x018966306Q5000\x00\x00\x00\x00', - b'\x018966306Q6000\x00\x00\x00\x00', - b'\x018966306Q7000\x00\x00\x00\x00', - b'\x018966306Q9000\x00\x00\x00\x00', - b'\x018966306R3000\x00\x00\x00\x00', - b'\x018966306R8000\x00\x00\x00\x00', - b'\x018966306T0000\x00\x00\x00\x00', - b'\x018966306T3100\x00\x00\x00\x00', - b'\x018966306T3200\x00\x00\x00\x00', - b'\x018966306T4000\x00\x00\x00\x00', - b'\x018966306T4100\x00\x00\x00\x00', - b'\x018966306V1000\x00\x00\x00\x00', - b'\x01896633T20000\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F6201200\x00\x00\x00\x00', - b'\x018821F6201300\x00\x00\x00\x00', - b'\x018821F6201400\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F0602100\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', - b'\x028646F0602200\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', - b'\x028646F0602300\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', - b'\x028646F3305200\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', - b'\x028646F3305200\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', - b'\x028646F3305300\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', - b'\x028646F3305300\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', - b'\x028646F3305500\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_CHR: { - (Ecu.engine, 0x700, None): [ - b'\x01896631017100\x00\x00\x00\x00', - b'\x01896631017200\x00\x00\x00\x00', - b'\x01896631021100\x00\x00\x00\x00', - b'\x0189663F413100\x00\x00\x00\x00', - b'\x0189663F414100\x00\x00\x00\x00', - b'\x0189663F438000\x00\x00\x00\x00', - b'\x02896631013200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x0289663F405000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x0289663F405100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x0289663F418000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x0289663F423000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x0289663F431000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'8821F0W01000 ', - b'8821F0W01100 ', - b'8821FF401600 ', - b'8821FF402300 ', - b'8821FF402400 ', - b'8821FF404000 ', - b'8821FF404100 ', - b'8821FF405000 ', - b'8821FF405100 ', - b'8821FF406000 ', - b'8821FF407100 ', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152610012\x00\x00\x00\x00\x00\x00', - b'F152610013\x00\x00\x00\x00\x00\x00', - b'F152610014\x00\x00\x00\x00\x00\x00', - b'F152610020\x00\x00\x00\x00\x00\x00', - b'F152610040\x00\x00\x00\x00\x00\x00', - b'F152610153\x00\x00\x00\x00\x00\x00', - b'F152610190\x00\x00\x00\x00\x00\x00', - b'F152610200\x00\x00\x00\x00\x00\x00', - b'F152610210\x00\x00\x00\x00\x00\x00', - b'F152610220\x00\x00\x00\x00\x00\x00', - b'F152610230\x00\x00\x00\x00\x00\x00', - b'F1526F4034\x00\x00\x00\x00\x00\x00', - b'F1526F4044\x00\x00\x00\x00\x00\x00', - b'F1526F4073\x00\x00\x00\x00\x00\x00', - b'F1526F4121\x00\x00\x00\x00\x00\x00', - b'F1526F4122\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B10011\x00\x00\x00\x00\x00\x00', - b'8965B10020\x00\x00\x00\x00\x00\x00', - b'8965B10040\x00\x00\x00\x00\x00\x00', - b'8965B10050\x00\x00\x00\x00\x00\x00', - b'8965B10070\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x0331024000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203202\x00\x00\x00\x00', - b'\x0331024000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', - b'\x0331036000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', - b'\x033F401100\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203102\x00\x00\x00\x00', - b'\x033F401200\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203202\x00\x00\x00\x00', - b'\x033F424000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203202\x00\x00\x00\x00', - b'\x033F424000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F0W01000 ', - b'8821F0W01100 ', - b'8821FF401600 ', - b'8821FF402300 ', - b'8821FF402400 ', - b'8821FF404000 ', - b'8821FF404100 ', - b'8821FF405000 ', - b'8821FF405100 ', - b'8821FF406000 ', - b'8821FF407100 ', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646FF401700 ', - b'8646FF401800 ', - b'8646FF402100 ', - b'8646FF404000 ', - b'8646FF406000 ', - b'8646FF407000 ', - b'8646FF407100 ', - ], - }, - CAR.TOYOTA_CHR_TSS2: { - (Ecu.abs, 0x7b0, None): [ - b'F152610041\x00\x00\x00\x00\x00\x00', - b'F152610260\x00\x00\x00\x00\x00\x00', - b'F1526F4270\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B10091\x00\x00\x00\x00\x00\x00', - b'8965B10092\x00\x00\x00\x00\x00\x00', - b'8965B10110\x00\x00\x00\x00\x00\x00', - b'8965B10111\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x700, None): [ - b'\x0189663F438000\x00\x00\x00\x00', - b'\x0189663F459000\x00\x00\x00\x00', - b'\x02896631025000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x0289663F453000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x0331014000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821FF410200\x00\x00\x00\x00', - b'\x018821FF410300\x00\x00\x00\x00', - b'\x018821FF410400\x00\x00\x00\x00', - b'\x018821FF410500\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646FF410200\x00\x00\x00\x008646GF408200\x00\x00\x00\x00', - b'\x028646FF411100\x00\x00\x00\x008646GF409000\x00\x00\x00\x00', - b'\x028646FF413100\x00\x00\x00\x008646GF411100\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_COROLLA: { - (Ecu.engine, 0x7e0, None): [ - b'\x0230ZC2000\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230ZC2100\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230ZC2200\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230ZC2300\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230ZC3000\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230ZC3100\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230ZC3200\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230ZC3300\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0330ZC1200\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00895231203202\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881510201100\x00\x00\x00\x00', - b'881510201200\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152602190\x00\x00\x00\x00\x00\x00', - b'F152602191\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B02181\x00\x00\x00\x00\x00\x00', - b'8965B02191\x00\x00\x00\x00\x00\x00', - b'8965B48150\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702100\x00\x00\x00\x00', - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F0201101\x00\x00\x00\x00', - b'8646F0201200\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_COROLLA_TSS2: { - (Ecu.engine, 0x700, None): [ - b'\x01896630A22000\x00\x00\x00\x00', - b'\x01896630ZG2000\x00\x00\x00\x00', - b'\x01896630ZG5000\x00\x00\x00\x00', - b'\x01896630ZG5100\x00\x00\x00\x00', - b'\x01896630ZG5200\x00\x00\x00\x00', - b'\x01896630ZG5300\x00\x00\x00\x00', - b'\x01896630ZJ1000\x00\x00\x00\x00', - b'\x01896630ZP1000\x00\x00\x00\x00', - b'\x01896630ZP2000\x00\x00\x00\x00', - b'\x01896630ZQ5000\x00\x00\x00\x00', - b'\x01896630ZU8000\x00\x00\x00\x00', - b'\x01896630ZU9000\x00\x00\x00\x00', - b'\x01896630ZX4000\x00\x00\x00\x00', - b'\x018966312L8000\x00\x00\x00\x00', - b'\x018966312M0000\x00\x00\x00\x00', - b'\x018966312M9000\x00\x00\x00\x00', - b'\x018966312P9000\x00\x00\x00\x00', - b'\x018966312P9100\x00\x00\x00\x00', - b'\x018966312P9200\x00\x00\x00\x00', - b'\x018966312P9300\x00\x00\x00\x00', - b'\x018966312Q2300\x00\x00\x00\x00', - b'\x018966312Q8000\x00\x00\x00\x00', - b'\x018966312R0000\x00\x00\x00\x00', - b'\x018966312R0100\x00\x00\x00\x00', - b'\x018966312R0200\x00\x00\x00\x00', - b'\x018966312R1000\x00\x00\x00\x00', - b'\x018966312R1100\x00\x00\x00\x00', - b'\x018966312R3100\x00\x00\x00\x00', - b'\x018966312S5000\x00\x00\x00\x00', - b'\x018966312S7000\x00\x00\x00\x00', - b'\x018966312W3000\x00\x00\x00\x00', - b'\x018966312W9000\x00\x00\x00\x00', - b'\x01896637621000\x00\x00\x00\x00', - b'\x01896637623000\x00\x00\x00\x00', - b'\x01896637624000\x00\x00\x00\x00', - b'\x01896637626000\x00\x00\x00\x00', - b'\x01896637639000\x00\x00\x00\x00', - b'\x01896637643000\x00\x00\x00\x00', - b'\x01896637644000\x00\x00\x00\x00', - b'\x01896637648000\x00\x00\x00\x00', - b'\x02896630A07000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896630A21000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896630ZJ5000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896630ZK8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896630ZN8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896630ZQ3000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896630ZR2000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896630ZT8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896630ZT9000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896630ZZ0000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x028966312K6000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x028966312L0000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x028966312Q3000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x028966312Q3100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x028966312Q4000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x038966312L7000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF1205001\x00\x00\x00\x00', - b'\x038966312N1000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00', - b'\x038966312T3000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF1205001\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x0230A10000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230A11000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230ZN4000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230ZN5000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02312K4000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02312U5000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x03312K7000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00', - b'\x03312M3000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00', - b'\x03312N6000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203202\x00\x00\x00\x00', - b'\x03312N6000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', - b'\x03312N6000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00', - b'\x03312N6100\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', - b'\x03312N6100\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00', - b'\x03312N6200\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203202\x00\x00\x00\x00', - b'\x03312N6200\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', - b'\x03312N6200\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'\x018965B12350\x00\x00\x00\x00\x00\x00', - b'\x018965B12470\x00\x00\x00\x00\x00\x00', - b'\x018965B12490\x00\x00\x00\x00\x00\x00', - b'\x018965B12500\x00\x00\x00\x00\x00\x00', - b'\x018965B12510\x00\x00\x00\x00\x00\x00', - b'\x018965B12520\x00\x00\x00\x00\x00\x00', - b'\x018965B12530\x00\x00\x00\x00\x00\x00', - b'\x018965B1254000\x00\x00\x00\x00', - b'\x018965B1255000\x00\x00\x00\x00', - b'\x018965B1256000\x00\x00\x00\x00', - b'8965B12361\x00\x00\x00\x00\x00\x00', - b'8965B12451\x00\x00\x00\x00\x00\x00', - b'8965B16011\x00\x00\x00\x00\x00\x00', - b'8965B16101\x00\x00\x00\x00\x00\x00', - b'8965B16170\x00\x00\x00\x00\x00\x00', - b'8965B76012\x00\x00\x00\x00\x00\x00', - b'8965B76050\x00\x00\x00\x00\x00\x00', - b'8965B76091\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'\x01F152602280\x00\x00\x00\x00\x00\x00', - b'\x01F152602281\x00\x00\x00\x00\x00\x00', - b'\x01F152602470\x00\x00\x00\x00\x00\x00', - b'\x01F152602560\x00\x00\x00\x00\x00\x00', - b'\x01F152602590\x00\x00\x00\x00\x00\x00', - b'\x01F152602650\x00\x00\x00\x00\x00\x00', - b'\x01F15260A010\x00\x00\x00\x00\x00\x00', - b'\x01F15260A050\x00\x00\x00\x00\x00\x00', - b'\x01F15260A070\x00\x00\x00\x00\x00\x00', - b'\x01F152612641\x00\x00\x00\x00\x00\x00', - b'\x01F152612651\x00\x00\x00\x00\x00\x00', - b'\x01F152612862\x00\x00\x00\x00\x00\x00', - b'\x01F152612B10\x00\x00\x00\x00\x00\x00', - b'\x01F152612B51\x00\x00\x00\x00\x00\x00', - b'\x01F152612B60\x00\x00\x00\x00\x00\x00', - b'\x01F152612B61\x00\x00\x00\x00\x00\x00', - b'\x01F152612B62\x00\x00\x00\x00\x00\x00', - b'\x01F152612B70\x00\x00\x00\x00\x00\x00', - b'\x01F152612B71\x00\x00\x00\x00\x00\x00', - b'\x01F152612B81\x00\x00\x00\x00\x00\x00', - b'\x01F152612B90\x00\x00\x00\x00\x00\x00', - b'\x01F152612B91\x00\x00\x00\x00\x00\x00', - b'\x01F152612C00\x00\x00\x00\x00\x00\x00', - b'\x01F152676250\x00\x00\x00\x00\x00\x00', - b'F152612590\x00\x00\x00\x00\x00\x00', - b'F152612691\x00\x00\x00\x00\x00\x00', - b'F152612692\x00\x00\x00\x00\x00\x00', - b'F152612700\x00\x00\x00\x00\x00\x00', - b'F152612710\x00\x00\x00\x00\x00\x00', - b'F152612790\x00\x00\x00\x00\x00\x00', - b'F152612800\x00\x00\x00\x00\x00\x00', - b'F152612820\x00\x00\x00\x00\x00\x00', - b'F152612840\x00\x00\x00\x00\x00\x00', - b'F152612842\x00\x00\x00\x00\x00\x00', - b'F152612890\x00\x00\x00\x00\x00\x00', - b'F152612A00\x00\x00\x00\x00\x00\x00', - b'F152612A10\x00\x00\x00\x00\x00\x00', - b'F152612D00\x00\x00\x00\x00\x00\x00', - b'F152616011\x00\x00\x00\x00\x00\x00', - b'F152616030\x00\x00\x00\x00\x00\x00', - b'F152616060\x00\x00\x00\x00\x00\x00', - b'F152642540\x00\x00\x00\x00\x00\x00', - b'F152676293\x00\x00\x00\x00\x00\x00', - b'F152676303\x00\x00\x00\x00\x00\x00', - b'F152676304\x00\x00\x00\x00\x00\x00', - b'F152676371\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F3301100\x00\x00\x00\x00', - b'\x018821F3301200\x00\x00\x00\x00', - b'\x018821F3301300\x00\x00\x00\x00', - b'\x018821F3301400\x00\x00\x00\x00', - b'\x018821F6201400\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F12010C0\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', - b'\x028646F12010D0\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', - b'\x028646F1201100\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', - b'\x028646F1201200\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', - b'\x028646F1201300\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - b'\x028646F1201400\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', - b'\x028646F1202000\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', - b'\x028646F1202100\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - b'\x028646F1202200\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', - b'\x028646F1206000\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', - b'\x028646F1601100\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - b'\x028646F1601200\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - b'\x028646F1601300\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - b'\x028646F4203400\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', - b'\x028646F76020C0\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', - b'\x028646F7603100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', - b'\x028646F7603200\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - b'\x028646F7603300\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - b'\x028646F7605100\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_HIGHLANDER: { - (Ecu.engine, 0x700, None): [ - b'\x01896630E09000\x00\x00\x00\x00', - b'\x01896630E43000\x00\x00\x00\x00', - b'\x01896630E43100\x00\x00\x00\x00', - b'\x01896630E43200\x00\x00\x00\x00', - b'\x01896630E44200\x00\x00\x00\x00', - b'\x01896630E44400\x00\x00\x00\x00', - b'\x01896630E45000\x00\x00\x00\x00', - b'\x01896630E45100\x00\x00\x00\x00', - b'\x01896630E45200\x00\x00\x00\x00', - b'\x01896630E46000\x00\x00\x00\x00', - b'\x01896630E46200\x00\x00\x00\x00', - b'\x01896630E74000\x00\x00\x00\x00', - b'\x01896630E75000\x00\x00\x00\x00', - b'\x01896630E76000\x00\x00\x00\x00', - b'\x01896630E77000\x00\x00\x00\x00', - b'\x01896630E83000\x00\x00\x00\x00', - b'\x01896630E84000\x00\x00\x00\x00', - b'\x01896630E85000\x00\x00\x00\x00', - b'\x01896630E86000\x00\x00\x00\x00', - b'\x01896630E88000\x00\x00\x00\x00', - b'\x01896630EA0000\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x0230E40000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230E40100\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230E51000\x00\x00\x00\x00\x00\x00\x00\x0050E17000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230EA2000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0230EA2100\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B48140\x00\x00\x00\x00\x00\x00', - b'8965B48150\x00\x00\x00\x00\x00\x00', - b'8965B48160\x00\x00\x00\x00\x00\x00', - b'8965B48210\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F15260E011\x00\x00\x00\x00\x00\x00', - b'F152648541\x00\x00\x00\x00\x00\x00', - b'F152648542\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881510E01100\x00\x00\x00\x00', - b'881510E01200\x00\x00\x00\x00', - b'881510E02200\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702100\x00\x00\x00\x00', - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F0E01200\x00\x00\x00\x00', - b'8646F0E01300\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_HIGHLANDER_TSS2: { - (Ecu.eps, 0x7a1, None): [ - b'8965B48241\x00\x00\x00\x00\x00\x00', - b'8965B48310\x00\x00\x00\x00\x00\x00', - b'8965B48320\x00\x00\x00\x00\x00\x00', - b'8965B48400\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'\x01F15260E051\x00\x00\x00\x00\x00\x00', - b'\x01F15260E05300\x00\x00\x00\x00', - b'\x01F15260E061\x00\x00\x00\x00\x00\x00', - b'\x01F15260E110\x00\x00\x00\x00\x00\x00', - b'\x01F15260E170\x00\x00\x00\x00\x00\x00', - b'\x01F15264872300\x00\x00\x00\x00', - b'\x01F15264872400\x00\x00\x00\x00', - b'\x01F15264872500\x00\x00\x00\x00', - b'\x01F15264872600\x00\x00\x00\x00', - b'\x01F15264872700\x00\x00\x00\x00', - b'\x01F15264873500\x00\x00\x00\x00', - b'\x01F152648C6300\x00\x00\x00\x00', - b'\x01F152648J4000\x00\x00\x00\x00', - b'\x01F152648J5000\x00\x00\x00\x00', - b'\x01F152648J6000\x00\x00\x00\x00', - b'\x01F152648J7000\x00\x00\x00\x00', - b'\x01F152648L5000\x00\x00\x00\x00', - ], - (Ecu.engine, 0x700, None): [ - b'\x01896630E62100\x00\x00\x00\x00', - b'\x01896630E62200\x00\x00\x00\x00', - b'\x01896630E64100\x00\x00\x00\x00', - b'\x01896630E64200\x00\x00\x00\x00', - b'\x01896630E64400\x00\x00\x00\x00', - b'\x01896630E67000\x00\x00\x00\x00', - b'\x01896630EA1000\x00\x00\x00\x00', - b'\x01896630EB1000\x00\x00\x00\x00', - b'\x01896630EB1100\x00\x00\x00\x00', - b'\x01896630EB1200\x00\x00\x00\x00', - b'\x01896630EB1300\x00\x00\x00\x00', - b'\x01896630EB2000\x00\x00\x00\x00', - b'\x01896630EB2100\x00\x00\x00\x00', - b'\x01896630EB2200\x00\x00\x00\x00', - b'\x01896630EC4000\x00\x00\x00\x00', - b'\x01896630ED9000\x00\x00\x00\x00', - b'\x01896630ED9100\x00\x00\x00\x00', - b'\x01896630EE1000\x00\x00\x00\x00', - b'\x01896630EE1100\x00\x00\x00\x00', - b'\x01896630EE4000\x00\x00\x00\x00', - b'\x01896630EE4100\x00\x00\x00\x00', - b'\x01896630EE5000\x00\x00\x00\x00', - b'\x01896630EE6000\x00\x00\x00\x00', - b'\x01896630EE7000\x00\x00\x00\x00', - b'\x01896630EF8000\x00\x00\x00\x00', - b'\x01896630EG3000\x00\x00\x00\x00', - b'\x01896630EG5000\x00\x00\x00\x00', - b'\x02896630E66000\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', - b'\x02896630E66100\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', - b'\x02896630EB3000\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', - b'\x02896630EB3100\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F3301400\x00\x00\x00\x00', - b'\x018821F6201200\x00\x00\x00\x00', - b'\x018821F6201300\x00\x00\x00\x00', - b'\x018821F6201400\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F0E02100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', - b'\x028646F4803000\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', - b'\x028646F4803000\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', - b'\x028646F4803200\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', - ], - }, - CAR.LEXUS_IS: { - (Ecu.engine, 0x700, None): [ - b'\x018966353M7000\x00\x00\x00\x00', - b'\x018966353M7100\x00\x00\x00\x00', - b'\x018966353Q2000\x00\x00\x00\x00', - b'\x018966353Q2100\x00\x00\x00\x00', - b'\x018966353Q2300\x00\x00\x00\x00', - b'\x018966353Q4000\x00\x00\x00\x00', - b'\x018966353R1100\x00\x00\x00\x00', - b'\x018966353R7100\x00\x00\x00\x00', - b'\x018966353R8000\x00\x00\x00\x00', - b'\x018966353R8100\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x0232480000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02353P7000\x00\x00\x00\x00\x00\x00\x00\x00530J5000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02353P9000\x00\x00\x00\x00\x00\x00\x00\x00553C1000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152653300\x00\x00\x00\x00\x00\x00', - b'F152653301\x00\x00\x00\x00\x00\x00', - b'F152653310\x00\x00\x00\x00\x00\x00', - b'F152653330\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881515306200\x00\x00\x00\x00', - b'881515306400\x00\x00\x00\x00', - b'881515306500\x00\x00\x00\x00', - b'881515307400\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B53270\x00\x00\x00\x00\x00\x00', - b'8965B53271\x00\x00\x00\x00\x00\x00', - b'8965B53280\x00\x00\x00\x00\x00\x00', - b'8965B53281\x00\x00\x00\x00\x00\x00', - b'8965B53311\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702100\x00\x00\x00\x00', - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F5301101\x00\x00\x00\x00', - b'8646F5301200\x00\x00\x00\x00', - b'8646F5301300\x00\x00\x00\x00', - b'8646F5301400\x00\x00\x00\x00', - ], - }, - CAR.LEXUS_IS_TSS2: { - (Ecu.engine, 0x700, None): [ - b'\x018966353S1000\x00\x00\x00\x00', - b'\x018966353S2000\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x02353U0000\x00\x00\x00\x00\x00\x00\x00\x0052422000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'\x01F15265337200\x00\x00\x00\x00', - b'\x01F15265342000\x00\x00\x00\x00', - b'\x01F15265343000\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B53450\x00\x00\x00\x00\x00\x00', - b'8965B53800\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F6201200\x00\x00\x00\x00', - b'\x018821F6201300\x00\x00\x00\x00', - b'\x018821F6201400\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F5303300\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', - b'\x028646F5303400\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_PRIUS: { - (Ecu.engine, 0x700, None): [ - b'\x02896634761000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634761100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634761200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634762000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634762100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634763000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634763100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634765000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634765100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634769000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634769100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634769200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634770000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634770100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634774000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634774100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634774200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634782000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x02896634784000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x028966347A0000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x028966347A5000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x028966347A8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x028966347B0000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x03896634759100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', - b'\x03896634759200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', - b'\x03896634759200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701004\x00\x00\x00\x00', - b'\x03896634759300\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', - b'\x03896634759300\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701004\x00\x00\x00\x00', - b'\x03896634760000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701002\x00\x00\x00\x00', - b'\x03896634760000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', - b'\x03896634760000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701004\x00\x00\x00\x00', - b'\x03896634760100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', - b'\x03896634760200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', - b'\x03896634760200\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701004\x00\x00\x00\x00', - b'\x03896634760300\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701004\x00\x00\x00\x00', - b'\x03896634768000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4703001\x00\x00\x00\x00', - b'\x03896634768000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4703002\x00\x00\x00\x00', - b'\x03896634768100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4703002\x00\x00\x00\x00', - b'\x03896634785000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4705001\x00\x00\x00\x00', - b'\x03896634785000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710001\x00\x00\x00\x00', - b'\x03896634786000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4705001\x00\x00\x00\x00', - b'\x03896634786000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710001\x00\x00\x00\x00', - b'\x03896634789000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4703002\x00\x00\x00\x00', - b'\x038966347A3000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4701003\x00\x00\x00\x00', - b'\x038966347A3000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4707001\x00\x00\x00\x00', - b'\x038966347B6000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710001\x00\x00\x00\x00', - b'\x038966347B7000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710001\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B47021\x00\x00\x00\x00\x00\x00', - b'8965B47022\x00\x00\x00\x00\x00\x00', - b'8965B47023\x00\x00\x00\x00\x00\x00', - b'8965B47050\x00\x00\x00\x00\x00\x00', - b'8965B47060\x00\x00\x00\x00\x00\x00', - b'8965B47070\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152647290\x00\x00\x00\x00\x00\x00', - b'F152647300\x00\x00\x00\x00\x00\x00', - b'F152647310\x00\x00\x00\x00\x00\x00', - b'F152647414\x00\x00\x00\x00\x00\x00', - b'F152647415\x00\x00\x00\x00\x00\x00', - b'F152647416\x00\x00\x00\x00\x00\x00', - b'F152647417\x00\x00\x00\x00\x00\x00', - b'F152647470\x00\x00\x00\x00\x00\x00', - b'F152647490\x00\x00\x00\x00\x00\x00', - b'F152647682\x00\x00\x00\x00\x00\x00', - b'F152647683\x00\x00\x00\x00\x00\x00', - b'F152647684\x00\x00\x00\x00\x00\x00', - b'F152647862\x00\x00\x00\x00\x00\x00', - b'F152647863\x00\x00\x00\x00\x00\x00', - b'F152647864\x00\x00\x00\x00\x00\x00', - b'F152647865\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881514702300\x00\x00\x00\x00', - b'881514702400\x00\x00\x00\x00', - b'881514703100\x00\x00\x00\x00', - b'881514704100\x00\x00\x00\x00', - b'881514706000\x00\x00\x00\x00', - b'881514706100\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702000\x00\x00\x00\x00', - b'8821F4702100\x00\x00\x00\x00', - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F4701300\x00\x00\x00\x00', - b'8646F4702001\x00\x00\x00\x00', - b'8646F4702100\x00\x00\x00\x00', - b'8646F4702200\x00\x00\x00\x00', - b'8646F4705000\x00\x00\x00\x00', - b'8646F4705200\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_PRIUS_V: { - (Ecu.abs, 0x7b0, None): [ - b'F152647280\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x0234781000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881514705100\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F4703300\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_RAV4: { - (Ecu.engine, 0x7e0, None): [ - b'\x02342Q1000\x00\x00\x00\x00\x00\x00\x00\x0054212000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02342Q1100\x00\x00\x00\x00\x00\x00\x00\x0054212000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02342Q1200\x00\x00\x00\x00\x00\x00\x00\x0054212000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02342Q1300\x00\x00\x00\x00\x00\x00\x00\x0054212000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02342Q2000\x00\x00\x00\x00\x00\x00\x00\x0054213000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02342Q2100\x00\x00\x00\x00\x00\x00\x00\x0054213000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02342Q2200\x00\x00\x00\x00\x00\x00\x00\x0054213000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02342Q4000\x00\x00\x00\x00\x00\x00\x00\x0054215000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B42063\x00\x00\x00\x00\x00\x00', - b'8965B42073\x00\x00\x00\x00\x00\x00', - b'8965B42082\x00\x00\x00\x00\x00\x00', - b'8965B42083\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F15260R102\x00\x00\x00\x00\x00\x00', - b'F15260R103\x00\x00\x00\x00\x00\x00', - b'F152642492\x00\x00\x00\x00\x00\x00', - b'F152642493\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881514201200\x00\x00\x00\x00', - b'881514201300\x00\x00\x00\x00', - b'881514201400\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702000\x00\x00\x00\x00', - b'8821F4702100\x00\x00\x00\x00', - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F4201100\x00\x00\x00\x00', - b'8646F4201200\x00\x00\x00\x00', - b'8646F4202001\x00\x00\x00\x00', - b'8646F4202100\x00\x00\x00\x00', - b'8646F4204000\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_RAV4H: { - (Ecu.engine, 0x7e0, None): [ - b'\x02342N9000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02342N9100\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02342P0000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B42102\x00\x00\x00\x00\x00\x00', - b'8965B42103\x00\x00\x00\x00\x00\x00', - b'8965B42112\x00\x00\x00\x00\x00\x00', - b'8965B42162\x00\x00\x00\x00\x00\x00', - b'8965B42163\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152642090\x00\x00\x00\x00\x00\x00', - b'F152642110\x00\x00\x00\x00\x00\x00', - b'F152642120\x00\x00\x00\x00\x00\x00', - b'F152642400\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881514202200\x00\x00\x00\x00', - b'881514202300\x00\x00\x00\x00', - b'881514202400\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702000\x00\x00\x00\x00', - b'8821F4702100\x00\x00\x00\x00', - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F4201100\x00\x00\x00\x00', - b'8646F4201200\x00\x00\x00\x00', - b'8646F4202001\x00\x00\x00\x00', - b'8646F4202100\x00\x00\x00\x00', - b'8646F4204000\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_RAV4_TSS2: { - (Ecu.engine, 0x700, None): [ - b'\x01896630R58000\x00\x00\x00\x00', - b'\x01896630R58100\x00\x00\x00\x00', - b'\x018966342E2000\x00\x00\x00\x00', - b'\x018966342M5000\x00\x00\x00\x00', - b'\x018966342M8000\x00\x00\x00\x00', - b'\x018966342S9000\x00\x00\x00\x00', - b'\x018966342T1000\x00\x00\x00\x00', - b'\x018966342T6000\x00\x00\x00\x00', - b'\x018966342T9000\x00\x00\x00\x00', - b'\x018966342U4000\x00\x00\x00\x00', - b'\x018966342U4100\x00\x00\x00\x00', - b'\x018966342U5100\x00\x00\x00\x00', - b'\x018966342V0000\x00\x00\x00\x00', - b'\x018966342V3000\x00\x00\x00\x00', - b'\x018966342V3100\x00\x00\x00\x00', - b'\x018966342V3200\x00\x00\x00\x00', - b'\x018966342W5000\x00\x00\x00\x00', - b'\x018966342W7000\x00\x00\x00\x00', - b'\x018966342W8000\x00\x00\x00\x00', - b'\x018966342X5000\x00\x00\x00\x00', - b'\x018966342X6000\x00\x00\x00\x00', - b'\x01896634A05000\x00\x00\x00\x00', - b'\x01896634A15000\x00\x00\x00\x00', - b'\x01896634A19000\x00\x00\x00\x00', - b'\x01896634A19100\x00\x00\x00\x00', - b'\x01896634A20000\x00\x00\x00\x00', - b'\x01896634A20100\x00\x00\x00\x00', - b'\x01896634A22000\x00\x00\x00\x00', - b'\x01896634A22100\x00\x00\x00\x00', - b'\x01896634A25000\x00\x00\x00\x00', - b'\x01896634A30000\x00\x00\x00\x00', - b'\x01896634A44000\x00\x00\x00\x00', - b'\x01896634A45000\x00\x00\x00\x00', - b'\x01896634A46000\x00\x00\x00\x00', - b'\x028966342M7000\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', - b'\x028966342T0000\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', - b'\x028966342V1000\x00\x00\x00\x00897CF1202001\x00\x00\x00\x00', - b'\x028966342W4001\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00', - b'\x028966342Y8000\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', - b'\x028966342Z8000\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', - b'\x02896634A13000\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02896634A13001\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', - b'\x02896634A13101\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', - b'\x02896634A13201\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', - b'\x02896634A14001\x00\x00\x00\x00897CF0R01000\x00\x00\x00\x00', - b'\x02896634A14001\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00', - b'\x02896634A14001\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', - b'\x02896634A14101\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', - b'\x02896634A18000\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', - b'\x02896634A18100\x00\x00\x00\x00897CF1201001\x00\x00\x00\x00', - b'\x02896634A23000\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02896634A23001\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00', - b'\x02896634A23101\x00\x00\x00\x00897CF1203001\x00\x00\x00\x00', - b'\x02896634A43000\x00\x00\x00\x00897CF4201001\x00\x00\x00\x00', - b'\x02896634A47000\x00\x00\x00\x00897CF4201001\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'\x01F15260R210\x00\x00\x00\x00\x00\x00', - b'\x01F15260R220\x00\x00\x00\x00\x00\x00', - b'\x01F15260R290\x00\x00\x00\x00\x00\x00', - b'\x01F15260R292\x00\x00\x00\x00\x00\x00', - b'\x01F15260R300\x00\x00\x00\x00\x00\x00', - b'\x01F15260R302\x00\x00\x00\x00\x00\x00', - b'\x01F152642551\x00\x00\x00\x00\x00\x00', - b'\x01F152642561\x00\x00\x00\x00\x00\x00', - b'\x01F152642601\x00\x00\x00\x00\x00\x00', - b'\x01F152642700\x00\x00\x00\x00\x00\x00', - b'\x01F152642701\x00\x00\x00\x00\x00\x00', - b'\x01F152642710\x00\x00\x00\x00\x00\x00', - b'\x01F152642711\x00\x00\x00\x00\x00\x00', - b'\x01F152642750\x00\x00\x00\x00\x00\x00', - b'\x01F152642751\x00\x00\x00\x00\x00\x00', - b'F152642290\x00\x00\x00\x00\x00\x00', - b'F152642291\x00\x00\x00\x00\x00\x00', - b'F152642322\x00\x00\x00\x00\x00\x00', - b'F152642330\x00\x00\x00\x00\x00\x00', - b'F152642331\x00\x00\x00\x00\x00\x00', - b'F152642520\x00\x00\x00\x00\x00\x00', - b'F152642521\x00\x00\x00\x00\x00\x00', - b'F152642531\x00\x00\x00\x00\x00\x00', - b'F152642532\x00\x00\x00\x00\x00\x00', - b'F152642540\x00\x00\x00\x00\x00\x00', - b'F152642541\x00\x00\x00\x00\x00\x00', - b'F152642542\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'\x028965B0R01200\x00\x00\x00\x008965B0R02200\x00\x00\x00\x00', - b'\x028965B0R01300\x00\x00\x00\x008965B0R02300\x00\x00\x00\x00', - b'\x028965B0R01400\x00\x00\x00\x008965B0R02400\x00\x00\x00\x00', - b'8965B42170\x00\x00\x00\x00\x00\x00', - b'8965B42171\x00\x00\x00\x00\x00\x00', - b'8965B42180\x00\x00\x00\x00\x00\x00', - b'8965B42181\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F3301100\x00\x00\x00\x00', - b'\x018821F3301200\x00\x00\x00\x00', - b'\x018821F3301300\x00\x00\x00\x00', - b'\x018821F3301400\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F4203200\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', - b'\x028646F4203300\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', - b'\x028646F4203400\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', - b'\x028646F4203500\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', - b'\x028646F4203700\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - b'\x028646F4203800\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_RAV4_TSS2_2022: { - (Ecu.abs, 0x7b0, None): [ - b'\x01F15260R350\x00\x00\x00\x00\x00\x00', - b'\x01F15260R361\x00\x00\x00\x00\x00\x00', - b'\x01F15264283100\x00\x00\x00\x00', - b'\x01F15264283200\x00\x00\x00\x00', - b'\x01F15264286100\x00\x00\x00\x00', - b'\x01F15264286200\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'\x028965B0R01500\x00\x00\x00\x008965B0R02500\x00\x00\x00\x00', - b'8965B42172\x00\x00\x00\x00\x00\x00', - b'8965B42182\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x700, None): [ - b'\x01896634A02001\x00\x00\x00\x00', - b'\x01896634A03000\x00\x00\x00\x00', - b'\x01896634A08000\x00\x00\x00\x00', - b'\x01896634A61000\x00\x00\x00\x00', - b'\x01896634A62000\x00\x00\x00\x00', - b'\x01896634A62100\x00\x00\x00\x00', - b'\x01896634A63000\x00\x00\x00\x00', - b'\x01896634A88000\x00\x00\x00\x00', - b'\x01896634A89000\x00\x00\x00\x00', - b'\x01896634A89100\x00\x00\x00\x00', - b'\x01896634AA0000\x00\x00\x00\x00', - b'\x01896634AA0100\x00\x00\x00\x00', - b'\x01896634AA1000\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F0R01100\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F0R02100\x00\x00\x00\x008646G0R01100\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_RAV4_TSS2_2023: { - (Ecu.abs, 0x7b0, None): [ - b'\x01F15260R450\x00\x00\x00\x00\x00\x00', - b'\x01F15260R50000\x00\x00\x00\x00', - b'\x01F15260R51000\x00\x00\x00\x00', - b'\x01F15264283200\x00\x00\x00\x00', - b'\x01F15264283300\x00\x00\x00\x00', - b'\x01F152642F1000\x00\x00\x00\x00', - b'\x01F152642F8000\x00\x00\x00\x00', - b'\x01F152642F8100\x00\x00\x00\x00', - b'\x01F152642F9000\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'\x028965B0R11000\x00\x00\x00\x008965B0R12000\x00\x00\x00\x00', - b'8965B42371\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x700, None): [ - b'\x01896634A61000\x00\x00\x00\x00', - b'\x01896634A88100\x00\x00\x00\x00', - b'\x01896634A89100\x00\x00\x00\x00', - b'\x01896634AE1001\x00\x00\x00\x00', - b'\x01896634AF0000\x00\x00\x00\x00', - b'\x01896634AJ2000\x00\x00\x00\x00', - b'\x01896634AL5000\x00\x00\x00\x00', - b'\x01896634AL6000\x00\x00\x00\x00', - b'\x01896634AL8000\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F0R03100\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F0R05100\x00\x00\x00\x008646G0R02100\x00\x00\x00\x00', - b'\x028646F0R05200\x00\x00\x00\x008646G0R02200\x00\x00\x00\x00', - b'\x028646F0R11000\x00\x00\x00\x008646G0R04000\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_SIENNA: { - (Ecu.engine, 0x700, None): [ - b'\x01896630832100\x00\x00\x00\x00', - b'\x01896630832200\x00\x00\x00\x00', - b'\x01896630838000\x00\x00\x00\x00', - b'\x01896630838100\x00\x00\x00\x00', - b'\x01896630842000\x00\x00\x00\x00', - b'\x01896630843000\x00\x00\x00\x00', - b'\x01896630851000\x00\x00\x00\x00', - b'\x01896630851100\x00\x00\x00\x00', - b'\x01896630851200\x00\x00\x00\x00', - b'\x01896630852000\x00\x00\x00\x00', - b'\x01896630852100\x00\x00\x00\x00', - b'\x01896630859000\x00\x00\x00\x00', - b'\x01896630860000\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B45070\x00\x00\x00\x00\x00\x00', - b'8965B45080\x00\x00\x00\x00\x00\x00', - b'8965B45082\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152608130\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881510801100\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702100\x00\x00\x00\x00', - b'8821F4702200\x00\x00\x00\x00', - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F0801100\x00\x00\x00\x00', - ], - }, - CAR.LEXUS_CTH: { - (Ecu.dsu, 0x791, None): [ - b'881517601100\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152676144\x00\x00\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x0237635000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F7601100\x00\x00\x00\x00', - ], - }, - CAR.LEXUS_ES_TSS2: { - (Ecu.engine, 0x700, None): [ - b'\x018966306U6000\x00\x00\x00\x00', - b'\x018966333T5000\x00\x00\x00\x00', - b'\x018966333T5100\x00\x00\x00\x00', - b'\x018966333X6000\x00\x00\x00\x00', - b'\x01896633T07000\x00\x00\x00\x00', - b'\x01896633T38000\x00\x00\x00\x00', - b'\x01896633T58000\x00\x00\x00\x00', - b'\x028966333S8000\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', - b'\x028966333S8000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', - b'\x028966333T0100\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', - b'\x028966333V4000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', - b'\x028966333W1000\x00\x00\x00\x00897CF3305001\x00\x00\x00\x00', - b'\x02896633T09000\x00\x00\x00\x00897CF3307001\x00\x00\x00\x00', - b'\x02896633T10000\x00\x00\x00\x00897CF3307001\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'\x01F152606281\x00\x00\x00\x00\x00\x00', - b'\x01F152606340\x00\x00\x00\x00\x00\x00', - b'\x01F152606461\x00\x00\x00\x00\x00\x00', - b'\x01F15260646200\x00\x00\x00\x00', - b'F152633423\x00\x00\x00\x00\x00\x00', - b'F152633680\x00\x00\x00\x00\x00\x00', - b'F152633681\x00\x00\x00\x00\x00\x00', - b'F152633F50\x00\x00\x00\x00\x00\x00', - b'F152633F51\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B33252\x00\x00\x00\x00\x00\x00', - b'8965B33590\x00\x00\x00\x00\x00\x00', - b'8965B33690\x00\x00\x00\x00\x00\x00', - b'8965B33721\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F3301100\x00\x00\x00\x00', - b'\x018821F3301200\x00\x00\x00\x00', - b'\x018821F3301300\x00\x00\x00\x00', - b'\x018821F3301400\x00\x00\x00\x00', - b'\x018821F6201200\x00\x00\x00\x00', - b'\x018821F6201300\x00\x00\x00\x00', - b'\x018821F6201400\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F0610000\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', - b'\x028646F33030D0\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', - b'\x028646F3303100\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', - b'\x028646F3303200\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', - b'\x028646F3304100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', - b'\x028646F3304200\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - b'\x028646F3304300\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', - b'\x028646F3309100\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', - b'\x028646F3309100\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', - ], - }, - CAR.LEXUS_ES: { - (Ecu.engine, 0x7e0, None): [ - b'\x02333M4100\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02333M4200\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02333R0000\x00\x00\x00\x00\x00\x00\x00\x00A0C01000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152606202\x00\x00\x00\x00\x00\x00', - b'F152633171\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881513309400\x00\x00\x00\x00', - b'881513309500\x00\x00\x00\x00', - b'881513310400\x00\x00\x00\x00', - b'881513310500\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B33502\x00\x00\x00\x00\x00\x00', - b'8965B33512\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4701100\x00\x00\x00\x00', - b'8821F4701200\x00\x00\x00\x00', - b'8821F4701300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F3302001\x00\x00\x00\x00', - b'8646F3302100\x00\x00\x00\x00', - b'8646F3302200\x00\x00\x00\x00', - ], - }, - CAR.LEXUS_GS_F: { - (Ecu.engine, 0x7e0, None): [ - b'\x0233075200\x00\x00\x00\x00\x00\x00\x00\x00530B9000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152630700\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881513016200\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B30551\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702000\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F3002100\x00\x00\x00\x00', - ], - }, - CAR.LEXUS_NX: { - (Ecu.engine, 0x700, None): [ - b'\x01896637850000\x00\x00\x00\x00', - b'\x01896637851000\x00\x00\x00\x00', - b'\x01896637852000\x00\x00\x00\x00', - b'\x01896637854000\x00\x00\x00\x00', - b'\x01896637873000\x00\x00\x00\x00', - b'\x01896637878000\x00\x00\x00\x00', - b'\x01896637878100\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x0237841000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0237842000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0237880000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0237882000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0237886000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152678130\x00\x00\x00\x00\x00\x00', - b'F152678140\x00\x00\x00\x00\x00\x00', - b'F152678160\x00\x00\x00\x00\x00\x00', - b'F152678170\x00\x00\x00\x00\x00\x00', - b'F152678171\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881517803100\x00\x00\x00\x00', - b'881517803300\x00\x00\x00\x00', - b'881517804100\x00\x00\x00\x00', - b'881517804300\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B78060\x00\x00\x00\x00\x00\x00', - b'8965B78080\x00\x00\x00\x00\x00\x00', - b'8965B78100\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702100\x00\x00\x00\x00', - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F7801100\x00\x00\x00\x00', - b'8646F7801300\x00\x00\x00\x00', - ], - }, - CAR.LEXUS_NX_TSS2: { - (Ecu.engine, 0x700, None): [ - b'\x018966378B2000\x00\x00\x00\x00', - b'\x018966378B2100\x00\x00\x00\x00', - b'\x018966378B3000\x00\x00\x00\x00', - b'\x018966378B3100\x00\x00\x00\x00', - b'\x018966378B4100\x00\x00\x00\x00', - b'\x018966378G2000\x00\x00\x00\x00', - b'\x018966378G3000\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x0237881000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0237887000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02378A0000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02378F4000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'\x01F152678221\x00\x00\x00\x00\x00\x00', - b'F152678200\x00\x00\x00\x00\x00\x00', - b'F152678210\x00\x00\x00\x00\x00\x00', - b'F152678211\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B78110\x00\x00\x00\x00\x00\x00', - b'8965B78120\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F3301200\x00\x00\x00\x00', - b'\x018821F3301300\x00\x00\x00\x00', - b'\x018821F3301400\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F78030A0\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', - b'\x028646F7803100\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - ], - }, - CAR.LEXUS_LC_TSS2: { - (Ecu.engine, 0x7e0, None): [ - b'\x0131130000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152611390\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B11091\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F6201400\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F1104200\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', - b'\x028646F1105200\x00\x00\x00\x008646G3304000\x00\x00\x00\x00', - ], - }, - CAR.LEXUS_RC: { - (Ecu.engine, 0x700, None): [ - b'\x01896632461100\x00\x00\x00\x00', - b'\x01896632478100\x00\x00\x00\x00', - b'\x01896632478200\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x0232484000\x00\x00\x00\x00\x00\x00\x00\x0052422000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152624150\x00\x00\x00\x00\x00\x00', - b'F152624221\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881512404100\x00\x00\x00\x00', - b'881512407000\x00\x00\x00\x00', - b'881512409100\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B24081\x00\x00\x00\x00\x00\x00', - b'8965B24240\x00\x00\x00\x00\x00\x00', - b'8965B24320\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4702300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F2401100\x00\x00\x00\x00', - b'8646F2401200\x00\x00\x00\x00', - b'8646F2402200\x00\x00\x00\x00', - ], - }, - CAR.LEXUS_RX: { - (Ecu.engine, 0x700, None): [ - b'\x01896630E36100\x00\x00\x00\x00', - b'\x01896630E36200\x00\x00\x00\x00', - b'\x01896630E36300\x00\x00\x00\x00', - b'\x01896630E37100\x00\x00\x00\x00', - b'\x01896630E37200\x00\x00\x00\x00', - b'\x01896630E37300\x00\x00\x00\x00', - b'\x01896630E41000\x00\x00\x00\x00', - b'\x01896630E41100\x00\x00\x00\x00', - b'\x01896630E41200\x00\x00\x00\x00', - b'\x01896630E41500\x00\x00\x00\x00', - b'\x01896630EA3100\x00\x00\x00\x00', - b'\x01896630EA3300\x00\x00\x00\x00', - b'\x01896630EA3400\x00\x00\x00\x00', - b'\x01896630EA4100\x00\x00\x00\x00', - b'\x01896630EA4300\x00\x00\x00\x00', - b'\x01896630EA4400\x00\x00\x00\x00', - b'\x01896630EA6300\x00\x00\x00\x00', - b'\x018966348R1300\x00\x00\x00\x00', - b'\x018966348R8500\x00\x00\x00\x00', - b'\x018966348W1300\x00\x00\x00\x00', - b'\x018966348W2300\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x02348J7000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02348N0000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02348Q4000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02348Q4100\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02348T1000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02348T1100\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02348T1200\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02348T3000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02348V6000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02348Z3000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152648361\x00\x00\x00\x00\x00\x00', - b'F152648472\x00\x00\x00\x00\x00\x00', - b'F152648473\x00\x00\x00\x00\x00\x00', - b'F152648474\x00\x00\x00\x00\x00\x00', - b'F152648492\x00\x00\x00\x00\x00\x00', - b'F152648493\x00\x00\x00\x00\x00\x00', - b'F152648494\x00\x00\x00\x00\x00\x00', - b'F152648501\x00\x00\x00\x00\x00\x00', - b'F152648502\x00\x00\x00\x00\x00\x00', - b'F152648504\x00\x00\x00\x00\x00\x00', - b'F152648630\x00\x00\x00\x00\x00\x00', - b'F152648740\x00\x00\x00\x00\x00\x00', - b'F152648A30\x00\x00\x00\x00\x00\x00', - ], - (Ecu.dsu, 0x791, None): [ - b'881514810300\x00\x00\x00\x00', - b'881514810500\x00\x00\x00\x00', - b'881514810700\x00\x00\x00\x00', - b'881514811300\x00\x00\x00\x00', - b'881514811500\x00\x00\x00\x00', - b'881514811700\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B0E011\x00\x00\x00\x00\x00\x00', - b'8965B0E012\x00\x00\x00\x00\x00\x00', - b'8965B48102\x00\x00\x00\x00\x00\x00', - b'8965B48111\x00\x00\x00\x00\x00\x00', - b'8965B48112\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'8821F4701000\x00\x00\x00\x00', - b'8821F4701100\x00\x00\x00\x00', - b'8821F4701200\x00\x00\x00\x00', - b'8821F4701300\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'8646F4801100\x00\x00\x00\x00', - b'8646F4801200\x00\x00\x00\x00', - b'8646F4802001\x00\x00\x00\x00', - b'8646F4802100\x00\x00\x00\x00', - b'8646F4802200\x00\x00\x00\x00', - b'8646F4809000\x00\x00\x00\x00', - ], - }, - CAR.LEXUS_RX_TSS2: { - (Ecu.engine, 0x700, None): [ - b'\x01896630EA9000\x00\x00\x00\x00', - b'\x01896630EB0000\x00\x00\x00\x00', - b'\x01896630EC9000\x00\x00\x00\x00', - b'\x01896630EC9100\x00\x00\x00\x00', - b'\x01896630ED0000\x00\x00\x00\x00', - b'\x01896630ED0100\x00\x00\x00\x00', - b'\x01896630ED5000\x00\x00\x00\x00', - b'\x01896630ED6000\x00\x00\x00\x00', - b'\x018966348R9200\x00\x00\x00\x00', - b'\x018966348T8000\x00\x00\x00\x00', - b'\x018966348W5100\x00\x00\x00\x00', - b'\x018966348W9000\x00\x00\x00\x00', - b'\x018966348X0000\x00\x00\x00\x00', - b'\x01896634D11000\x00\x00\x00\x00', - b'\x01896634D12000\x00\x00\x00\x00', - b'\x01896634D12100\x00\x00\x00\x00', - b'\x01896634D43000\x00\x00\x00\x00', - b'\x01896634D44000\x00\x00\x00\x00', - ], - (Ecu.engine, 0x7e0, None): [ - b'\x02348U2000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02348X4000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02348X5000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02348X8000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x02348Y3000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0234D14000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0234D16000\x00\x00\x00\x00\x00\x00\x00\x00A4802000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'\x01F15260E031\x00\x00\x00\x00\x00\x00', - b'\x01F15260E041\x00\x00\x00\x00\x00\x00', - b'\x01F152648781\x00\x00\x00\x00\x00\x00', - b'\x01F152648801\x00\x00\x00\x00\x00\x00', - b'F152648493\x00\x00\x00\x00\x00\x00', - b'F152648811\x00\x00\x00\x00\x00\x00', - b'F152648831\x00\x00\x00\x00\x00\x00', - b'F152648891\x00\x00\x00\x00\x00\x00', - b'F152648C80\x00\x00\x00\x00\x00\x00', - b'F152648D00\x00\x00\x00\x00\x00\x00', - b'F152648D60\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B48261\x00\x00\x00\x00\x00\x00', - b'8965B48271\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F3301100\x00\x00\x00\x00', - b'\x018821F3301300\x00\x00\x00\x00', - b'\x018821F3301400\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F4810100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', - b'\x028646F4810200\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - b'\x028646F4810300\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - b'\x028646F4810400\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_PRIUS_TSS2: { - (Ecu.engine, 0x700, None): [ - b'\x028966347B1000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x028966347C4000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x028966347C6000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x028966347C7000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x028966347C8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', - b'\x038966347C0000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710101\x00\x00\x00\x00', - b'\x038966347C1000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710101\x00\x00\x00\x00', - b'\x038966347C5000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4707101\x00\x00\x00\x00', - b'\x038966347C5100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4707101\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152647500\x00\x00\x00\x00\x00\x00', - b'F152647510\x00\x00\x00\x00\x00\x00', - b'F152647520\x00\x00\x00\x00\x00\x00', - b'F152647521\x00\x00\x00\x00\x00\x00', - b'F152647531\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B47070\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F3301400\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F4707000\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - b'\x028646F4710000\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', - b'\x028646F4712000\x00\x00\x00\x008646G2601500\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_MIRAI: { - (Ecu.abs, 0x7d1, None): [ - b'\x01898A36203000\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'\x01F15266203200\x00\x00\x00\x00', - b'\x01F15266203500\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'\x028965B6204100\x00\x00\x00\x008965B6203100\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F6201200\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F6201400\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', - ], - }, - CAR.TOYOTA_ALPHARD_TSS2: { - (Ecu.engine, 0x7e0, None): [ - b'\x0235870000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0235879000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', - b'\x0235883000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', - ], - (Ecu.eps, 0x7a1, None): [ - b'8965B58040\x00\x00\x00\x00\x00\x00', - b'8965B58052\x00\x00\x00\x00\x00\x00', - ], - (Ecu.abs, 0x7b0, None): [ - b'F152658320\x00\x00\x00\x00\x00\x00', - b'F152658341\x00\x00\x00\x00\x00\x00', - ], - (Ecu.fwdRadar, 0x750, 0xf): [ - b'\x018821F3301200\x00\x00\x00\x00', - b'\x018821F3301400\x00\x00\x00\x00', - ], - (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F58010C0\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', - b'\x028646F5803200\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - b'\x028646FV201000\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', - ], - }, -} diff --git a/car/toyota/interface.py b/car/toyota/interface.py deleted file mode 100644 index 3ea05f9fef..0000000000 --- a/car/toyota/interface.py +++ /dev/null @@ -1,202 +0,0 @@ -from cereal import car -from panda import Panda -from panda.python import uds -from openpilot.selfdrive.car.toyota.values import Ecu, CAR, DBC, ToyotaFlags, CarControllerParams, TSS2_CAR, RADAR_ACC_CAR, NO_DSU_CAR, \ - MIN_ACC_SPEED, EPS_SCALE, UNSUPPORTED_DSU_CAR, NO_STOP_TIMER_CAR, ANGLE_CONTROL_CAR -from openpilot.selfdrive.car import create_button_events, get_safety_config -from openpilot.selfdrive.car.disable_ecu import disable_ecu -from openpilot.selfdrive.car.interfaces import CarInterfaceBase - -ButtonType = car.CarState.ButtonEvent.Type -EventName = car.CarEvent.EventName -SteerControlType = car.CarParams.SteerControlType - - -class CarInterface(CarInterfaceBase): - @staticmethod - def get_pid_accel_limits(CP, current_speed, cruise_speed): - return CarControllerParams.ACCEL_MIN, CarControllerParams.ACCEL_MAX - - @staticmethod - def _get_params(ret, candidate, fingerprint, car_fw, experimental_long, docs): - ret.carName = "toyota" - ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.toyota)] - ret.safetyConfigs[0].safetyParam = EPS_SCALE[candidate] - - # BRAKE_MODULE is on a different address for these cars - if DBC[candidate]["pt"] == "toyota_new_mc_pt_generated": - ret.safetyConfigs[0].safetyParam |= Panda.FLAG_TOYOTA_ALT_BRAKE - - if candidate in ANGLE_CONTROL_CAR: - ret.steerControlType = SteerControlType.angle - ret.safetyConfigs[0].safetyParam |= Panda.FLAG_TOYOTA_LTA - - # LTA control can be more delayed and winds up more often - ret.steerActuatorDelay = 0.18 - ret.steerLimitTimer = 0.8 - else: - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) - - ret.steerActuatorDelay = 0.12 # Default delay, Prius has larger delay - ret.steerLimitTimer = 0.4 - - ret.stoppingControl = False # Toyota starts braking more when it thinks you want to stop - - stop_and_go = candidate in TSS2_CAR - - # Detect smartDSU, which intercepts ACC_CMD from the DSU (or radar) allowing openpilot to send it - # 0x2AA is sent by a similar device which intercepts the radar instead of DSU on NO_DSU_CARs - if 0x2FF in fingerprint[0] or (0x2AA in fingerprint[0] and candidate in NO_DSU_CAR): - ret.flags |= ToyotaFlags.SMART_DSU.value - - if 0x2AA in fingerprint[0] and candidate in NO_DSU_CAR: - ret.flags |= ToyotaFlags.RADAR_CAN_FILTER.value - - # In TSS2 cars, the camera does long control - found_ecus = [fw.ecu for fw in car_fw] - ret.enableDsu = len(found_ecus) > 0 and Ecu.dsu not in found_ecus and candidate not in (NO_DSU_CAR | UNSUPPORTED_DSU_CAR) \ - and not (ret.flags & ToyotaFlags.SMART_DSU) - - if candidate == CAR.TOYOTA_PRIUS: - stop_and_go = True - # Only give steer angle deadzone to for bad angle sensor prius - for fw in car_fw: - if fw.ecu == "eps" and not fw.fwVersion == b'8965B47060\x00\x00\x00\x00\x00\x00': - ret.steerActuatorDelay = 0.25 - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning, steering_angle_deadzone_deg=0.2) - - elif candidate in (CAR.LEXUS_RX, CAR.LEXUS_RX_TSS2): - stop_and_go = True - ret.wheelSpeedFactor = 1.035 - - elif candidate in (CAR.TOYOTA_AVALON, CAR.TOYOTA_AVALON_2019, CAR.TOYOTA_AVALON_TSS2): - # starting from 2019, all Avalon variants have stop and go - # https://engage.toyota.com/static/images/toyota_safety_sense/TSS_Applicability_Chart.pdf - stop_and_go = candidate != CAR.TOYOTA_AVALON - - elif candidate in (CAR.TOYOTA_RAV4_TSS2, CAR.TOYOTA_RAV4_TSS2_2022, CAR.TOYOTA_RAV4_TSS2_2023): - ret.lateralTuning.init('pid') - ret.lateralTuning.pid.kiBP = [0.0] - ret.lateralTuning.pid.kpBP = [0.0] - ret.lateralTuning.pid.kpV = [0.6] - ret.lateralTuning.pid.kiV = [0.1] - ret.lateralTuning.pid.kf = 0.00007818594 - - # 2019+ RAV4 TSS2 uses two different steering racks and specific tuning seems to be necessary. - # See https://github.com/commaai/openpilot/pull/21429#issuecomment-873652891 - for fw in car_fw: - if fw.ecu == "eps" and (fw.fwVersion.startswith(b'\x02') or fw.fwVersion in [b'8965B42181\x00\x00\x00\x00\x00\x00']): - ret.lateralTuning.pid.kpV = [0.15] - ret.lateralTuning.pid.kiV = [0.05] - ret.lateralTuning.pid.kf = 0.00004 - break - - elif candidate in (CAR.TOYOTA_CHR, CAR.TOYOTA_CAMRY, CAR.TOYOTA_SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_NX): - # TODO: Some of these platforms are not advertised to have full range ACC, are they similar to SNG_WITHOUT_DSU cars? - stop_and_go = True - - # TODO: these models can do stop and go, but unclear if it requires sDSU or unplugging DSU. - # For now, don't list stop and go functionality in the docs - if ret.flags & ToyotaFlags.SNG_WITHOUT_DSU: - stop_and_go = stop_and_go or bool(ret.flags & ToyotaFlags.SMART_DSU.value) or (ret.enableDsu and not docs) - - ret.centerToFront = ret.wheelbase * 0.44 - - # TODO: Some TSS-P platforms have BSM, but are flipped based on region or driving direction. - # Detect flipped signals and enable for C-HR and others - ret.enableBsm = 0x3F6 in fingerprint[0] and candidate in TSS2_CAR - - # No radar dbc for cars without DSU which are not TSS 2.0 - # TODO: make an adas dbc file for dsu-less models - ret.radarUnavailable = DBC[candidate]['radar'] is None or candidate in (NO_DSU_CAR - TSS2_CAR) - - # if the smartDSU is detected, openpilot can send ACC_CONTROL and the smartDSU will block it from the DSU or radar. - # since we don't yet parse radar on TSS2/TSS-P radar-based ACC cars, gate longitudinal behind experimental toggle - use_sdsu = bool(ret.flags & ToyotaFlags.SMART_DSU) - if candidate in (RADAR_ACC_CAR | NO_DSU_CAR): - ret.experimentalLongitudinalAvailable = use_sdsu or candidate in RADAR_ACC_CAR - - if not use_sdsu: - # Disabling radar is only supported on TSS2 radar-ACC cars - if experimental_long and candidate in RADAR_ACC_CAR: - ret.flags |= ToyotaFlags.DISABLE_RADAR.value - else: - use_sdsu = use_sdsu and experimental_long - - # openpilot longitudinal enabled by default: - # - non-(TSS2 radar ACC cars) w/ smartDSU installed - # - cars w/ DSU disconnected - # - TSS2 cars with camera sending ACC_CONTROL where we can block it - # openpilot longitudinal behind experimental long toggle: - # - TSS2 radar ACC cars w/ smartDSU installed - # - TSS2 radar ACC cars w/o smartDSU installed (disables radar) - # - TSS-P DSU-less cars w/ CAN filter installed (no radar parser yet) - ret.openpilotLongitudinalControl = use_sdsu or ret.enableDsu or candidate in (TSS2_CAR - RADAR_ACC_CAR) or bool(ret.flags & ToyotaFlags.DISABLE_RADAR.value) - ret.autoResumeSng = ret.openpilotLongitudinalControl and candidate in NO_STOP_TIMER_CAR - - if not ret.openpilotLongitudinalControl: - ret.safetyConfigs[0].safetyParam |= Panda.FLAG_TOYOTA_STOCK_LONGITUDINAL - - # min speed to enable ACC. if car can do stop and go, then set enabling speed - # to a negative value, so it won't matter. - ret.minEnableSpeed = -1. if stop_and_go else MIN_ACC_SPEED - - tune = ret.longitudinalTuning - tune.deadzoneBP = [0., 9.] - tune.deadzoneV = [.0, .15] - if candidate in TSS2_CAR: - tune.kpBP = [0., 5., 20.] - tune.kpV = [1.3, 1.0, 0.7] - tune.kiBP = [0., 5., 12., 20., 27.] - tune.kiV = [.35, .23, .20, .17, .1] - if candidate in TSS2_CAR: - ret.vEgoStopping = 0.25 - ret.vEgoStarting = 0.25 - ret.stoppingDecelRate = 0.3 # reach stopping target smoothly - else: - tune.kpBP = [0., 5., 35.] - tune.kiBP = [0., 35.] - tune.kpV = [3.6, 2.4, 1.5] - tune.kiV = [0.54, 0.36] - - return ret - - @staticmethod - def init(CP, logcan, sendcan): - # disable radar if alpha longitudinal toggled on radar-ACC car without CAN filter/smartDSU - if CP.flags & ToyotaFlags.DISABLE_RADAR.value: - communication_control = bytes([uds.SERVICE_TYPE.COMMUNICATION_CONTROL, uds.CONTROL_TYPE.ENABLE_RX_DISABLE_TX, uds.MESSAGE_TYPE.NORMAL]) - disable_ecu(logcan, sendcan, bus=0, addr=0x750, sub_addr=0xf, com_cont_req=communication_control) - - # returns a car.CarState - def _update(self, c): - ret = self.CS.update(self.cp, self.cp_cam) - - if self.CP.carFingerprint in (TSS2_CAR - RADAR_ACC_CAR) or (self.CP.flags & ToyotaFlags.SMART_DSU and not self.CP.flags & ToyotaFlags.RADAR_CAN_FILTER): - ret.buttonEvents = create_button_events(self.CS.distance_button, self.CS.prev_distance_button, {1: ButtonType.gapAdjustCruise}) - - # events - events = self.create_common_events(ret) - - # Lane Tracing Assist control is unavailable (EPS_STATUS->LTA_STATE=0) until - # the more accurate angle sensor signal is initialized - if self.CP.steerControlType == SteerControlType.angle and not self.CS.accurate_steer_angle_seen: - events.add(EventName.vehicleSensorsInvalid) - - if self.CP.openpilotLongitudinalControl: - if ret.cruiseState.standstill and not ret.brakePressed: - events.add(EventName.resumeRequired) - if self.CS.low_speed_lockout: - events.add(EventName.lowSpeedLockout) - if ret.vEgo < self.CP.minEnableSpeed: - events.add(EventName.belowEngageSpeed) - if c.actuators.accel > 0.3: - # some margin on the actuator to not false trigger cancellation while stopping - events.add(EventName.speedTooLow) - if ret.vEgo < 0.001: - # while in standstill, send a user alert - events.add(EventName.manualRestart) - - ret.events = events.to_msg() - - return ret diff --git a/car/toyota/radar_interface.py b/car/toyota/radar_interface.py deleted file mode 100755 index fae6eecaf6..0000000000 --- a/car/toyota/radar_interface.py +++ /dev/null @@ -1,94 +0,0 @@ -#!/usr/bin/env python3 -from opendbc.can.parser import CANParser -from cereal import car -from openpilot.selfdrive.car.toyota.values import DBC, TSS2_CAR -from openpilot.selfdrive.car.interfaces import RadarInterfaceBase - - -def _create_radar_can_parser(car_fingerprint): - if car_fingerprint in TSS2_CAR: - RADAR_A_MSGS = list(range(0x180, 0x190)) - RADAR_B_MSGS = list(range(0x190, 0x1a0)) - else: - RADAR_A_MSGS = list(range(0x210, 0x220)) - RADAR_B_MSGS = list(range(0x220, 0x230)) - - msg_a_n = len(RADAR_A_MSGS) - msg_b_n = len(RADAR_B_MSGS) - messages = list(zip(RADAR_A_MSGS + RADAR_B_MSGS, [20] * (msg_a_n + msg_b_n), strict=True)) - - return CANParser(DBC[car_fingerprint]['radar'], messages, 1) - -class RadarInterface(RadarInterfaceBase): - def __init__(self, CP): - super().__init__(CP) - self.track_id = 0 - self.radar_ts = CP.radarTimeStep - - if CP.carFingerprint in TSS2_CAR: - self.RADAR_A_MSGS = list(range(0x180, 0x190)) - self.RADAR_B_MSGS = list(range(0x190, 0x1a0)) - else: - self.RADAR_A_MSGS = list(range(0x210, 0x220)) - self.RADAR_B_MSGS = list(range(0x220, 0x230)) - - self.valid_cnt = {key: 0 for key in self.RADAR_A_MSGS} - - self.rcp = None if CP.radarUnavailable else _create_radar_can_parser(CP.carFingerprint) - self.trigger_msg = self.RADAR_B_MSGS[-1] - self.updated_messages = set() - - def update(self, can_strings): - if self.rcp is None: - return super().update(None) - - vls = self.rcp.update_strings(can_strings) - self.updated_messages.update(vls) - - if self.trigger_msg not in self.updated_messages: - return None - - rr = self._update(self.updated_messages) - self.updated_messages.clear() - - return rr - - def _update(self, updated_messages): - ret = car.RadarData.new_message() - errors = [] - if not self.rcp.can_valid: - errors.append("canError") - ret.errors = errors - - for ii in sorted(updated_messages): - if ii in self.RADAR_A_MSGS: - cpt = self.rcp.vl[ii] - - if cpt['LONG_DIST'] >= 255 or cpt['NEW_TRACK']: - self.valid_cnt[ii] = 0 # reset counter - if cpt['VALID'] and cpt['LONG_DIST'] < 255: - self.valid_cnt[ii] += 1 - else: - self.valid_cnt[ii] = max(self.valid_cnt[ii] - 1, 0) - - score = self.rcp.vl[ii+16]['SCORE'] - # print ii, self.valid_cnt[ii], score, cpt['VALID'], cpt['LONG_DIST'], cpt['LAT_DIST'] - - # radar point only valid if it's a valid measurement and score is above 50 - if cpt['VALID'] or (score > 50 and cpt['LONG_DIST'] < 255 and self.valid_cnt[ii] > 0): - if ii not in self.pts or cpt['NEW_TRACK']: - self.pts[ii] = car.RadarData.RadarPoint.new_message() - self.pts[ii].trackId = self.track_id - self.track_id += 1 - self.pts[ii].dRel = cpt['LONG_DIST'] # from front of car - self.pts[ii].yRel = -cpt['LAT_DIST'] # in car frame's y axis, left is positive - self.pts[ii].vRel = cpt['REL_SPEED'] - self.pts[ii].aRel = float('nan') - self.pts[ii].yvRel = float('nan') - self.pts[ii].measured = bool(cpt['VALID']) - else: - if ii in self.pts: - del self.pts[ii] - - ret.points = list(self.pts.values()) - return ret diff --git a/car/toyota/tests/__init__.py b/car/toyota/tests/__init__.py deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/car/toyota/tests/print_platform_codes.py b/car/toyota/tests/print_platform_codes.py deleted file mode 100755 index 9ec7a14cd3..0000000000 --- a/car/toyota/tests/print_platform_codes.py +++ /dev/null @@ -1,35 +0,0 @@ -#!/usr/bin/env python3 -from collections import defaultdict -from cereal import car -from openpilot.selfdrive.car.toyota.values import PLATFORM_CODE_ECUS, get_platform_codes -from openpilot.selfdrive.car.toyota.fingerprints import FW_VERSIONS - -Ecu = car.CarParams.Ecu -ECU_NAME = {v: k for k, v in Ecu.schema.enumerants.items()} - -if __name__ == "__main__": - parts_for_ecu: dict = defaultdict(set) - cars_for_code: dict = defaultdict(lambda: defaultdict(set)) - for car_model, ecus in FW_VERSIONS.items(): - print() - print(car_model) - for ecu in sorted(ecus, key=lambda x: int(x[0])): - if ecu[0] not in PLATFORM_CODE_ECUS: - continue - - platform_codes = get_platform_codes(ecus[ecu]) - parts_for_ecu[ecu] |= {code.split(b'-')[0] for code in platform_codes if code.count(b'-') > 1} - for code in platform_codes: - cars_for_code[ecu][b'-'.join(code.split(b'-')[:2])] |= {car_model} - print(f' (Ecu.{ECU_NAME[ecu[0]]}, {hex(ecu[1])}, {ecu[2]}):') - print(f' Codes: {platform_codes}') - - print('\nECU parts:') - for ecu, parts in parts_for_ecu.items(): - print(f' (Ecu.{ECU_NAME[ecu[0]]}, {hex(ecu[1])}, {ecu[2]}): {parts}') - - print('\nCar models vs. platform codes (no major versions):') - for ecu, codes in cars_for_code.items(): - print(f' (Ecu.{ECU_NAME[ecu[0]]}, {hex(ecu[1])}, {ecu[2]}):') - for code, cars in codes.items(): - print(f' {code!r}: {sorted(cars)}') diff --git a/car/toyota/tests/test_toyota.py b/car/toyota/tests/test_toyota.py deleted file mode 100644 index 0217a0fbc1..0000000000 --- a/car/toyota/tests/test_toyota.py +++ /dev/null @@ -1,166 +0,0 @@ -from hypothesis import given, settings, strategies as st - -from cereal import car -from openpilot.selfdrive.car.fw_versions import build_fw_dict -from openpilot.selfdrive.car.toyota.fingerprints import FW_VERSIONS -from openpilot.selfdrive.car.toyota.values import CAR, DBC, TSS2_CAR, ANGLE_CONTROL_CAR, RADAR_ACC_CAR, \ - FW_QUERY_CONFIG, PLATFORM_CODE_ECUS, FUZZY_EXCLUDED_PLATFORMS, \ - get_platform_codes - -Ecu = car.CarParams.Ecu -ECU_NAME = {v: k for k, v in Ecu.schema.enumerants.items()} - - -def check_fw_version(fw_version: bytes) -> bool: - return b'?' not in fw_version - - -class TestToyotaInterfaces: - def test_car_sets(self): - assert len(ANGLE_CONTROL_CAR - TSS2_CAR) == 0 - assert len(RADAR_ACC_CAR - TSS2_CAR) == 0 - - def test_lta_platforms(self): - # At this time, only RAV4 2023 is expected to use LTA/angle control - assert ANGLE_CONTROL_CAR == {CAR.TOYOTA_RAV4_TSS2_2023} - - def test_tss2_dbc(self): - # We make some assumptions about TSS2 platforms, - # like looking up certain signals only in this DBC - for car_model, dbc in DBC.items(): - if car_model in TSS2_CAR: - assert dbc["pt"] == "toyota_nodsu_pt_generated" - - def test_essential_ecus(self, subtests): - # Asserts standard ECUs exist for each platform - common_ecus = {Ecu.fwdRadar, Ecu.fwdCamera} - for car_model, ecus in FW_VERSIONS.items(): - with subtests.test(car_model=car_model.value): - present_ecus = {ecu[0] for ecu in ecus} - missing_ecus = common_ecus - present_ecus - assert len(missing_ecus) == 0 - - # Some exceptions for other common ECUs - if car_model not in (CAR.TOYOTA_ALPHARD_TSS2,): - assert Ecu.abs in present_ecus - - if car_model not in (CAR.TOYOTA_MIRAI,): - assert Ecu.engine in present_ecus - - if car_model not in (CAR.TOYOTA_PRIUS_V, CAR.LEXUS_CTH): - assert Ecu.eps in present_ecus - - -class TestToyotaFingerprint: - def test_non_essential_ecus(self, subtests): - # Ensures only the cars that have multiple engine ECUs are in the engine non-essential ECU list - for car_model, ecus in FW_VERSIONS.items(): - with subtests.test(car_model=car_model.value): - engine_ecus = {ecu for ecu in ecus if ecu[0] == Ecu.engine} - assert (len(engine_ecus) > 1) == (car_model in FW_QUERY_CONFIG.non_essential_ecus[Ecu.engine]), \ - f"Car model unexpectedly {'not ' if len(engine_ecus) > 1 else ''}in non-essential list" - - def test_valid_fw_versions(self, subtests): - # Asserts all FW versions are valid - for car_model, ecus in FW_VERSIONS.items(): - with subtests.test(car_model=car_model.value): - for fws in ecus.values(): - for fw in fws: - assert check_fw_version(fw), fw - - # Tests for part numbers, platform codes, and sub-versions which Toyota will use to fuzzy - # fingerprint in the absence of full FW matches: - @settings(max_examples=100) - @given(data=st.data()) - def test_platform_codes_fuzzy_fw(self, data): - fw_strategy = st.lists(st.binary()) - fws = data.draw(fw_strategy) - get_platform_codes(fws) - - def test_platform_code_ecus_available(self, subtests): - # Asserts ECU keys essential for fuzzy fingerprinting are available on all platforms - for car_model, ecus in FW_VERSIONS.items(): - with subtests.test(car_model=car_model.value): - for platform_code_ecu in PLATFORM_CODE_ECUS: - if platform_code_ecu == Ecu.eps and car_model in (CAR.TOYOTA_PRIUS_V, CAR.LEXUS_CTH,): - continue - if platform_code_ecu == Ecu.abs and car_model in (CAR.TOYOTA_ALPHARD_TSS2,): - continue - assert platform_code_ecu in [e[0] for e in ecus] - - def test_fw_format(self, subtests): - # Asserts: - # - every supported ECU FW version returns one platform code - # - every supported ECU FW version has a part number - # - expected parsing of ECU sub-versions - - for car_model, ecus in FW_VERSIONS.items(): - with subtests.test(car_model=car_model.value): - for ecu, fws in ecus.items(): - if ecu[0] not in PLATFORM_CODE_ECUS: - continue - - codes = dict() - for fw in fws: - result = get_platform_codes([fw]) - # Check only one platform code and sub-version - assert 1 == len(result), f"Unable to parse FW: {fw}" - assert 1 == len(list(result.values())[0]), f"Unable to parse FW: {fw}" - codes |= result - - # Toyota places the ECU part number in their FW versions, assert all parsable - # Note that there is only one unique part number per ECU across the fleet, so this - # is not important for identification, just a sanity check. - assert all(code.count(b"-") > 1 for code in codes), f"FW does not have part number: {fw} {codes}" - - def test_platform_codes_spot_check(self): - # Asserts basic platform code parsing behavior for a few cases - results = get_platform_codes([ - b"F152607140\x00\x00\x00\x00\x00\x00", - b"F152607171\x00\x00\x00\x00\x00\x00", - b"F152607110\x00\x00\x00\x00\x00\x00", - b"F152607180\x00\x00\x00\x00\x00\x00", - ]) - assert results == {b"F1526-07-1": {b"10", b"40", b"71", b"80"}} - - results = get_platform_codes([ - b"\x028646F4104100\x00\x00\x00\x008646G5301200\x00\x00\x00\x00", - b"\x028646F4104100\x00\x00\x00\x008646G3304000\x00\x00\x00\x00", - ]) - assert results == {b"8646F-41-04": {b"100"}} - - # Short version has no part number - results = get_platform_codes([ - b"\x0235870000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00", - b"\x0235883000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00", - ]) - assert results == {b"58-70": {b"000"}, b"58-83": {b"000"}} - - results = get_platform_codes([ - b"F152607110\x00\x00\x00\x00\x00\x00", - b"F152607140\x00\x00\x00\x00\x00\x00", - b"\x028646F4104100\x00\x00\x00\x008646G5301200\x00\x00\x00\x00", - b"\x0235879000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00", - ]) - assert results == {b"F1526-07-1": {b"10", b"40"}, b"8646F-41-04": {b"100"}, b"58-79": {b"000"}} - - def test_fuzzy_excluded_platforms(self): - # Asserts a list of platforms that will not fuzzy fingerprint with platform codes due to them being shared. - platforms_with_shared_codes = set() - for platform, fw_by_addr in FW_VERSIONS.items(): - car_fw = [] - for ecu, fw_versions in fw_by_addr.items(): - ecu_name, addr, sub_addr = ecu - for fw in fw_versions: - car_fw.append({"ecu": ecu_name, "fwVersion": fw, "address": addr, - "subAddress": 0 if sub_addr is None else sub_addr}) - - CP = car.CarParams.new_message(carFw=car_fw) - matches = FW_QUERY_CONFIG.match_fw_to_car_fuzzy(build_fw_dict(CP.carFw), CP.carVin, FW_VERSIONS) - if len(matches) == 1: - assert list(matches)[0] == platform - else: - # If a platform has multiple matches, add it and its matches - platforms_with_shared_codes |= {str(platform), *matches} - - assert platforms_with_shared_codes == FUZZY_EXCLUDED_PLATFORMS, (len(platforms_with_shared_codes), len(FW_VERSIONS)) diff --git a/car/toyota/toyotacan.py b/car/toyota/toyotacan.py deleted file mode 100644 index 1cc99b41b5..0000000000 --- a/car/toyota/toyotacan.py +++ /dev/null @@ -1,118 +0,0 @@ -from cereal import car - -SteerControlType = car.CarParams.SteerControlType - - -def create_steer_command(packer, steer, steer_req): - """Creates a CAN message for the Toyota Steer Command.""" - - values = { - "STEER_REQUEST": steer_req, - "STEER_TORQUE_CMD": steer, - "SET_ME_1": 1, - } - return packer.make_can_msg("STEERING_LKA", 0, values) - - -def create_lta_steer_command(packer, steer_control_type, steer_angle, steer_req, frame, torque_wind_down): - """Creates a CAN message for the Toyota LTA Steer Command.""" - - values = { - "COUNTER": frame + 128, - "SETME_X1": 1, # suspected LTA feature availability - # 1 for TSS 2.5 cars, 3 for TSS 2.0. Send based on whether we're using LTA for lateral control - "SETME_X3": 1 if steer_control_type == SteerControlType.angle else 3, - "PERCENTAGE": 100, - "TORQUE_WIND_DOWN": torque_wind_down, - "ANGLE": 0, - "STEER_ANGLE_CMD": steer_angle, - "STEER_REQUEST": steer_req, - "STEER_REQUEST_2": steer_req, - "CLEAR_HOLD_STEERING_ALERT": 0, - } - return packer.make_can_msg("STEERING_LTA", 0, values) - - -def create_accel_command(packer, accel, pcm_cancel, standstill_req, lead, acc_type, fcw_alert, distance): - # TODO: find the exact canceling bit that does not create a chime - values = { - "ACCEL_CMD": accel, - "ACC_TYPE": acc_type, - "DISTANCE": distance, - "MINI_CAR": lead, - "PERMIT_BRAKING": 1, - "RELEASE_STANDSTILL": not standstill_req, - "CANCEL_REQ": pcm_cancel, - "ALLOW_LONG_PRESS": 1, - "ACC_CUT_IN": fcw_alert, # only shown when ACC enabled - } - return packer.make_can_msg("ACC_CONTROL", 0, values) - - -def create_acc_cancel_command(packer): - values = { - "GAS_RELEASED": 0, - "CRUISE_ACTIVE": 0, - "ACC_BRAKING": 0, - "ACCEL_NET": 0, - "CRUISE_STATE": 0, - "CANCEL_REQ": 1, - } - return packer.make_can_msg("PCM_CRUISE", 0, values) - - -def create_fcw_command(packer, fcw): - values = { - "PCS_INDICATOR": 1, # PCS turned off - "FCW": fcw, - "SET_ME_X20": 0x20, - "SET_ME_X10": 0x10, - "PCS_OFF": 1, - "PCS_SENSITIVITY": 0, - } - return packer.make_can_msg("PCS_HUD", 0, values) - - -def create_ui_command(packer, steer, chime, left_line, right_line, left_lane_depart, right_lane_depart, enabled, stock_lkas_hud): - values = { - "TWO_BEEPS": chime, - "LDA_ALERT": steer, - "RIGHT_LINE": 3 if right_lane_depart else 1 if right_line else 2, - "LEFT_LINE": 3 if left_lane_depart else 1 if left_line else 2, - "BARRIERS": 1 if enabled else 0, - - # static signals - "SET_ME_X02": 2, - "SET_ME_X01": 1, - "LKAS_STATUS": 1, - "REPEATED_BEEPS": 0, - "LANE_SWAY_FLD": 7, - "LANE_SWAY_BUZZER": 0, - "LANE_SWAY_WARNING": 0, - "LDA_FRONT_CAMERA_BLOCKED": 0, - "TAKE_CONTROL": 0, - "LANE_SWAY_SENSITIVITY": 2, - "LANE_SWAY_TOGGLE": 1, - "LDA_ON_MESSAGE": 0, - "LDA_MESSAGES": 0, - "LDA_SA_TOGGLE": 1, - "LDA_SENSITIVITY": 2, - "LDA_UNAVAILABLE": 0, - "LDA_MALFUNCTION": 0, - "LDA_UNAVAILABLE_QUIET": 0, - "ADJUSTING_CAMERA": 0, - "LDW_EXIST": 1, - } - - # lane sway functionality - # not all cars have LKAS_HUD — update with camera values if available - if len(stock_lkas_hud): - values.update({s: stock_lkas_hud[s] for s in [ - "LANE_SWAY_FLD", - "LANE_SWAY_BUZZER", - "LANE_SWAY_WARNING", - "LANE_SWAY_SENSITIVITY", - "LANE_SWAY_TOGGLE", - ]}) - - return packer.make_can_msg("LKAS_HUD", 0, values) diff --git a/car/toyota/values.py b/car/toyota/values.py deleted file mode 100644 index dbab2e9255..0000000000 --- a/car/toyota/values.py +++ /dev/null @@ -1,575 +0,0 @@ -import re -from collections import defaultdict -from dataclasses import dataclass, field -from enum import Enum, IntFlag - -from cereal import car -from openpilot.common.conversions import Conversions as CV -from openpilot.selfdrive.car import CarSpecs, PlatformConfig, Platforms -from openpilot.selfdrive.car import AngleRateLimit, dbc_dict -from openpilot.selfdrive.car.docs_definitions import CarFootnote, CarDocs, Column, CarParts, CarHarness -from openpilot.selfdrive.car.fw_query_definitions import FwQueryConfig, Request, StdQueries - -Ecu = car.CarParams.Ecu -MIN_ACC_SPEED = 19. * CV.MPH_TO_MS -PEDAL_TRANSITION = 10. * CV.MPH_TO_MS - - -class CarControllerParams: - ACCEL_MAX = 1.5 # m/s2, lower than allowed 2.0 m/s2 for tuning reasons - ACCEL_MIN = -3.5 # m/s2 - - STEER_STEP = 1 - STEER_MAX = 1500 - STEER_ERROR_MAX = 350 # max delta between torque cmd and torque motor - - # Lane Tracing Assist (LTA) control limits - # Assuming a steering ratio of 13.7: - # Limit to ~2.0 m/s^3 up (7.5 deg/s), ~3.5 m/s^3 down (13 deg/s) at 75 mph - # Worst case, the low speed limits will allow ~4.0 m/s^3 up (15 deg/s) and ~4.9 m/s^3 down (18 deg/s) at 75 mph, - # however the EPS has its own internal limits at all speeds which are less than that: - # Observed internal torque rate limit on TSS 2.5 Camry and RAV4 is ~1500 units/sec up and down when using LTA - ANGLE_RATE_LIMIT_UP = AngleRateLimit(speed_bp=[5, 25], angle_v=[0.3, 0.15]) - ANGLE_RATE_LIMIT_DOWN = AngleRateLimit(speed_bp=[5, 25], angle_v=[0.36, 0.26]) - - def __init__(self, CP): - if CP.lateralTuning.which == 'torque': - self.STEER_DELTA_UP = 15 # 1.0s time to peak torque - self.STEER_DELTA_DOWN = 25 # always lower than 45 otherwise the Rav4 faults (Prius seems ok with 50) - else: - self.STEER_DELTA_UP = 10 # 1.5s time to peak torque - self.STEER_DELTA_DOWN = 25 # always lower than 45 otherwise the Rav4 faults (Prius seems ok with 50) - - -class ToyotaFlags(IntFlag): - # Detected flags - HYBRID = 1 - SMART_DSU = 2 - DISABLE_RADAR = 4 - RADAR_CAN_FILTER = 1024 - - # Static flags - TSS2 = 8 - NO_DSU = 16 - UNSUPPORTED_DSU = 32 - RADAR_ACC = 64 - # these cars use the Lane Tracing Assist (LTA) message for lateral control - ANGLE_CONTROL = 128 - NO_STOP_TIMER = 256 - # these cars are speculated to allow stop and go when the DSU is unplugged or disabled with sDSU - SNG_WITHOUT_DSU = 512 - - -class Footnote(Enum): - CAMRY = CarFootnote( - "openpilot operates above 28mph for Camry 4CYL L, 4CYL LE and 4CYL SE which don't have Full-Speed Range Dynamic Radar Cruise Control.", - Column.FSR_LONGITUDINAL) - - -@dataclass -class ToyotaCarDocs(CarDocs): - package: str = "All" - car_parts: CarParts = field(default_factory=CarParts.common([CarHarness.toyota_a])) - - -@dataclass -class ToyotaTSS2PlatformConfig(PlatformConfig): - dbc_dict: dict = field(default_factory=lambda: dbc_dict('toyota_nodsu_pt_generated', 'toyota_tss2_adas')) - - def init(self): - self.flags |= ToyotaFlags.TSS2 | ToyotaFlags.NO_STOP_TIMER | ToyotaFlags.NO_DSU - - if self.flags & ToyotaFlags.RADAR_ACC: - self.dbc_dict = dbc_dict('toyota_nodsu_pt_generated', None) - - -class CAR(Platforms): - # Toyota - TOYOTA_ALPHARD_TSS2 = ToyotaTSS2PlatformConfig( - [ - ToyotaCarDocs("Toyota Alphard 2019-20"), - ToyotaCarDocs("Toyota Alphard Hybrid 2021"), - ], - CarSpecs(mass=4305. * CV.LB_TO_KG, wheelbase=3.0, steerRatio=14.2, tireStiffnessFactor=0.444), - ) - TOYOTA_AVALON = PlatformConfig( - [ - ToyotaCarDocs("Toyota Avalon 2016", "Toyota Safety Sense P"), - ToyotaCarDocs("Toyota Avalon 2017-18"), - ], - CarSpecs(mass=3505. * CV.LB_TO_KG, wheelbase=2.82, steerRatio=14.8, tireStiffnessFactor=0.7983), - dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), - ) - TOYOTA_AVALON_2019 = PlatformConfig( - [ - ToyotaCarDocs("Toyota Avalon 2019-21"), - ToyotaCarDocs("Toyota Avalon Hybrid 2019-21"), - ], - TOYOTA_AVALON.specs, - dbc_dict('toyota_nodsu_pt_generated', 'toyota_adas'), - ) - TOYOTA_AVALON_TSS2 = ToyotaTSS2PlatformConfig( # TSS 2.5 - [ - ToyotaCarDocs("Toyota Avalon 2022"), - ToyotaCarDocs("Toyota Avalon Hybrid 2022"), - ], - TOYOTA_AVALON.specs, - ) - TOYOTA_CAMRY = PlatformConfig( - [ - ToyotaCarDocs("Toyota Camry 2018-20", video_link="https://www.youtube.com/watch?v=fkcjviZY9CM", footnotes=[Footnote.CAMRY]), - ToyotaCarDocs("Toyota Camry Hybrid 2018-20", video_link="https://www.youtube.com/watch?v=Q2DYY0AWKgk"), - ], - CarSpecs(mass=3400. * CV.LB_TO_KG, wheelbase=2.82448, steerRatio=13.7, tireStiffnessFactor=0.7933), - dbc_dict('toyota_nodsu_pt_generated', 'toyota_adas'), - flags=ToyotaFlags.NO_DSU, - ) - TOYOTA_CAMRY_TSS2 = ToyotaTSS2PlatformConfig( # TSS 2.5 - [ - ToyotaCarDocs("Toyota Camry 2021-24", footnotes=[Footnote.CAMRY]), - ToyotaCarDocs("Toyota Camry Hybrid 2021-24"), - ], - TOYOTA_CAMRY.specs, - ) - TOYOTA_CHR = PlatformConfig( - [ - ToyotaCarDocs("Toyota C-HR 2017-20"), - ToyotaCarDocs("Toyota C-HR Hybrid 2017-20"), - ], - CarSpecs(mass=3300. * CV.LB_TO_KG, wheelbase=2.63906, steerRatio=13.6, tireStiffnessFactor=0.7933), - dbc_dict('toyota_nodsu_pt_generated', 'toyota_adas'), - flags=ToyotaFlags.NO_DSU, - ) - TOYOTA_CHR_TSS2 = ToyotaTSS2PlatformConfig( - [ - ToyotaCarDocs("Toyota C-HR 2021"), - ToyotaCarDocs("Toyota C-HR Hybrid 2021-22"), - ], - TOYOTA_CHR.specs, - flags=ToyotaFlags.RADAR_ACC, - ) - TOYOTA_COROLLA = PlatformConfig( - [ToyotaCarDocs("Toyota Corolla 2017-19")], - CarSpecs(mass=2860. * CV.LB_TO_KG, wheelbase=2.7, steerRatio=18.27, tireStiffnessFactor=0.444), - dbc_dict('toyota_new_mc_pt_generated', 'toyota_adas'), - ) - # LSS2 Lexus UX Hybrid is same as a TSS2 Corolla Hybrid - TOYOTA_COROLLA_TSS2 = ToyotaTSS2PlatformConfig( - [ - ToyotaCarDocs("Toyota Corolla 2020-22", video_link="https://www.youtube.com/watch?v=_66pXk0CBYA"), - ToyotaCarDocs("Toyota Corolla Cross (Non-US only) 2020-23", min_enable_speed=7.5), - ToyotaCarDocs("Toyota Corolla Hatchback 2019-22", video_link="https://www.youtube.com/watch?v=_66pXk0CBYA"), - # Hybrid platforms - ToyotaCarDocs("Toyota Corolla Hybrid 2020-22"), - ToyotaCarDocs("Toyota Corolla Hybrid (Non-US only) 2020-23", min_enable_speed=7.5), - ToyotaCarDocs("Toyota Corolla Cross Hybrid (Non-US only) 2020-22", min_enable_speed=7.5), - ToyotaCarDocs("Lexus UX Hybrid 2019-23"), - ], - CarSpecs(mass=3060. * CV.LB_TO_KG, wheelbase=2.67, steerRatio=13.9, tireStiffnessFactor=0.444), - ) - TOYOTA_HIGHLANDER = PlatformConfig( - [ - ToyotaCarDocs("Toyota Highlander 2017-19", video_link="https://www.youtube.com/watch?v=0wS0wXSLzoo"), - ToyotaCarDocs("Toyota Highlander Hybrid 2017-19"), - ], - CarSpecs(mass=4516. * CV.LB_TO_KG, wheelbase=2.8194, steerRatio=16.0, tireStiffnessFactor=0.8), - dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), - flags=ToyotaFlags.NO_STOP_TIMER | ToyotaFlags.SNG_WITHOUT_DSU, - ) - TOYOTA_HIGHLANDER_TSS2 = ToyotaTSS2PlatformConfig( - [ - ToyotaCarDocs("Toyota Highlander 2020-23"), - ToyotaCarDocs("Toyota Highlander Hybrid 2020-23"), - ], - TOYOTA_HIGHLANDER.specs, - ) - TOYOTA_PRIUS = PlatformConfig( - [ - ToyotaCarDocs("Toyota Prius 2016", "Toyota Safety Sense P", video_link="https://www.youtube.com/watch?v=8zopPJI8XQ0"), - ToyotaCarDocs("Toyota Prius 2017-20", video_link="https://www.youtube.com/watch?v=8zopPJI8XQ0"), - ToyotaCarDocs("Toyota Prius Prime 2017-20", video_link="https://www.youtube.com/watch?v=8zopPJI8XQ0"), - ], - CarSpecs(mass=3045. * CV.LB_TO_KG, wheelbase=2.7, steerRatio=15.74, tireStiffnessFactor=0.6371), - dbc_dict('toyota_nodsu_pt_generated', 'toyota_adas'), - ) - TOYOTA_PRIUS_V = PlatformConfig( - [ToyotaCarDocs("Toyota Prius v 2017", "Toyota Safety Sense P", min_enable_speed=MIN_ACC_SPEED)], - CarSpecs(mass=3340. * CV.LB_TO_KG, wheelbase=2.78, steerRatio=17.4, tireStiffnessFactor=0.5533), - dbc_dict('toyota_new_mc_pt_generated', 'toyota_adas'), - flags=ToyotaFlags.NO_STOP_TIMER | ToyotaFlags.SNG_WITHOUT_DSU, - ) - TOYOTA_PRIUS_TSS2 = ToyotaTSS2PlatformConfig( - [ - ToyotaCarDocs("Toyota Prius 2021-22", video_link="https://www.youtube.com/watch?v=J58TvCpUd4U"), - ToyotaCarDocs("Toyota Prius Prime 2021-22", video_link="https://www.youtube.com/watch?v=J58TvCpUd4U"), - ], - CarSpecs(mass=3115. * CV.LB_TO_KG, wheelbase=2.70002, steerRatio=13.4, tireStiffnessFactor=0.6371), - ) - TOYOTA_RAV4 = PlatformConfig( - [ - ToyotaCarDocs("Toyota RAV4 2016", "Toyota Safety Sense P"), - ToyotaCarDocs("Toyota RAV4 2017-18") - ], - CarSpecs(mass=3650. * CV.LB_TO_KG, wheelbase=2.65, steerRatio=16.88, tireStiffnessFactor=0.5533), - dbc_dict('toyota_new_mc_pt_generated', 'toyota_adas'), - ) - TOYOTA_RAV4H = PlatformConfig( - [ - ToyotaCarDocs("Toyota RAV4 Hybrid 2016", "Toyota Safety Sense P", video_link="https://youtu.be/LhT5VzJVfNI?t=26"), - ToyotaCarDocs("Toyota RAV4 Hybrid 2017-18", video_link="https://youtu.be/LhT5VzJVfNI?t=26") - ], - TOYOTA_RAV4.specs, - dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), - # Note that the ICE RAV4 does not respect positive acceleration commands under 19 mph - flags=ToyotaFlags.NO_STOP_TIMER | ToyotaFlags.SNG_WITHOUT_DSU, - ) - TOYOTA_RAV4_TSS2 = ToyotaTSS2PlatformConfig( - [ - ToyotaCarDocs("Toyota RAV4 2019-21", video_link="https://www.youtube.com/watch?v=wJxjDd42gGA"), - ToyotaCarDocs("Toyota RAV4 Hybrid 2019-21"), - ], - CarSpecs(mass=3585. * CV.LB_TO_KG, wheelbase=2.68986, steerRatio=14.3, tireStiffnessFactor=0.7933), - ) - TOYOTA_RAV4_TSS2_2022 = ToyotaTSS2PlatformConfig( - [ - ToyotaCarDocs("Toyota RAV4 2022"), - ToyotaCarDocs("Toyota RAV4 Hybrid 2022", video_link="https://youtu.be/U0nH9cnrFB0"), - ], - TOYOTA_RAV4_TSS2.specs, - flags=ToyotaFlags.RADAR_ACC, - ) - TOYOTA_RAV4_TSS2_2023 = ToyotaTSS2PlatformConfig( - [ - ToyotaCarDocs("Toyota RAV4 2023-24"), - ToyotaCarDocs("Toyota RAV4 Hybrid 2023-24"), - ], - TOYOTA_RAV4_TSS2.specs, - flags=ToyotaFlags.RADAR_ACC | ToyotaFlags.ANGLE_CONTROL, - ) - TOYOTA_MIRAI = ToyotaTSS2PlatformConfig( # TSS 2.5 - [ToyotaCarDocs("Toyota Mirai 2021")], - CarSpecs(mass=4300. * CV.LB_TO_KG, wheelbase=2.91, steerRatio=14.8, tireStiffnessFactor=0.8), - ) - TOYOTA_SIENNA = PlatformConfig( - [ToyotaCarDocs("Toyota Sienna 2018-20", video_link="https://www.youtube.com/watch?v=q1UPOo4Sh68", min_enable_speed=MIN_ACC_SPEED)], - CarSpecs(mass=4590. * CV.LB_TO_KG, wheelbase=3.03, steerRatio=15.5, tireStiffnessFactor=0.444), - dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), - flags=ToyotaFlags.NO_STOP_TIMER, - ) - - # Lexus - LEXUS_CTH = PlatformConfig( - [ToyotaCarDocs("Lexus CT Hybrid 2017-18", "Lexus Safety System+")], - CarSpecs(mass=3108. * CV.LB_TO_KG, wheelbase=2.6, steerRatio=18.6, tireStiffnessFactor=0.517), - dbc_dict('toyota_new_mc_pt_generated', 'toyota_adas'), - ) - LEXUS_ES = PlatformConfig( - [ - ToyotaCarDocs("Lexus ES 2017-18"), - ToyotaCarDocs("Lexus ES Hybrid 2017-18"), - ], - CarSpecs(mass=3677. * CV.LB_TO_KG, wheelbase=2.8702, steerRatio=16.0, tireStiffnessFactor=0.444), - dbc_dict('toyota_new_mc_pt_generated', 'toyota_adas'), - ) - LEXUS_ES_TSS2 = ToyotaTSS2PlatformConfig( - [ - ToyotaCarDocs("Lexus ES 2019-24"), - ToyotaCarDocs("Lexus ES Hybrid 2019-24", video_link="https://youtu.be/BZ29osRVJeg?t=12"), - ], - LEXUS_ES.specs, - ) - LEXUS_IS = PlatformConfig( - [ToyotaCarDocs("Lexus IS 2017-19")], - CarSpecs(mass=3736.8 * CV.LB_TO_KG, wheelbase=2.79908, steerRatio=13.3, tireStiffnessFactor=0.444), - dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), - flags=ToyotaFlags.UNSUPPORTED_DSU, - ) - LEXUS_IS_TSS2 = ToyotaTSS2PlatformConfig( - [ToyotaCarDocs("Lexus IS 2022-23")], - LEXUS_IS.specs, - ) - LEXUS_NX = PlatformConfig( - [ - ToyotaCarDocs("Lexus NX 2018-19"), - ToyotaCarDocs("Lexus NX Hybrid 2018-19"), - ], - CarSpecs(mass=4070. * CV.LB_TO_KG, wheelbase=2.66, steerRatio=14.7, tireStiffnessFactor=0.444), - dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), - ) - LEXUS_NX_TSS2 = ToyotaTSS2PlatformConfig( - [ - ToyotaCarDocs("Lexus NX 2020-21"), - ToyotaCarDocs("Lexus NX Hybrid 2020-21"), - ], - LEXUS_NX.specs, - ) - LEXUS_LC_TSS2 = ToyotaTSS2PlatformConfig( - [ToyotaCarDocs("Lexus LC 2024")], - CarSpecs(mass=4500. * CV.LB_TO_KG, wheelbase=2.87, steerRatio=13.0, tireStiffnessFactor=0.444), - ) - LEXUS_RC = PlatformConfig( - [ToyotaCarDocs("Lexus RC 2018-20")], - LEXUS_IS.specs, - dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), - flags=ToyotaFlags.UNSUPPORTED_DSU, - ) - LEXUS_RX = PlatformConfig( - [ - ToyotaCarDocs("Lexus RX 2016", "Lexus Safety System+"), - ToyotaCarDocs("Lexus RX 2017-19"), - # Hybrid platforms - ToyotaCarDocs("Lexus RX Hybrid 2016", "Lexus Safety System+"), - ToyotaCarDocs("Lexus RX Hybrid 2017-19"), - ], - CarSpecs(mass=4481. * CV.LB_TO_KG, wheelbase=2.79, steerRatio=16., tireStiffnessFactor=0.5533), - dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), - ) - LEXUS_RX_TSS2 = ToyotaTSS2PlatformConfig( - [ - ToyotaCarDocs("Lexus RX 2020-22"), - ToyotaCarDocs("Lexus RX Hybrid 2020-22"), - ], - LEXUS_RX.specs, - ) - LEXUS_GS_F = PlatformConfig( - [ToyotaCarDocs("Lexus GS F 2016")], - CarSpecs(mass=4034. * CV.LB_TO_KG, wheelbase=2.84988, steerRatio=13.3, tireStiffnessFactor=0.444), - dbc_dict('toyota_new_mc_pt_generated', 'toyota_adas'), - flags=ToyotaFlags.UNSUPPORTED_DSU, - ) - - -# (addr, cars, bus, 1/freq*100, vl) -STATIC_DSU_MSGS = [ - (0x128, (CAR.TOYOTA_PRIUS, CAR.TOYOTA_RAV4H, CAR.LEXUS_RX, CAR.LEXUS_NX, CAR.TOYOTA_RAV4, CAR.TOYOTA_COROLLA, CAR.TOYOTA_AVALON), \ - 1, 3, b'\xf4\x01\x90\x83\x00\x37'), - (0x128, (CAR.TOYOTA_HIGHLANDER, CAR.TOYOTA_SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES), 1, 3, b'\x03\x00\x20\x00\x00\x52'), - (0x141, (CAR.TOYOTA_PRIUS, CAR.TOYOTA_RAV4H, CAR.LEXUS_RX, CAR.LEXUS_NX, CAR.TOYOTA_RAV4, CAR.TOYOTA_COROLLA, CAR.TOYOTA_HIGHLANDER, CAR.TOYOTA_AVALON, - CAR.TOYOTA_SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES, CAR.TOYOTA_PRIUS_V), 1, 2, b'\x00\x00\x00\x46'), - (0x160, (CAR.TOYOTA_PRIUS, CAR.TOYOTA_RAV4H, CAR.LEXUS_RX, CAR.LEXUS_NX, CAR.TOYOTA_RAV4, CAR.TOYOTA_COROLLA, CAR.TOYOTA_HIGHLANDER, CAR.TOYOTA_AVALON, - CAR.TOYOTA_SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES, CAR.TOYOTA_PRIUS_V), 1, 7, b'\x00\x00\x08\x12\x01\x31\x9c\x51'), - (0x161, (CAR.TOYOTA_PRIUS, CAR.TOYOTA_RAV4H, CAR.LEXUS_RX, CAR.LEXUS_NX, CAR.TOYOTA_RAV4, CAR.TOYOTA_COROLLA, CAR.TOYOTA_AVALON, CAR.TOYOTA_PRIUS_V), - 1, 7, b'\x00\x1e\x00\x00\x00\x80\x07'), - (0X161, (CAR.TOYOTA_HIGHLANDER, CAR.TOYOTA_SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES), 1, 7, b'\x00\x1e\x00\xd4\x00\x00\x5b'), - (0x283, (CAR.TOYOTA_PRIUS, CAR.TOYOTA_RAV4H, CAR.LEXUS_RX, CAR.LEXUS_NX, CAR.TOYOTA_RAV4, CAR.TOYOTA_COROLLA, CAR.TOYOTA_HIGHLANDER, CAR.TOYOTA_AVALON, - CAR.TOYOTA_SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES, CAR.TOYOTA_PRIUS_V), 0, 3, b'\x00\x00\x00\x00\x00\x00\x8c'), - (0x2E6, (CAR.TOYOTA_PRIUS, CAR.TOYOTA_RAV4H, CAR.LEXUS_RX), 0, 3, b'\xff\xf8\x00\x08\x7f\xe0\x00\x4e'), - (0x2E7, (CAR.TOYOTA_PRIUS, CAR.TOYOTA_RAV4H, CAR.LEXUS_RX), 0, 3, b'\xa8\x9c\x31\x9c\x00\x00\x00\x02'), - (0x33E, (CAR.TOYOTA_PRIUS, CAR.TOYOTA_RAV4H, CAR.LEXUS_RX), 0, 20, b'\x0f\xff\x26\x40\x00\x1f\x00'), - (0x344, (CAR.TOYOTA_PRIUS, CAR.TOYOTA_RAV4H, CAR.LEXUS_RX, CAR.LEXUS_NX, CAR.TOYOTA_RAV4, CAR.TOYOTA_COROLLA, CAR.TOYOTA_HIGHLANDER, CAR.TOYOTA_AVALON, - CAR.TOYOTA_SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES, CAR.TOYOTA_PRIUS_V), 0, 5, b'\x00\x00\x01\x00\x00\x00\x00\x50'), - (0x365, (CAR.TOYOTA_PRIUS, CAR.LEXUS_NX, CAR.TOYOTA_HIGHLANDER), 0, 20, b'\x00\x00\x00\x80\x03\x00\x08'), - (0x365, (CAR.TOYOTA_RAV4, CAR.TOYOTA_RAV4H, CAR.TOYOTA_COROLLA, CAR.TOYOTA_AVALON, CAR.TOYOTA_SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES, CAR.LEXUS_RX, - CAR.TOYOTA_PRIUS_V), 0, 20, b'\x00\x00\x00\x80\xfc\x00\x08'), - (0x366, (CAR.TOYOTA_PRIUS, CAR.TOYOTA_RAV4H, CAR.LEXUS_RX, CAR.LEXUS_NX, CAR.TOYOTA_HIGHLANDER), 0, 20, b'\x00\x00\x4d\x82\x40\x02\x00'), - (0x366, (CAR.TOYOTA_RAV4, CAR.TOYOTA_COROLLA, CAR.TOYOTA_AVALON, CAR.TOYOTA_SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES, CAR.TOYOTA_PRIUS_V), - 0, 20, b'\x00\x72\x07\xff\x09\xfe\x00'), - (0x470, (CAR.TOYOTA_PRIUS, CAR.LEXUS_RX), 1, 100, b'\x00\x00\x02\x7a'), - (0x470, (CAR.TOYOTA_HIGHLANDER, CAR.TOYOTA_RAV4H, CAR.TOYOTA_SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES, CAR.TOYOTA_PRIUS_V), 1, 100, b'\x00\x00\x01\x79'), - (0x4CB, (CAR.TOYOTA_PRIUS, CAR.TOYOTA_RAV4H, CAR.LEXUS_RX, CAR.LEXUS_NX, CAR.TOYOTA_RAV4, CAR.TOYOTA_COROLLA, CAR.TOYOTA_HIGHLANDER, CAR.TOYOTA_AVALON, - CAR.TOYOTA_SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ES, CAR.TOYOTA_PRIUS_V), 0, 100, b'\x0c\x00\x00\x00\x00\x00\x00\x00'), -] - - -def get_platform_codes(fw_versions: list[bytes]) -> dict[bytes, set[bytes]]: - # Returns sub versions in a dict so comparisons can be made within part-platform-major_version combos - codes = defaultdict(set) # Optional[part]-platform-major_version: set of sub_version - for fw in fw_versions: - # FW versions returned from UDS queries can return multiple fields/chunks of data (different ECU calibrations, different data?) - # and are prefixed with a byte that describes how many chunks of data there are. - # But FW returned from KWP requires querying of each sub-data id and does not have a length prefix. - - length_code = 1 - length_code_match = FW_LEN_CODE.search(fw) - if length_code_match is not None: - length_code = length_code_match.group()[0] - fw = fw[1:] - - # fw length should be multiple of 16 bytes (per chunk, even if no length code), skip parsing if unexpected length - if length_code * FW_CHUNK_LEN != len(fw): - continue - - chunks = [fw[FW_CHUNK_LEN * i:FW_CHUNK_LEN * i + FW_CHUNK_LEN].strip(b'\x00 ') for i in range(length_code)] - - # only first is considered for now since second is commonly shared (TODO: understand that) - first_chunk = chunks[0] - if len(first_chunk) == 8: - # TODO: no part number, but some short chunks have it in subsequent chunks - fw_match = SHORT_FW_PATTERN.search(first_chunk) - if fw_match is not None: - platform, major_version, sub_version = fw_match.groups() - codes[b'-'.join((platform, major_version))].add(sub_version) - - elif len(first_chunk) == 10: - fw_match = MEDIUM_FW_PATTERN.search(first_chunk) - if fw_match is not None: - part, platform, major_version, sub_version = fw_match.groups() - codes[b'-'.join((part, platform, major_version))].add(sub_version) - - elif len(first_chunk) == 12: - fw_match = LONG_FW_PATTERN.search(first_chunk) - if fw_match is not None: - part, platform, major_version, sub_version = fw_match.groups() - codes[b'-'.join((part, platform, major_version))].add(sub_version) - - return dict(codes) - - -def match_fw_to_car_fuzzy(live_fw_versions, vin, offline_fw_versions) -> set[str]: - candidates = set() - - for candidate, fws in offline_fw_versions.items(): - # Keep track of ECUs which pass all checks (platform codes, within sub-version range) - valid_found_ecus = set() - valid_expected_ecus = {ecu[1:] for ecu in fws if ecu[0] in PLATFORM_CODE_ECUS} - for ecu, expected_versions in fws.items(): - addr = ecu[1:] - # Only check ECUs expected to have platform codes - if ecu[0] not in PLATFORM_CODE_ECUS: - continue - - # Expected platform codes & versions - expected_platform_codes = get_platform_codes(expected_versions) - - # Found platform codes & versions - found_platform_codes = get_platform_codes(live_fw_versions.get(addr, set())) - - # Check part number + platform code + major version matches for any found versions - # Platform codes and major versions change for different physical parts, generation, API, etc. - # Sub-versions are incremented for minor recalls, do not need to be checked. - if not any(found_platform_code in expected_platform_codes for found_platform_code in found_platform_codes): - break - - valid_found_ecus.add(addr) - - # If all live ECUs pass all checks for candidate, add it as a match - if valid_expected_ecus.issubset(valid_found_ecus): - candidates.add(candidate) - - return {str(c) for c in (candidates - FUZZY_EXCLUDED_PLATFORMS)} - - -# Regex patterns for parsing more general platform-specific identifiers from FW versions. -# - Part number: Toyota part number (usually last character needs to be ignored to find a match). -# Each ECU address has just one part number. -# - Platform: usually multiple codes per an openpilot platform, however this is the least variable and -# is usually shared across ECUs and model years signifying this describes something about the specific platform. -# This describes more generational changes (TSS-P vs TSS2), or manufacture region. -# - Major version: second least variable part of the FW version. Seen splitting cars by model year/API such as -# RAV4 2022/2023 and Avalon. Used to differentiate cars where API has changed slightly, but is not a generational change. -# It is important to note that these aren't always consecutive, for example: -# Avalon 2016-18's fwdCamera has these major versions: 01, 03 while 2019 has: 02 -# - Sub version: exclusive to major version, but shared with other cars. Should only be used for further filtering. -# Seen bumped in TSB FW updates, and describes other minor differences. -SHORT_FW_PATTERN = re.compile(b'[A-Z0-9](?P[A-Z0-9]{2})(?P[A-Z0-9]{2})(?P[A-Z0-9]{3})') -MEDIUM_FW_PATTERN = re.compile(b'(?P[A-Z0-9]{5})(?P[A-Z0-9]{2})(?P[A-Z0-9]{1})(?P[A-Z0-9]{2})') -LONG_FW_PATTERN = re.compile(b'(?P[A-Z0-9]{5})(?P[A-Z0-9]{2})(?P[A-Z0-9]{2})(?P[A-Z0-9]{3})') -FW_LEN_CODE = re.compile(b'^[\x01-\x03]') # highest seen is 3 chunks, 16 bytes each -FW_CHUNK_LEN = 16 - -# List of ECUs that are most unique across openpilot platforms -# - fwdCamera: describes actual features related to ADAS. For example, on the Avalon it describes -# when TSS-P became standard, whether the car supports stop and go, and whether it's TSS2. -# On the RAV4, it describes the move to the radar doing ACC, and the use of LTA for lane keeping. -# Note that the platform codes & major versions do not describe features in plain text, only with -# matching against other seen FW versions in the database they can describe features. -# - fwdRadar: sanity check against fwdCamera, commonly shares a platform code. -# For example the RAV4 2022's new radar architecture is shown for both with platform code. -# - abs: differentiates hybrid/ICE on most cars (Corolla TSS2 is an exception, not used due to hybrid platform combination) -# - eps: describes lateral API changes for the EPS, such as using LTA for lane keeping and rejecting LKA messages -PLATFORM_CODE_ECUS = (Ecu.fwdCamera, Ecu.fwdRadar, Ecu.eps) - -# These platforms have at least one platform code for all ECUs shared with another platform. -FUZZY_EXCLUDED_PLATFORMS: set[CAR] = set() - -# Some ECUs that use KWP2000 have their FW versions on non-standard data identifiers. -# Toyota diagnostic software first gets the supported data ids, then queries them one by one. -# For example, sends: 0x1a8800, receives: 0x1a8800010203, queries: 0x1a8801, 0x1a8802, 0x1a8803 -TOYOTA_VERSION_REQUEST_KWP = b'\x1a\x88\x01' -TOYOTA_VERSION_RESPONSE_KWP = b'\x5a\x88\x01' - -FW_QUERY_CONFIG = FwQueryConfig( - # TODO: look at data to whitelist new ECUs effectively - requests=[ - Request( - [StdQueries.SHORT_TESTER_PRESENT_REQUEST, TOYOTA_VERSION_REQUEST_KWP], - [StdQueries.SHORT_TESTER_PRESENT_RESPONSE, TOYOTA_VERSION_RESPONSE_KWP], - whitelist_ecus=[Ecu.fwdCamera, Ecu.fwdRadar, Ecu.dsu, Ecu.abs, Ecu.eps, Ecu.srs, Ecu.transmission, Ecu.hvac], - bus=0, - ), - Request( - [StdQueries.SHORT_TESTER_PRESENT_REQUEST, StdQueries.OBD_VERSION_REQUEST], - [StdQueries.SHORT_TESTER_PRESENT_RESPONSE, StdQueries.OBD_VERSION_RESPONSE], - whitelist_ecus=[Ecu.engine, Ecu.hybrid, Ecu.srs, Ecu.transmission, Ecu.hvac], - bus=0, - ), - Request( - [StdQueries.TESTER_PRESENT_REQUEST, StdQueries.DEFAULT_DIAGNOSTIC_REQUEST, StdQueries.EXTENDED_DIAGNOSTIC_REQUEST, StdQueries.UDS_VERSION_REQUEST], - [StdQueries.TESTER_PRESENT_RESPONSE, StdQueries.DEFAULT_DIAGNOSTIC_RESPONSE, StdQueries.EXTENDED_DIAGNOSTIC_RESPONSE, StdQueries.UDS_VERSION_RESPONSE], - whitelist_ecus=[Ecu.engine, Ecu.fwdRadar, Ecu.fwdCamera, Ecu.abs, Ecu.eps, - Ecu.hybrid, Ecu.srs, Ecu.transmission, Ecu.hvac], - bus=0, - ), - ], - non_essential_ecus={ - # FIXME: On some models, abs can sometimes be missing - Ecu.abs: [CAR.TOYOTA_RAV4, CAR.TOYOTA_COROLLA, CAR.TOYOTA_HIGHLANDER, CAR.TOYOTA_SIENNA, CAR.LEXUS_IS, CAR.TOYOTA_ALPHARD_TSS2], - # On some models, the engine can show on two different addresses - Ecu.engine: [CAR.TOYOTA_HIGHLANDER, CAR.TOYOTA_CAMRY, CAR.TOYOTA_COROLLA_TSS2, CAR.TOYOTA_CHR, CAR.TOYOTA_CHR_TSS2, CAR.LEXUS_IS, - CAR.LEXUS_IS_TSS2, CAR.LEXUS_RC, CAR.LEXUS_NX, CAR.LEXUS_NX_TSS2, CAR.LEXUS_RX, CAR.LEXUS_RX_TSS2], - }, - extra_ecus=[ - # All known ECUs on a late-model Toyota vehicle not queried here: - # Responds to UDS: - # - Combination Meter (0x7c0) - # - HV Battery (0x713, 0x747) - # - Motor Generator (0x716, 0x724) - # - 2nd ABS "Brake/EPB" (0x730) - # - Electronic Parking Brake ((0x750, 0x2c)) - # - Telematics ((0x750, 0xc7)) - # Responds to KWP (0x1a8801): - # - Steering Angle Sensor (0x7b3) - # - EPS/EMPS (0x7a0, 0x7a1) - # - 2nd SRS Airbag (0x784) - # - Central Gateway ((0x750, 0x5f)) - # - Telematics ((0x750, 0xc7)) - # Responds to KWP (0x1a8881): - # - Body Control Module ((0x750, 0x40)) - # - Telematics ((0x750, 0xc7)) - - # Hybrid control computer can be on 0x7e2 (KWP) or 0x7d2 (UDS) depending on platform - (Ecu.hybrid, 0x7e2, None), # Hybrid Control Assembly & Computer - (Ecu.srs, 0x780, None), # SRS Airbag - # Transmission is combined with engine on some platforms, such as TSS-P RAV4 - (Ecu.transmission, 0x701, None), - # A few platforms have a tester present response on this address, add to log - (Ecu.transmission, 0x7e1, None), - (Ecu.hvac, 0x7c4, None), - ], - match_fw_to_car_fuzzy=match_fw_to_car_fuzzy, -) - - -STEER_THRESHOLD = 100 - -# These cars have non-standard EPS torque scale factors. All others are 73 -EPS_SCALE = defaultdict(lambda: 73, - {CAR.TOYOTA_PRIUS: 66, CAR.TOYOTA_COROLLA: 88, CAR.LEXUS_IS: 77, CAR.LEXUS_RC: 77, CAR.LEXUS_CTH: 100, CAR.TOYOTA_PRIUS_V: 100}) - -# Toyota/Lexus Safety Sense 2.0 and 2.5 -TSS2_CAR = CAR.with_flags(ToyotaFlags.TSS2) - -NO_DSU_CAR = CAR.with_flags(ToyotaFlags.NO_DSU) - -# the DSU uses the AEB message for longitudinal on these cars -UNSUPPORTED_DSU_CAR = CAR.with_flags(ToyotaFlags.UNSUPPORTED_DSU) - -# these cars have a radar which sends ACC messages instead of the camera -RADAR_ACC_CAR = CAR.with_flags(ToyotaFlags.RADAR_ACC) - -ANGLE_CONTROL_CAR = CAR.with_flags(ToyotaFlags.ANGLE_CONTROL) - -# no resume button press required -NO_STOP_TIMER_CAR = CAR.with_flags(ToyotaFlags.NO_STOP_TIMER) - -DBC = CAR.create_dbc_map() diff --git a/car/volkswagen/__init__.py b/car/volkswagen/__init__.py deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/car/volkswagen/carcontroller.py b/car/volkswagen/carcontroller.py deleted file mode 100644 index a4e0c8946a..0000000000 --- a/car/volkswagen/carcontroller.py +++ /dev/null @@ -1,121 +0,0 @@ -from cereal import car -from opendbc.can.packer import CANPacker -from openpilot.common.numpy_fast import clip -from openpilot.common.conversions import Conversions as CV -from openpilot.common.realtime import DT_CTRL -from openpilot.selfdrive.car import apply_driver_steer_torque_limits -from openpilot.selfdrive.car.interfaces import CarControllerBase -from openpilot.selfdrive.car.volkswagen import mqbcan, pqcan -from openpilot.selfdrive.car.volkswagen.values import CANBUS, CarControllerParams, VolkswagenFlags - -VisualAlert = car.CarControl.HUDControl.VisualAlert -LongCtrlState = car.CarControl.Actuators.LongControlState - - -class CarController(CarControllerBase): - def __init__(self, dbc_name, CP, VM): - self.CP = CP - self.CCP = CarControllerParams(CP) - self.CCS = pqcan if CP.flags & VolkswagenFlags.PQ else mqbcan - self.packer_pt = CANPacker(dbc_name) - self.ext_bus = CANBUS.pt if CP.networkLocation == car.CarParams.NetworkLocation.fwdCamera else CANBUS.cam - - self.apply_steer_last = 0 - self.gra_acc_counter_last = None - self.frame = 0 - self.eps_timer_soft_disable_alert = False - self.hca_frame_timer_running = 0 - self.hca_frame_same_torque = 0 - - def update(self, CC, CS, now_nanos): - actuators = CC.actuators - hud_control = CC.hudControl - can_sends = [] - - # **** Steering Controls ************************************************ # - - if self.frame % self.CCP.STEER_STEP == 0: - # Logic to avoid HCA state 4 "refused": - # * Don't steer unless HCA is in state 3 "ready" or 5 "active" - # * Don't steer at standstill - # * Don't send > 3.00 Newton-meters torque - # * Don't send the same torque for > 6 seconds - # * Don't send uninterrupted steering for > 360 seconds - # MQB racks reset the uninterrupted steering timer after a single frame - # of HCA disabled; this is done whenever output happens to be zero. - - if CC.latActive: - new_steer = int(round(actuators.steer * self.CCP.STEER_MAX)) - apply_steer = apply_driver_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.CCP) - self.hca_frame_timer_running += self.CCP.STEER_STEP - if self.apply_steer_last == apply_steer: - self.hca_frame_same_torque += self.CCP.STEER_STEP - if self.hca_frame_same_torque > self.CCP.STEER_TIME_STUCK_TORQUE / DT_CTRL: - apply_steer -= (1, -1)[apply_steer < 0] - self.hca_frame_same_torque = 0 - else: - self.hca_frame_same_torque = 0 - hca_enabled = abs(apply_steer) > 0 - else: - hca_enabled = False - apply_steer = 0 - - if not hca_enabled: - self.hca_frame_timer_running = 0 - - self.eps_timer_soft_disable_alert = self.hca_frame_timer_running > self.CCP.STEER_TIME_ALERT / DT_CTRL - self.apply_steer_last = apply_steer - can_sends.append(self.CCS.create_steering_control(self.packer_pt, CANBUS.pt, apply_steer, hca_enabled)) - - if self.CP.flags & VolkswagenFlags.STOCK_HCA_PRESENT: - # Pacify VW Emergency Assist driver inactivity detection by changing its view of driver steering input torque - # to the greatest of actual driver input or 2x openpilot's output (1x openpilot output is not enough to - # consistently reset inactivity detection on straight level roads). See commaai/openpilot#23274 for background. - ea_simulated_torque = clip(apply_steer * 2, -self.CCP.STEER_MAX, self.CCP.STEER_MAX) - if abs(CS.out.steeringTorque) > abs(ea_simulated_torque): - ea_simulated_torque = CS.out.steeringTorque - can_sends.append(self.CCS.create_eps_update(self.packer_pt, CANBUS.cam, CS.eps_stock_values, ea_simulated_torque)) - - # **** Acceleration Controls ******************************************** # - - if self.frame % self.CCP.ACC_CONTROL_STEP == 0 and self.CP.openpilotLongitudinalControl: - acc_control = self.CCS.acc_control_value(CS.out.cruiseState.available, CS.out.accFaulted, CC.longActive) - accel = clip(actuators.accel, self.CCP.ACCEL_MIN, self.CCP.ACCEL_MAX) if CC.longActive else 0 - stopping = actuators.longControlState == LongCtrlState.stopping - starting = actuators.longControlState == LongCtrlState.pid and (CS.esp_hold_confirmation or CS.out.vEgo < self.CP.vEgoStopping) - can_sends.extend(self.CCS.create_acc_accel_control(self.packer_pt, CANBUS.pt, CS.acc_type, CC.longActive, accel, - acc_control, stopping, starting, CS.esp_hold_confirmation)) - - # **** HUD Controls ***************************************************** # - - if self.frame % self.CCP.LDW_STEP == 0: - hud_alert = 0 - if hud_control.visualAlert in (VisualAlert.steerRequired, VisualAlert.ldw): - hud_alert = self.CCP.LDW_MESSAGES["laneAssistTakeOver"] - can_sends.append(self.CCS.create_lka_hud_control(self.packer_pt, CANBUS.pt, CS.ldw_stock_values, CC.latActive, - CS.out.steeringPressed, hud_alert, hud_control)) - - if self.frame % self.CCP.ACC_HUD_STEP == 0 and self.CP.openpilotLongitudinalControl: - lead_distance = 0 - if hud_control.leadVisible and self.frame * DT_CTRL > 1.0: # Don't display lead until we know the scaling factor - lead_distance = 512 if CS.upscale_lead_car_signal else 8 - acc_hud_status = self.CCS.acc_hud_status_value(CS.out.cruiseState.available, CS.out.accFaulted, CC.longActive) - # FIXME: follow the recent displayed-speed updates, also use mph_kmh toggle to fix display rounding problem? - set_speed = hud_control.setSpeed * CV.MS_TO_KPH - can_sends.append(self.CCS.create_acc_hud_control(self.packer_pt, CANBUS.pt, acc_hud_status, set_speed, - lead_distance, hud_control.leadDistanceBars)) - - # **** Stock ACC Button Controls **************************************** # - - gra_send_ready = self.CP.pcmCruise and CS.gra_stock_values["COUNTER"] != self.gra_acc_counter_last - if gra_send_ready and (CC.cruiseControl.cancel or CC.cruiseControl.resume): - can_sends.append(self.CCS.create_acc_buttons_control(self.packer_pt, self.ext_bus, CS.gra_stock_values, - cancel=CC.cruiseControl.cancel, resume=CC.cruiseControl.resume)) - - new_actuators = actuators.as_builder() - new_actuators.steer = self.apply_steer_last / self.CCP.STEER_MAX - new_actuators.steerOutputCan = self.apply_steer_last - - self.gra_acc_counter_last = CS.gra_stock_values["COUNTER"] - self.frame += 1 - return new_actuators, can_sends diff --git a/car/volkswagen/carstate.py b/car/volkswagen/carstate.py deleted file mode 100644 index ec6403496f..0000000000 --- a/car/volkswagen/carstate.py +++ /dev/null @@ -1,398 +0,0 @@ -import numpy as np -from cereal import car -from openpilot.common.conversions import Conversions as CV -from openpilot.selfdrive.car.interfaces import CarStateBase -from opendbc.can.parser import CANParser -from openpilot.selfdrive.car.volkswagen.values import DBC, CANBUS, NetworkLocation, TransmissionType, GearShifter, \ - CarControllerParams, VolkswagenFlags - - -class CarState(CarStateBase): - def __init__(self, CP): - super().__init__(CP) - self.frame = 0 - self.eps_init_complete = False - self.CCP = CarControllerParams(CP) - self.button_states = {button.event_type: False for button in self.CCP.BUTTONS} - self.esp_hold_confirmation = False - self.upscale_lead_car_signal = False - self.eps_stock_values = False - - def create_button_events(self, pt_cp, buttons): - button_events = [] - - for button in buttons: - state = pt_cp.vl[button.can_addr][button.can_msg] in button.values - if self.button_states[button.event_type] != state: - event = car.CarState.ButtonEvent.new_message() - event.type = button.event_type - event.pressed = state - button_events.append(event) - self.button_states[button.event_type] = state - - return button_events - - def update(self, pt_cp, cam_cp, ext_cp, trans_type): - if self.CP.flags & VolkswagenFlags.PQ: - return self.update_pq(pt_cp, cam_cp, ext_cp, trans_type) - - ret = car.CarState.new_message() - # Update vehicle speed and acceleration from ABS wheel speeds. - ret.wheelSpeeds = self.get_wheel_speeds( - pt_cp.vl["ESP_19"]["ESP_VL_Radgeschw_02"], - pt_cp.vl["ESP_19"]["ESP_VR_Radgeschw_02"], - pt_cp.vl["ESP_19"]["ESP_HL_Radgeschw_02"], - pt_cp.vl["ESP_19"]["ESP_HR_Radgeschw_02"], - ) - - ret.vEgoRaw = float(np.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 - - # Update EPS position and state info. For signed values, VW sends the sign in a separate signal. - ret.steeringAngleDeg = pt_cp.vl["LWI_01"]["LWI_Lenkradwinkel"] * (1, -1)[int(pt_cp.vl["LWI_01"]["LWI_VZ_Lenkradwinkel"])] - ret.steeringRateDeg = pt_cp.vl["LWI_01"]["LWI_Lenkradw_Geschw"] * (1, -1)[int(pt_cp.vl["LWI_01"]["LWI_VZ_Lenkradw_Geschw"])] - ret.steeringTorque = pt_cp.vl["LH_EPS_03"]["EPS_Lenkmoment"] * (1, -1)[int(pt_cp.vl["LH_EPS_03"]["EPS_VZ_Lenkmoment"])] - ret.steeringPressed = abs(ret.steeringTorque) > self.CCP.STEER_DRIVER_ALLOWANCE - ret.yawRate = pt_cp.vl["ESP_02"]["ESP_Gierrate"] * (1, -1)[int(pt_cp.vl["ESP_02"]["ESP_VZ_Gierrate"])] * CV.DEG_TO_RAD - hca_status = self.CCP.hca_status_values.get(pt_cp.vl["LH_EPS_03"]["EPS_HCA_Status"]) - ret.steerFaultTemporary, ret.steerFaultPermanent = self.update_hca_state(hca_status) - - # VW Emergency Assist status tracking and mitigation - self.eps_stock_values = pt_cp.vl["LH_EPS_03"] - if self.CP.flags & VolkswagenFlags.STOCK_HCA_PRESENT: - ret.carFaultedNonCritical = bool(cam_cp.vl["HCA_01"]["EA_Ruckfreigabe"]) or cam_cp.vl["HCA_01"]["EA_ACC_Sollstatus"] > 0 - - # Update gas, brakes, and gearshift. - ret.gas = pt_cp.vl["Motor_20"]["MO_Fahrpedalrohwert_01"] / 100.0 - ret.gasPressed = ret.gas > 0 - ret.brake = pt_cp.vl["ESP_05"]["ESP_Bremsdruck"] / 250.0 # FIXME: this is pressure in Bar, not sure what OP expects - brake_pedal_pressed = bool(pt_cp.vl["Motor_14"]["MO_Fahrer_bremst"]) - brake_pressure_detected = bool(pt_cp.vl["ESP_05"]["ESP_Fahrer_bremst"]) - ret.brakePressed = brake_pedal_pressed or brake_pressure_detected - ret.parkingBrake = bool(pt_cp.vl["Kombi_01"]["KBI_Handbremse"]) # FIXME: need to include an EPB check as well - - # Update gear and/or clutch position data. - if trans_type == TransmissionType.automatic: - ret.gearShifter = self.parse_gear_shifter(self.CCP.shifter_values.get(pt_cp.vl["Getriebe_11"]["GE_Fahrstufe"], None)) - elif trans_type == TransmissionType.direct: - ret.gearShifter = self.parse_gear_shifter(self.CCP.shifter_values.get(pt_cp.vl["EV_Gearshift"]["GearPosition"], None)) - elif trans_type == TransmissionType.manual: - ret.clutchPressed = not pt_cp.vl["Motor_14"]["MO_Kuppl_schalter"] - if bool(pt_cp.vl["Gateway_72"]["BCM1_Rueckfahrlicht_Schalter"]): - ret.gearShifter = GearShifter.reverse - else: - ret.gearShifter = GearShifter.drive - - # Update door and trunk/hatch lid open status. - ret.doorOpen = any([pt_cp.vl["Gateway_72"]["ZV_FT_offen"], - pt_cp.vl["Gateway_72"]["ZV_BT_offen"], - pt_cp.vl["Gateway_72"]["ZV_HFS_offen"], - pt_cp.vl["Gateway_72"]["ZV_HBFS_offen"], - pt_cp.vl["Gateway_72"]["ZV_HD_offen"]]) - - # Update seatbelt fastened status. - ret.seatbeltUnlatched = pt_cp.vl["Airbag_02"]["AB_Gurtschloss_FA"] != 3 - - # Consume blind-spot monitoring info/warning LED states, if available. - # Infostufe: BSM LED on, Warnung: BSM LED flashing - if self.CP.enableBsm: - ret.leftBlindspot = bool(ext_cp.vl["SWA_01"]["SWA_Infostufe_SWA_li"]) or bool(ext_cp.vl["SWA_01"]["SWA_Warnung_SWA_li"]) - ret.rightBlindspot = bool(ext_cp.vl["SWA_01"]["SWA_Infostufe_SWA_re"]) or bool(ext_cp.vl["SWA_01"]["SWA_Warnung_SWA_re"]) - - # Consume factory LDW data relevant for factory SWA (Lane Change Assist) - # and capture it for forwarding to the blind spot radar controller - self.ldw_stock_values = cam_cp.vl["LDW_02"] if self.CP.networkLocation == NetworkLocation.fwdCamera else {} - - # Stock FCW is considered active if the release bit for brake-jerk warning - # is set. Stock AEB considered active if the partial braking or target - # braking release bits are set. - # Refer to VW Self Study Program 890253: Volkswagen Driver Assistance - # Systems, chapter on Front Assist with Braking: Golf Family for all MQB - ret.stockFcw = bool(ext_cp.vl["ACC_10"]["AWV2_Freigabe"]) - ret.stockAeb = bool(ext_cp.vl["ACC_10"]["ANB_Teilbremsung_Freigabe"]) or bool(ext_cp.vl["ACC_10"]["ANB_Zielbremsung_Freigabe"]) - - # Update ACC radar status. - self.acc_type = ext_cp.vl["ACC_06"]["ACC_Typ"] - - # ACC okay but disabled (1), ACC ready (2), a radar visibility or other fault/disruption (6 or 7) - # currently regulating speed (3), driver accel override (4), brake only (5) - ret.cruiseState.available = pt_cp.vl["TSK_06"]["TSK_Status"] in (2, 3, 4, 5) - ret.cruiseState.enabled = pt_cp.vl["TSK_06"]["TSK_Status"] in (3, 4, 5) - - if self.CP.pcmCruise: - # Cruise Control mode; check for distance UI setting from the radar. - # ECM does not manage this, so do not need to check for openpilot longitudinal - ret.cruiseState.nonAdaptive = ext_cp.vl["ACC_02"]["ACC_Gesetzte_Zeitluecke"] == 0 - else: - # Speed limiter mode; ECM faults if we command ACC while not pcmCruise - ret.cruiseState.nonAdaptive = bool(pt_cp.vl["TSK_06"]["TSK_Limiter_ausgewaehlt"]) - - ret.accFaulted = pt_cp.vl["TSK_06"]["TSK_Status"] in (6, 7) - - self.esp_hold_confirmation = bool(pt_cp.vl["ESP_21"]["ESP_Haltebestaetigung"]) - ret.cruiseState.standstill = self.CP.pcmCruise and self.esp_hold_confirmation - - # Update ACC setpoint. When the setpoint is zero or there's an error, the - # radar sends a set-speed of ~90.69 m/s / 203mph. - if self.CP.pcmCruise: - ret.cruiseState.speed = ext_cp.vl["ACC_02"]["ACC_Wunschgeschw_02"] * CV.KPH_TO_MS - if ret.cruiseState.speed > 90: - ret.cruiseState.speed = 0 - - # Update button states for turn signals and ACC controls, capture all ACC button state/config for passthrough - ret.leftBlinker = bool(pt_cp.vl["Blinkmodi_02"]["Comfort_Signal_Left"]) - ret.rightBlinker = bool(pt_cp.vl["Blinkmodi_02"]["Comfort_Signal_Right"]) - ret.buttonEvents = self.create_button_events(pt_cp, self.CCP.BUTTONS) - self.gra_stock_values = pt_cp.vl["GRA_ACC_01"] - - # Additional safety checks performed in CarInterface. - ret.espDisabled = pt_cp.vl["ESP_21"]["ESP_Tastung_passiv"] != 0 - - # Digital instrument clusters expect the ACC HUD lead car distance to be scaled differently - self.upscale_lead_car_signal = bool(pt_cp.vl["Kombi_03"]["KBI_Variante"]) - - self.frame += 1 - return ret - - def update_pq(self, pt_cp, cam_cp, ext_cp, trans_type): - ret = car.CarState.new_message() - # Update vehicle speed and acceleration from ABS wheel speeds. - ret.wheelSpeeds = self.get_wheel_speeds( - pt_cp.vl["Bremse_3"]["Radgeschw__VL_4_1"], - pt_cp.vl["Bremse_3"]["Radgeschw__VR_4_1"], - pt_cp.vl["Bremse_3"]["Radgeschw__HL_4_1"], - pt_cp.vl["Bremse_3"]["Radgeschw__HR_4_1"], - ) - - # vEgo obtained from Bremse_1 vehicle speed rather than Bremse_3 wheel speeds because Bremse_3 isn't present on NSF - ret.vEgoRaw = pt_cp.vl["Bremse_1"]["Geschwindigkeit_neu__Bremse_1_"] * CV.KPH_TO_MS - ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) - ret.standstill = ret.vEgoRaw == 0 - - # Update EPS position and state info. For signed values, VW sends the sign in a separate signal. - ret.steeringAngleDeg = pt_cp.vl["Lenkhilfe_3"]["LH3_BLW"] * (1, -1)[int(pt_cp.vl["Lenkhilfe_3"]["LH3_BLWSign"])] - ret.steeringRateDeg = pt_cp.vl["Lenkwinkel_1"]["Lenkradwinkel_Geschwindigkeit"] * (1, -1)[int(pt_cp.vl["Lenkwinkel_1"]["Lenkradwinkel_Geschwindigkeit_S"])] - ret.steeringTorque = pt_cp.vl["Lenkhilfe_3"]["LH3_LM"] * (1, -1)[int(pt_cp.vl["Lenkhilfe_3"]["LH3_LMSign"])] - ret.steeringPressed = abs(ret.steeringTorque) > self.CCP.STEER_DRIVER_ALLOWANCE - ret.yawRate = pt_cp.vl["Bremse_5"]["Giergeschwindigkeit"] * (1, -1)[int(pt_cp.vl["Bremse_5"]["Vorzeichen_der_Giergeschwindigk"])] * CV.DEG_TO_RAD - hca_status = self.CCP.hca_status_values.get(pt_cp.vl["Lenkhilfe_2"]["LH2_Sta_HCA"]) - ret.steerFaultTemporary, ret.steerFaultPermanent = self.update_hca_state(hca_status) - - # Update gas, brakes, and gearshift. - ret.gas = pt_cp.vl["Motor_3"]["Fahrpedal_Rohsignal"] / 100.0 - ret.gasPressed = ret.gas > 0 - ret.brake = pt_cp.vl["Bremse_5"]["Bremsdruck"] / 250.0 # FIXME: this is pressure in Bar, not sure what OP expects - ret.brakePressed = bool(pt_cp.vl["Motor_2"]["Bremslichtschalter"]) - ret.parkingBrake = bool(pt_cp.vl["Kombi_1"]["Bremsinfo"]) - - # Update gear and/or clutch position data. - if trans_type == TransmissionType.automatic: - ret.gearShifter = self.parse_gear_shifter(self.CCP.shifter_values.get(pt_cp.vl["Getriebe_1"]["Waehlhebelposition__Getriebe_1_"], None)) - elif trans_type == TransmissionType.manual: - ret.clutchPressed = not pt_cp.vl["Motor_1"]["Kupplungsschalter"] - reverse_light = bool(pt_cp.vl["Gate_Komf_1"]["GK1_Rueckfahr"]) - if reverse_light: - ret.gearShifter = GearShifter.reverse - else: - ret.gearShifter = GearShifter.drive - - # Update door and trunk/hatch lid open status. - ret.doorOpen = any([pt_cp.vl["Gate_Komf_1"]["GK1_Fa_Tuerkont"], - pt_cp.vl["Gate_Komf_1"]["BSK_BT_geoeffnet"], - pt_cp.vl["Gate_Komf_1"]["BSK_HL_geoeffnet"], - pt_cp.vl["Gate_Komf_1"]["BSK_HR_geoeffnet"], - pt_cp.vl["Gate_Komf_1"]["BSK_HD_Hauptraste"]]) - - # Update seatbelt fastened status. - ret.seatbeltUnlatched = not bool(pt_cp.vl["Airbag_1"]["Gurtschalter_Fahrer"]) - - # Consume blind-spot monitoring info/warning LED states, if available. - # Infostufe: BSM LED on, Warnung: BSM LED flashing - if self.CP.enableBsm: - ret.leftBlindspot = bool(ext_cp.vl["SWA_1"]["SWA_Infostufe_SWA_li"]) or bool(ext_cp.vl["SWA_1"]["SWA_Warnung_SWA_li"]) - ret.rightBlindspot = bool(ext_cp.vl["SWA_1"]["SWA_Infostufe_SWA_re"]) or bool(ext_cp.vl["SWA_1"]["SWA_Warnung_SWA_re"]) - - # Consume factory LDW data relevant for factory SWA (Lane Change Assist) - # and capture it for forwarding to the blind spot radar controller - self.ldw_stock_values = cam_cp.vl["LDW_Status"] if self.CP.networkLocation == NetworkLocation.fwdCamera else {} - - # Stock FCW is considered active if the release bit for brake-jerk warning - # is set. Stock AEB considered active if the partial braking or target - # braking release bits are set. - # Refer to VW Self Study Program 890253: Volkswagen Driver Assistance - # Systems, chapters on Front Assist with Braking and City Emergency - # Braking for the 2016 Passat NMS - # TODO: deferred until we can collect data on pre-MY2016 behavior, AWV message may be shorter with fewer signals - ret.stockFcw = False - ret.stockAeb = False - - # Update ACC radar status. - self.acc_type = ext_cp.vl["ACC_System"]["ACS_Typ_ACC"] - ret.cruiseState.available = bool(pt_cp.vl["Motor_5"]["GRA_Hauptschalter"]) - ret.cruiseState.enabled = pt_cp.vl["Motor_2"]["GRA_Status"] in (1, 2) - if self.CP.pcmCruise: - ret.accFaulted = ext_cp.vl["ACC_GRA_Anzeige"]["ACA_StaACC"] in (6, 7) - else: - ret.accFaulted = pt_cp.vl["Motor_2"]["GRA_Status"] == 3 - - # Update ACC setpoint. When the setpoint reads as 255, the driver has not - # yet established an ACC setpoint, so treat it as zero. - ret.cruiseState.speed = ext_cp.vl["ACC_GRA_Anzeige"]["ACA_V_Wunsch"] * CV.KPH_TO_MS - if ret.cruiseState.speed > 70: # 255 kph in m/s == no current setpoint - ret.cruiseState.speed = 0 - - # Update button states for turn signals and ACC controls, capture all ACC button state/config for passthrough - ret.leftBlinker, ret.rightBlinker = self.update_blinker_from_stalk(300, pt_cp.vl["Gate_Komf_1"]["GK1_Blinker_li"], - pt_cp.vl["Gate_Komf_1"]["GK1_Blinker_re"]) - ret.buttonEvents = self.create_button_events(pt_cp, self.CCP.BUTTONS) - self.gra_stock_values = pt_cp.vl["GRA_Neu"] - - # Additional safety checks performed in CarInterface. - ret.espDisabled = bool(pt_cp.vl["Bremse_1"]["ESP_Passiv_getastet"]) - - self.frame += 1 - return ret - - def update_hca_state(self, hca_status): - # Treat INITIALIZING and FAULT as temporary for worst likely EPS recovery time, for cars without factory Lane Assist - # DISABLED means the EPS hasn't been configured to support Lane Assist - self.eps_init_complete = self.eps_init_complete or (hca_status in ("DISABLED", "READY", "ACTIVE") or self.frame > 600) - perm_fault = hca_status == "DISABLED" or (self.eps_init_complete and hca_status in ("INITIALIZING", "FAULT")) - temp_fault = hca_status in ("REJECTED", "PREEMPTED") or not self.eps_init_complete - return temp_fault, perm_fault - - @staticmethod - def get_can_parser(CP): - if CP.flags & VolkswagenFlags.PQ: - return CarState.get_can_parser_pq(CP) - - messages = [ - # sig_address, frequency - ("LWI_01", 100), # From J500 Steering Assist with integrated sensors - ("LH_EPS_03", 100), # From J500 Steering Assist with integrated sensors - ("ESP_19", 100), # From J104 ABS/ESP controller - ("ESP_05", 50), # From J104 ABS/ESP controller - ("ESP_21", 50), # From J104 ABS/ESP controller - ("Motor_20", 50), # From J623 Engine control module - ("TSK_06", 50), # From J623 Engine control module - ("ESP_02", 50), # From J104 ABS/ESP controller - ("GRA_ACC_01", 33), # From J533 CAN gateway (via LIN from steering wheel controls) - ("Gateway_72", 10), # From J533 CAN gateway (aggregated data) - ("Motor_14", 10), # From J623 Engine control module - ("Airbag_02", 5), # From J234 Airbag control module - ("Kombi_01", 2), # From J285 Instrument cluster - ("Blinkmodi_02", 1), # From J519 BCM (sent at 1Hz when no lights active, 50Hz when active) - ("Kombi_03", 0), # From J285 instrument cluster (not present on older cars, 1Hz when present) - ] - - if CP.transmissionType == TransmissionType.automatic: - messages.append(("Getriebe_11", 20)) # From J743 Auto transmission control module - elif CP.transmissionType == TransmissionType.direct: - messages.append(("EV_Gearshift", 10)) # From J??? unknown EV control module - - if CP.networkLocation == NetworkLocation.fwdCamera: - # Radars are here on CANBUS.pt - messages += MqbExtraSignals.fwd_radar_messages - if CP.enableBsm: - messages += MqbExtraSignals.bsm_radar_messages - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, CANBUS.pt) - - @staticmethod - def get_cam_can_parser(CP): - if CP.flags & VolkswagenFlags.PQ: - return CarState.get_cam_can_parser_pq(CP) - - messages = [] - - if CP.flags & VolkswagenFlags.STOCK_HCA_PRESENT: - messages += [ - ("HCA_01", 1), # From R242 Driver assistance camera, 50Hz if steering/1Hz if not - ] - - if CP.networkLocation == NetworkLocation.fwdCamera: - messages += [ - # sig_address, frequency - ("LDW_02", 10) # From R242 Driver assistance camera - ] - else: - # Radars are here on CANBUS.cam - messages += MqbExtraSignals.fwd_radar_messages - if CP.enableBsm: - messages += MqbExtraSignals.bsm_radar_messages - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, CANBUS.cam) - - @staticmethod - def get_can_parser_pq(CP): - messages = [ - # sig_address, frequency - ("Bremse_1", 100), # From J104 ABS/ESP controller - ("Bremse_3", 100), # From J104 ABS/ESP controller - ("Lenkhilfe_3", 100), # From J500 Steering Assist with integrated sensors - ("Lenkwinkel_1", 100), # From J500 Steering Assist with integrated sensors - ("Motor_3", 100), # From J623 Engine control module - ("Airbag_1", 50), # From J234 Airbag control module - ("Bremse_5", 50), # From J104 ABS/ESP controller - ("GRA_Neu", 50), # From J??? steering wheel control buttons - ("Kombi_1", 50), # From J285 Instrument cluster - ("Motor_2", 50), # From J623 Engine control module - ("Motor_5", 50), # From J623 Engine control module - ("Lenkhilfe_2", 20), # From J500 Steering Assist with integrated sensors - ("Gate_Komf_1", 10), # From J533 CAN gateway - ] - - if CP.transmissionType == TransmissionType.automatic: - messages += [("Getriebe_1", 100)] # From J743 Auto transmission control module - elif CP.transmissionType == TransmissionType.manual: - messages += [("Motor_1", 100)] # From J623 Engine control module - - if CP.networkLocation == NetworkLocation.fwdCamera: - # Extended CAN devices other than the camera are here on CANBUS.pt - messages += PqExtraSignals.fwd_radar_messages - if CP.enableBsm: - messages += PqExtraSignals.bsm_radar_messages - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, CANBUS.pt) - - @staticmethod - def get_cam_can_parser_pq(CP): - - messages = [] - - if CP.networkLocation == NetworkLocation.fwdCamera: - messages += [ - # sig_address, frequency - ("LDW_Status", 10) # From R242 Driver assistance camera - ] - - if CP.networkLocation == NetworkLocation.gateway: - # Radars are here on CANBUS.cam - messages += PqExtraSignals.fwd_radar_messages - if CP.enableBsm: - messages += PqExtraSignals.bsm_radar_messages - - return CANParser(DBC[CP.carFingerprint]["pt"], messages, CANBUS.cam) - - -class MqbExtraSignals: - # Additional signal and message lists for optional or bus-portable controllers - fwd_radar_messages = [ - ("ACC_06", 50), # From J428 ACC radar control module - ("ACC_10", 50), # From J428 ACC radar control module - ("ACC_02", 17), # From J428 ACC radar control module - ] - bsm_radar_messages = [ - ("SWA_01", 20), # From J1086 Lane Change Assist - ] - -class PqExtraSignals: - # Additional signal and message lists for optional or bus-portable controllers - fwd_radar_messages = [ - ("ACC_System", 50), # From J428 ACC radar control module - ("ACC_GRA_Anzeige", 25), # From J428 ACC radar control module - ] - bsm_radar_messages = [ - ("SWA_1", 20), # From J1086 Lane Change Assist - ] diff --git a/car/volkswagen/fingerprints.py b/car/volkswagen/fingerprints.py deleted file mode 100644 index fdc375fc8d..0000000000 --- a/car/volkswagen/fingerprints.py +++ /dev/null @@ -1,1201 +0,0 @@ -from cereal import car -from openpilot.selfdrive.car.volkswagen.values import CAR - -Ecu = car.CarParams.Ecu - -# TODO: Sharan Mk2 EPS and DQ250 auto trans both require KWP2000 support for fingerprinting - - -FW_VERSIONS = { - CAR.VOLKSWAGEN_ARTEON_MK1: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x873G0906259AH\xf1\x890001', - b'\xf1\x873G0906259F \xf1\x890004', - b'\xf1\x873G0906259G \xf1\x890004', - b'\xf1\x873G0906259G \xf1\x890005', - b'\xf1\x873G0906259M \xf1\x890003', - b'\xf1\x873G0906259N \xf1\x890004', - b'\xf1\x873G0906259P \xf1\x890001', - b'\xf1\x875NA907115H \xf1\x890002', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x8709G927158L \xf1\x893611', - b'\xf1\x870DL300014C \xf1\x893704', - b'\xf1\x870GC300011L \xf1\x891401', - b'\xf1\x870GC300014M \xf1\x892802', - b'\xf1\x870GC300019G \xf1\x892804', - b'\xf1\x870GC300040P \xf1\x891401', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x873Q0959655BK\xf1\x890703\xf1\x82\x0e1616001613121157161111572900', - b'\xf1\x873Q0959655BK\xf1\x890703\xf1\x82\x0e1616001613121177161113772900', - b'\xf1\x873Q0959655CK\xf1\x890711\xf1\x82\x0e1712141712141105121122052900', - b'\xf1\x873Q0959655DA\xf1\x890720\xf1\x82\x0e1712141712141105121122052900', - b'\xf1\x873Q0959655DL\xf1\x890732\xf1\x82\x0e1812141812171105141123052J00', - b'\xf1\x875QF959655AP\xf1\x890755\xf1\x82\x1311110011111311111100110200--1611125F49', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571B41815A1', - b'\xf1\x873Q0909144L \xf1\x895081\xf1\x82\x0571B00817A1', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567B0020800', - b'\xf1\x875WA907145M \xf1\x891051\xf1\x82\x002MB4092M7N', - b'\xf1\x875WA907145M \xf1\x891051\xf1\x82\x002NB4202N7N', - b'\xf1\x875WA907145Q \xf1\x891063\xf1\x82\x002KB4092KOM', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x872Q0907572T \xf1\x890383', - b'\xf1\x875Q0907572J \xf1\x890654', - b'\xf1\x875Q0907572R \xf1\x890771', - ], - }, - CAR.VOLKSWAGEN_ATLAS_MK1: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8703H906026AA\xf1\x899970', - b'\xf1\x8703H906026AG\xf1\x899973', - b'\xf1\x8703H906026AJ\xf1\x890638', - b'\xf1\x8703H906026AJ\xf1\x891017', - b'\xf1\x8703H906026AT\xf1\x891922', - b'\xf1\x8703H906026BC\xf1\x892664', - b'\xf1\x8703H906026F \xf1\x896696', - b'\xf1\x8703H906026F \xf1\x899970', - b'\xf1\x8703H906026J \xf1\x896026', - b'\xf1\x8703H906026J \xf1\x899970', - b'\xf1\x8703H906026J \xf1\x899971', - b'\xf1\x8703H906026S \xf1\x896693', - b'\xf1\x8703H906026S \xf1\x899970', - b'\xf1\x873CN906259 \xf1\x890005', - b'\xf1\x873CN906259F \xf1\x890002', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x8709G927158A \xf1\x893387', - b'\xf1\x8709G927158DR\xf1\x893536', - b'\xf1\x8709G927158DR\xf1\x893742', - b'\xf1\x8709G927158EN\xf1\x893691', - b'\xf1\x8709G927158F \xf1\x893489', - b'\xf1\x8709G927158FT\xf1\x893835', - b'\xf1\x8709G927158GL\xf1\x893939', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x873Q0959655BC\xf1\x890503\xf1\x82\x0e1914151912001103111122031200', - b'\xf1\x873Q0959655BN\xf1\x890713\xf1\x82\x0e2214152212001105141122052900', - b'\xf1\x873Q0959655DB\xf1\x890720\xf1\x82\x0e1114151112001105111122052900', - b'\xf1\x873Q0959655DB\xf1\x890720\xf1\x82\x0e2214152212001105141122052900', - b'\xf1\x873Q0959655DM\xf1\x890732\xf1\x82\x0e1114151112001105111122052J00', - b'\xf1\x873Q0959655DM\xf1\x890732\xf1\x82\x0e1114151112001105161122052J00', - b'\xf1\x873Q0959655DM\xf1\x890732\xf1\x82\x0e1115151112001105171122052J00', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x873QF909144B \xf1\x891582\xf1\x82\x0571B60924A1', - b'\xf1\x873QF909144B \xf1\x891582\xf1\x82\x0571B6G920A1', - b'\xf1\x873QF909144B \xf1\x891582\xf1\x82\x0571B6M921A1', - b'\xf1\x873QF909144B \xf1\x891582\xf1\x82\x0571B6N920A1', - b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820528B6080105', - b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820528B6090105', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x872Q0907572R \xf1\x890372', - b'\xf1\x872Q0907572T \xf1\x890383', - b'\xf1\x875Q0907572H \xf1\x890620', - b'\xf1\x875Q0907572J \xf1\x890654', - b'\xf1\x875Q0907572P \xf1\x890682', - b'\xf1\x875Q0907572S \xf1\x890780', - ], - }, - CAR.VOLKSWAGEN_CADDY_MK3: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704E906027T \xf1\x892363', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x872K5959655E \xf1\x890018\xf1\x82\x05000P037605', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x877N0907572C \xf1\x890211\xf1\x82\x0155', - ], - }, - CAR.VOLKSWAGEN_CRAFTER_MK2: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704L906056BP\xf1\x894729', - b'\xf1\x8704L906056EK\xf1\x896391', - b'\xf1\x8705L906023BC\xf1\x892688', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x873Q0959655AL\xf1\x890505\xf1\x82\x0e1411001413001203151311031100', - b'\xf1\x873Q0959655BG\xf1\x890703\xf1\x82\x0e16120016130012051G1313052900', - b'\xf1\x875QF959655AS\xf1\x890755\xf1\x82\x1315140015150011111100050200--1311120749', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x872N0909143D\x00\xf1\x897010\xf1\x82\x05183AZ306A2', - b'\xf1\x872N0909143E \xf1\x897021\xf1\x82\x05163AZ306A2', - b'\xf1\x872N0909144K \xf1\x897045\xf1\x82\x05233AZ810A2', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x872Q0907572J \xf1\x890156', - b'\xf1\x872Q0907572M \xf1\x890233', - ], - }, - CAR.VOLKSWAGEN_GOLF_MK7: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704E906016A \xf1\x897697', - b'\xf1\x8704E906016AD\xf1\x895758', - b'\xf1\x8704E906016CE\xf1\x899096', - b'\xf1\x8704E906016CH\xf1\x899226', - b'\xf1\x8704E906016N \xf1\x899105', - b'\xf1\x8704E906023AG\xf1\x891726', - b'\xf1\x8704E906023BN\xf1\x894518', - b'\xf1\x8704E906024K \xf1\x896811', - b'\xf1\x8704E906024K \xf1\x899970', - b'\xf1\x8704E906027GR\xf1\x892394', - b'\xf1\x8704E906027HD\xf1\x892603', - b'\xf1\x8704E906027HD\xf1\x893742', - b'\xf1\x8704E906027MA\xf1\x894958', - b'\xf1\x8704L906021DT\xf1\x895520', - b'\xf1\x8704L906021DT\xf1\x898127', - b'\xf1\x8704L906021N \xf1\x895518', - b'\xf1\x8704L906021N \xf1\x898138', - b'\xf1\x8704L906026BN\xf1\x891197', - b'\xf1\x8704L906026BP\xf1\x897608', - b'\xf1\x8704L906026NF\xf1\x899528', - b'\xf1\x8704L906056CL\xf1\x893823', - b'\xf1\x8704L906056CR\xf1\x895813', - b'\xf1\x8704L906056HE\xf1\x893758', - b'\xf1\x8704L906056HN\xf1\x896590', - b'\xf1\x8704L906056HT\xf1\x896591', - b'\xf1\x8704L997022N \xf1\x899459', - b'\xf1\x870EA906016A \xf1\x898343', - b'\xf1\x870EA906016E \xf1\x894219', - b'\xf1\x870EA906016F \xf1\x894238', - b'\xf1\x870EA906016F \xf1\x895002', - b'\xf1\x870EA906016Q \xf1\x895993', - b'\xf1\x870EA906016S \xf1\x897207', - b'\xf1\x875G0906259 \xf1\x890007', - b'\xf1\x875G0906259D \xf1\x890002', - b'\xf1\x875G0906259J \xf1\x890002', - b'\xf1\x875G0906259L \xf1\x890002', - b'\xf1\x875G0906259N \xf1\x890003', - b'\xf1\x875G0906259Q \xf1\x890002', - b'\xf1\x875G0906259Q \xf1\x892313', - b'\xf1\x875G0906259T \xf1\x890003', - b'\xf1\x878V0906259H \xf1\x890002', - b'\xf1\x878V0906259J \xf1\x890003', - b'\xf1\x878V0906259J \xf1\x890103', - b'\xf1\x878V0906259K \xf1\x890001', - b'\xf1\x878V0906259K \xf1\x890003', - b'\xf1\x878V0906259P \xf1\x890001', - b'\xf1\x878V0906259Q \xf1\x890002', - b'\xf1\x878V0906259R \xf1\x890002', - b'\xf1\x878V0906264F \xf1\x890003', - b'\xf1\x878V0906264L \xf1\x890002', - b'\xf1\x878V0906264M \xf1\x890001', - b'\xf1\x878V09C0BB01 \xf1\x890001', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x8709G927749AP\xf1\x892943', - b'\xf1\x8709S927158A \xf1\x893585', - b'\xf1\x870CW300040H \xf1\x890606', - b'\xf1\x870CW300041D \xf1\x891004', - b'\xf1\x870CW300041H \xf1\x891010', - b'\xf1\x870CW300042F \xf1\x891604', - b'\xf1\x870CW300043B \xf1\x891601', - b'\xf1\x870CW300043E \xf1\x891603', - b'\xf1\x870CW300044S \xf1\x894530', - b'\xf1\x870CW300044T \xf1\x895245', - b'\xf1\x870CW300045 \xf1\x894531', - b'\xf1\x870CW300047D \xf1\x895261', - b'\xf1\x870CW300047E \xf1\x895261', - b'\xf1\x870CW300048J \xf1\x890611', - b'\xf1\x870CW300049H \xf1\x890905', - b'\xf1\x870CW300050G \xf1\x891905', - b'\xf1\x870D9300012 \xf1\x894904', - b'\xf1\x870D9300012 \xf1\x894913', - b'\xf1\x870D9300012 \xf1\x894937', - b'\xf1\x870D9300012 \xf1\x895045', - b'\xf1\x870D9300012 \xf1\x895046', - b'\xf1\x870D9300014M \xf1\x895004', - b'\xf1\x870D9300014Q \xf1\x895006', - b'\xf1\x870D9300018 \xf1\x895201', - b'\xf1\x870D9300020J \xf1\x894902', - b'\xf1\x870D9300020Q \xf1\x895201', - b'\xf1\x870D9300020S \xf1\x895201', - b'\xf1\x870D9300040A \xf1\x893613', - b'\xf1\x870D9300040S \xf1\x894311', - b'\xf1\x870D9300041H \xf1\x895220', - b'\xf1\x870D9300041N \xf1\x894512', - b'\xf1\x870D9300041P \xf1\x894507', - b'\xf1\x870DD300045K \xf1\x891120', - b'\xf1\x870DD300046F \xf1\x891601', - b'\xf1\x870GC300012A \xf1\x891401', - b'\xf1\x870GC300012A \xf1\x891403', - b'\xf1\x870GC300012A \xf1\x891422', - b'\xf1\x870GC300012M \xf1\x892301', - b'\xf1\x870GC300014B \xf1\x892401', - b'\xf1\x870GC300014B \xf1\x892403', - b'\xf1\x870GC300014B \xf1\x892405', - b'\xf1\x870GC300020G \xf1\x892401', - b'\xf1\x870GC300020G \xf1\x892403', - b'\xf1\x870GC300020G \xf1\x892404', - b'\xf1\x870GC300020N \xf1\x892804', - b'\xf1\x870GC300043T \xf1\x899999', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x875Q0959655AA\xf1\x890386\xf1\x82\x111413001113120043114317121C111C9113', - b'\xf1\x875Q0959655AA\xf1\x890386\xf1\x82\x111413001113120053114317121C111C9113', - b'\xf1\x875Q0959655AA\xf1\x890388\xf1\x82\x111413001113120043114317121C111C9113', - b'\xf1\x875Q0959655AA\xf1\x890388\xf1\x82\x111413001113120043114417121411149113', - b'\xf1\x875Q0959655AA\xf1\x890388\xf1\x82\x111413001113120053114317121C111C9113', - b'\xf1\x875Q0959655AR\xf1\x890317\xf1\x82\x13141500111233003142114A2131219333313100', - b'\xf1\x875Q0959655BH\xf1\x890336\xf1\x82\x1314160011123300314211012230229333423100', - b'\xf1\x875Q0959655BH\xf1\x890336\xf1\x82\x1314160011123300314211012230229333463100', - b'\xf1\x875Q0959655BJ\xf1\x890339\xf1\x82\x13141600111233003142115A2232229333463100', - b'\xf1\x875Q0959655BS\xf1\x890403\xf1\x82\x1314160011123300314240012250229333463100', - b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x13141600111233003142404A2251229333463100', - b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x13141600111233003142404A2252229333463100', - b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x13141600111233003142405A2251229333463100', - b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x13141600111233003142405A2252229333463100', - b'\xf1\x875Q0959655C \xf1\x890361\xf1\x82\x111413001112120004110415121610169112', - b'\xf1\x875Q0959655CA\xf1\x890403\xf1\x82\x1314160011123300314240012250229333463100', - b'\xf1\x875Q0959655D \xf1\x890388\xf1\x82\x111413001113120006110417121A101A9113', - b'\xf1\x875Q0959655J \xf1\x890825\xf1\x82\x13271112111312--071104171825102591131211', - b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13271112111312--071104171825102591131211', - b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13271212111312--071104171838103891131211', - b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13272512111312--07110417182C102C91131211', - b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13341512112212--071104172328102891131211', - b'\xf1\x875Q0959655M \xf1\x890361\xf1\x82\x111413001112120041114115121611169112', - b'\xf1\x875Q0959655S \xf1\x890870\xf1\x82\x1315120011211200061104171717101791132111', - b'\xf1\x875Q0959655S \xf1\x890870\xf1\x82\x1315120011211200621143171717111791132111', - b'\xf1\x875Q0959655S \xf1\x890870\xf1\x82\x1324230011211200061104171724102491132111', - b'\xf1\x875Q0959655S \xf1\x890870\xf1\x82\x1324230011211200621143171724112491132111', - b'\xf1\x875Q0959655S \xf1\x890870\xf1\x82\x1324230011211200631143171724122491132111', - b'\xf1\x875Q0959655T \xf1\x890825\xf1\x82\x13271200111312--071104171837103791132111', - b'\xf1\x875Q0959655T \xf1\x890830\xf1\x82\x13271100111312--071104171826102691131211', - b'\xf1\x875QD959655 \xf1\x890388\xf1\x82\x111413001113120006110417121D101D9112', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x873Q0909144F \xf1\x895043\xf1\x82\x0561A01612A0', - b'\xf1\x873Q0909144H \xf1\x895061\xf1\x82\x0566A0J612A1', - b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566A00514A1', - b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566A01613A1', - b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566A0J712A1', - b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571A0J714A1', - b'\xf1\x873Q0909144L \xf1\x895081\xf1\x82\x0571A0JA15A1', - b'\xf1\x873Q0909144M \xf1\x895082\xf1\x82\x0571A01A18A1', - b'\xf1\x873Q0909144M \xf1\x895082\xf1\x82\x0571A02A16A1', - b'\xf1\x873Q0909144M \xf1\x895082\xf1\x82\x0571A0JA16A1', - b'\xf1\x873QM909144 \xf1\x895072\xf1\x82\x0571A01714A1', - b'\xf1\x875Q0909143K \xf1\x892033\xf1\x820519A9040203', - b'\xf1\x875Q0909144AA\xf1\x891081\xf1\x82\x0521A00441A1', - b'\xf1\x875Q0909144AA\xf1\x891081\xf1\x82\x0521A00608A1', - b'\xf1\x875Q0909144AA\xf1\x891081\xf1\x82\x0521A00641A1', - b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521A00442A1', - b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521A00642A1', - b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521A07B05A1', - b'\xf1\x875Q0909144L \xf1\x891021\xf1\x82\x0521A00502A0', - b'\xf1\x875Q0909144L \xf1\x891021\xf1\x82\x0521A00602A0', - b'\xf1\x875Q0909144L \xf1\x891021\xf1\x82\x0522A00402A0', - b'\xf1\x875Q0909144P \xf1\x891043\xf1\x82\x0511A00403A0', - b'\xf1\x875Q0909144R \xf1\x891061\xf1\x82\x0516A00604A1', - b'\xf1\x875Q0909144S \xf1\x891063\xf1\x82\x0516A00404A1', - b'\xf1\x875Q0909144S \xf1\x891063\xf1\x82\x0516A00504A1', - b'\xf1\x875Q0909144S \xf1\x891063\xf1\x82\x0516A00604A1', - b'\xf1\x875Q0909144S \xf1\x891063\xf1\x82\x0516A07A02A1', - b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521A00407A1', - b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521A00507A1', - b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521A07B04A1', - b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521A20B03A1', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567A2000400', - b'\xf1\x875QD909144B \xf1\x891072\xf1\x82\x0521A00507A1', - b'\xf1\x875QM909144A \xf1\x891072\xf1\x82\x0521A20B03A1', - b'\xf1\x875QM909144B \xf1\x891081\xf1\x82\x0521A00442A1', - b'\xf1\x875QM909144B \xf1\x891081\xf1\x82\x0521A00642A1', - b'\xf1\x875QN909144A \xf1\x895081\xf1\x82\x0571A01A16A1', - b'\xf1\x875QN909144A \xf1\x895081\xf1\x82\x0571A01A17A1', - b'\xf1\x875QN909144A \xf1\x895081\xf1\x82\x0571A01A18A1', - b'\xf1\x875QN909144B \xf1\x895082\xf1\x82\x0571A01A18A1', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x875Q0907567G \xf1\x890390\xf1\x82\x0101', - b'\xf1\x875Q0907567J \xf1\x890396\xf1\x82\x0101', - b'\xf1\x875Q0907567L \xf1\x890098\xf1\x82\x0101', - b'\xf1\x875Q0907572A \xf1\x890141\xf1\x82\x0101', - b'\xf1\x875Q0907572B \xf1\x890200\xf1\x82\x0101', - b'\xf1\x875Q0907572C \xf1\x890210\xf1\x82\x0101', - b'\xf1\x875Q0907572D \xf1\x890304\xf1\x82\x0101', - b'\xf1\x875Q0907572E \xf1\x89X310\xf1\x82\x0101', - b'\xf1\x875Q0907572F \xf1\x890400\xf1\x82\x0101', - b'\xf1\x875Q0907572G \xf1\x890571', - b'\xf1\x875Q0907572H \xf1\x890620', - b'\xf1\x875Q0907572J \xf1\x890653', - b'\xf1\x875Q0907572J \xf1\x890654', - b'\xf1\x875Q0907572P \xf1\x890682', - b'\xf1\x875Q0907572R \xf1\x890771', - b'\xf1\x875Q0907572S \xf1\x890780', - ], - }, - CAR.VOLKSWAGEN_JETTA_MK7: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704E906024AK\xf1\x899937', - b'\xf1\x8704E906024AS\xf1\x899912', - b'\xf1\x8704E906024B \xf1\x895594', - b'\xf1\x8704E906024BC\xf1\x899971', - b'\xf1\x8704E906024BG\xf1\x891057', - b'\xf1\x8704E906024C \xf1\x899970', - b'\xf1\x8704E906024C \xf1\x899971', - b'\xf1\x8704E906024L \xf1\x895595', - b'\xf1\x8704E906024L \xf1\x899970', - b'\xf1\x8704E906027MS\xf1\x896223', - b'\xf1\x8705E906013DB\xf1\x893361', - b'\xf1\x875G0906259T \xf1\x890003', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x8709G927158BQ\xf1\x893545', - b'\xf1\x8709S927158BS\xf1\x893642', - b'\xf1\x8709S927158BS\xf1\x893694', - b'\xf1\x8709S927158CK\xf1\x893770', - b'\xf1\x8709S927158JC\xf1\x894113', - b'\xf1\x8709S927158R \xf1\x893552', - b'\xf1\x8709S927158R \xf1\x893587', - b'\xf1\x870GC300020N \xf1\x892803', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x875Q0959655AG\xf1\x890336\xf1\x82\x1314171231313500314611011630169333463100', - b'\xf1\x875Q0959655AG\xf1\x890338\xf1\x82\x1314171231313500314611011630169333463100', - b'\xf1\x875Q0959655BM\xf1\x890403\xf1\x82\x1314171231313500314642011650169333463100', - b'\xf1\x875Q0959655BM\xf1\x890403\xf1\x82\x1314171231313500314643011650169333463100', - b'\xf1\x875Q0959655BR\xf1\x890403\xf1\x82\x1311170031313300314240011150119333433100', - b'\xf1\x875Q0959655BR\xf1\x890403\xf1\x82\x1319170031313300314240011550159333463100', - b'\xf1\x875Q0959655CB\xf1\x890421\xf1\x82\x1314171231313500314642021650169333613100', - b'\xf1\x875Q0959655CB\xf1\x890421\xf1\x82\x1314171231313500314643021650169333613100', - b'\xf1\x875Q0959655CB\xf1\x890421\xf1\x82\x1317171231313500314642023050309333613100', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x873Q0909144M \xf1\x895082\xf1\x82\x0571A10A11A1', - b'\xf1\x875QM907144D \xf1\x891063\xf1\x82\x000_A1080_OM', - b'\xf1\x875QM909144B \xf1\x891081\xf1\x82\x0521A10A01A1', - b'\xf1\x875QM909144B \xf1\x891081\xf1\x82\x0521B00404A1', - b'\xf1\x875QM909144C \xf1\x891082\xf1\x82\x0521A00642A1', - b'\xf1\x875QM909144C \xf1\x891082\xf1\x82\x0521A10A01A1', - b'\xf1\x875QN909144B \xf1\x895082\xf1\x82\x0571A10A11A1', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x875Q0907572N \xf1\x890681', - b'\xf1\x875Q0907572P \xf1\x890682', - b'\xf1\x875Q0907572R \xf1\x890771', - ], - }, - CAR.VOLKSWAGEN_PASSAT_MK8: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8703N906026E \xf1\x892114', - b'\xf1\x8704E906023AH\xf1\x893379', - b'\xf1\x8704E906023BM\xf1\x894522', - b'\xf1\x8704L906026DP\xf1\x891538', - b'\xf1\x8704L906026ET\xf1\x891990', - b'\xf1\x8704L906026FP\xf1\x892012', - b'\xf1\x8704L906026GA\xf1\x892013', - b'\xf1\x8704L906026GK\xf1\x899971', - b'\xf1\x8704L906026KD\xf1\x894798', - b'\xf1\x8705L906022A \xf1\x890827', - b'\xf1\x873G0906259 \xf1\x890004', - b'\xf1\x873G0906259B \xf1\x890002', - b'\xf1\x873G0906264 \xf1\x890004', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300041E \xf1\x891006', - b'\xf1\x870CW300042H \xf1\x891601', - b'\xf1\x870CW300042H \xf1\x891607', - b'\xf1\x870CW300043H \xf1\x891601', - b'\xf1\x870CW300048R \xf1\x890610', - b'\xf1\x870D9300013A \xf1\x894905', - b'\xf1\x870D9300014L \xf1\x895002', - b'\xf1\x870D9300018C \xf1\x895297', - b'\xf1\x870D9300041A \xf1\x894801', - b'\xf1\x870D9300042H \xf1\x894901', - b'\xf1\x870DD300045T \xf1\x891601', - b'\xf1\x870DD300046H \xf1\x891601', - b'\xf1\x870DL300011H \xf1\x895201', - b'\xf1\x870GC300042H \xf1\x891404', - b'\xf1\x870GC300043 \xf1\x892301', - b'\xf1\x870GC300046P \xf1\x892805', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x873Q0959655AE\xf1\x890195\xf1\x82\r56140056130012416612124111', - b'\xf1\x873Q0959655AF\xf1\x890195\xf1\x82\r56140056130012026612120211', - b'\xf1\x873Q0959655AN\xf1\x890305\xf1\x82\r58160058140013036914110311', - b'\xf1\x873Q0959655AN\xf1\x890306\xf1\x82\r58160058140013036914110311', - b'\xf1\x873Q0959655BA\xf1\x890195\xf1\x82\r56140056130012416612124111', - b'\xf1\x873Q0959655BA\xf1\x890195\xf1\x82\r56140056130012516612125111', - b'\xf1\x873Q0959655BB\xf1\x890195\xf1\x82\r56140056130012026612120211', - b'\xf1\x873Q0959655BG\xf1\x890712\xf1\x82\x0e5915005914001305701311052900', - b'\xf1\x873Q0959655BJ\xf1\x890703\xf1\x82\x0e5915005914001305701311052900', - b'\xf1\x873Q0959655BK\xf1\x890703\xf1\x82\x0e5915005914001344701311442900', - b'\xf1\x873Q0959655BK\xf1\x890703\xf1\x82\x0e5915005914001354701311542900', - b'\xf1\x873Q0959655CN\xf1\x890720\xf1\x82\x0e5915005914001305701311052900', - b'\xf1\x875Q0959655S \xf1\x890870\xf1\x82\x1315120011111200631145171716121691132111', - b'\xf1\x875QF959655S \xf1\x890639\xf1\x82\x13131100131300111111000120----2211114A48', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566B00611A1', - b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566B00711A1', - b'\xf1\x875Q0909143K \xf1\x892033\xf1\x820514B0060703', - b'\xf1\x875Q0909143M \xf1\x892041\xf1\x820522B0060803', - b'\xf1\x875Q0909143M \xf1\x892041\xf1\x820522B0080803', - b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820526B0060905', - b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820531B0062105', - b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521B00606A1', - b'\xf1\x875Q0909144S \xf1\x891063\xf1\x82\x0516B00501A1', - b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521B00603A1', - b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521B00703A1', - b'\xf1\x875Q0910143B \xf1\x892201\xf1\x82\x0563B0000600', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567B0020600', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x873Q0907572A \xf1\x890126', - b'\xf1\x873Q0907572A \xf1\x890130', - b'\xf1\x873Q0907572B \xf1\x890192', - b'\xf1\x873Q0907572B \xf1\x890194', - b'\xf1\x873Q0907572C \xf1\x890195', - b'\xf1\x873Q0907572C \xf1\x890196', - b'\xf1\x875Q0907572P \xf1\x890682', - b'\xf1\x875Q0907572R \xf1\x890771', - b'\xf1\x875Q0907572S \xf1\x890780', - ], - }, - CAR.VOLKSWAGEN_PASSAT_NMS: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8706K906016C \xf1\x899609', - b'\xf1\x8706K906016E \xf1\x899830', - b'\xf1\x8706K906016G \xf1\x891124', - b'\xf1\x8706K906071BJ\xf1\x894891', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x8709G927158AB\xf1\x893318', - b'\xf1\x8709G927158BD\xf1\x893121', - b'\xf1\x8709G927158DK\xf1\x893594', - b'\xf1\x8709G927158FQ\xf1\x893745', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x87561959655 \xf1\x890210\xf1\x82\x1212121111113000102011--121012--101312', - b'\xf1\x87561959655C \xf1\x890508\xf1\x82\x1215141111121100314919--153015--304831', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x87561907567A \xf1\x890132', - b'\xf1\x877N0907572C \xf1\x890211\xf1\x82\x0152', - ], - }, - CAR.VOLKSWAGEN_POLO_MK6: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704C906025H \xf1\x895177', - b'\xf1\x8705C906032J \xf1\x891702', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300042D \xf1\x891612', - b'\xf1\x870CW300050D \xf1\x891908', - b'\xf1\x870CW300051G \xf1\x891909', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x872Q0959655AG\xf1\x890248\xf1\x82\x1218130411110411--04040404231811152H14', - b'\xf1\x872Q0959655AJ\xf1\x890250\xf1\x82\x1248130411110416--04040404784811152H14', - b'\xf1\x872Q0959655AS\xf1\x890411\xf1\x82\x1384830511110516041405820599841215391471', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x872Q1909144M \xf1\x896041', - b'\xf1\x872Q2909144AB\xf1\x896050', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x872Q0907572R \xf1\x890372', - ], - }, - CAR.VOLKSWAGEN_SHARAN_MK2: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704L906016HE\xf1\x894635', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x877N0959655D \xf1\x890016\xf1\x82\x0801100705----10--', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x877N0907572C \xf1\x890211\xf1\x82\x0153', - ], - }, - CAR.VOLKSWAGEN_TAOS_MK1: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704E906025CK\xf1\x892228', - b'\xf1\x8704E906027NJ\xf1\x891445', - b'\xf1\x8704E906027NP\xf1\x891286', - b'\xf1\x8705E906013BD\xf1\x892496', - b'\xf1\x8705E906013E \xf1\x891624', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x8709G927158EM\xf1\x893812', - b'\xf1\x8709S927158BL\xf1\x893791', - b'\xf1\x8709S927158CR\xf1\x893924', - b'\xf1\x8709S927158DN\xf1\x893946', - b'\xf1\x8709S927158FF\xf1\x893876', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x875Q0959655CB\xf1\x890421\xf1\x82\x1311111111333500314646021450149333613100', - b'\xf1\x875Q0959655CB\xf1\x890421\xf1\x82\x1312111111333500314646021550159333613100', - b'\xf1\x875Q0959655CE\xf1\x890421\xf1\x82\x1311110011333300314240021350139333613100', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x875QM907144D \xf1\x891063\xf1\x82\x001O06081OOM', - b'\xf1\x875QM909144C \xf1\x891082\xf1\x82\x0521060405A1', - b'\xf1\x875QM909144C \xf1\x891082\xf1\x82\x0521060605A1', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x872Q0907572T \xf1\x890383', - ], - }, - CAR.VOLKSWAGEN_TCROSS_MK1: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704C906025AK\xf1\x897053', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300050E \xf1\x891903', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x872Q0959655AJ\xf1\x890250\xf1\x82\x1212130411110411--04041104141311152H14', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x872Q1909144M \xf1\x896041', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572T \xf1\x890383', - ], - }, - CAR.VOLKSWAGEN_TIGUAN_MK2: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8703N906026D \xf1\x893680', - b'\xf1\x8704E906024AP\xf1\x891461', - b'\xf1\x8704E906027NB\xf1\x899504', - b'\xf1\x8704L906026EJ\xf1\x893661', - b'\xf1\x8704L906027G \xf1\x899893', - b'\xf1\x8705E906018BS\xf1\x890914', - b'\xf1\x875N0906259 \xf1\x890002', - b'\xf1\x875NA906259H \xf1\x890002', - b'\xf1\x875NA907115E \xf1\x890003', - b'\xf1\x875NA907115E \xf1\x890005', - b'\xf1\x875NA907115J \xf1\x890002', - b'\xf1\x875NA907115K \xf1\x890004', - b'\xf1\x8783A907115 \xf1\x890007', - b'\xf1\x8783A907115B \xf1\x890005', - b'\xf1\x8783A907115F \xf1\x890002', - b'\xf1\x8783A907115G \xf1\x890001', - b'\xf1\x8783A907115K \xf1\x890001', - b'\xf1\x8783A907115K \xf1\x890002', - b'\xf1\x8783A907115Q \xf1\x890001', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x8709G927158DT\xf1\x893698', - b'\xf1\x8709G927158FM\xf1\x893757', - b'\xf1\x8709G927158GC\xf1\x893821', - b'\xf1\x8709G927158GD\xf1\x893820', - b'\xf1\x8709G927158GM\xf1\x893936', - b'\xf1\x8709G927158GN\xf1\x893938', - b'\xf1\x8709G927158HB\xf1\x894069', - b'\xf1\x8709G927158HC\xf1\x894070', - b'\xf1\x870D9300043 \xf1\x895202', - b'\xf1\x870DD300046K \xf1\x892302', - b'\xf1\x870DL300011N \xf1\x892001', - b'\xf1\x870DL300011N \xf1\x892012', - b'\xf1\x870DL300012M \xf1\x892107', - b'\xf1\x870DL300012P \xf1\x892103', - b'\xf1\x870DL300013A \xf1\x893005', - b'\xf1\x870DL300013G \xf1\x892119', - b'\xf1\x870DL300013G \xf1\x892120', - b'\xf1\x870DL300014C \xf1\x893703', - b'\xf1\x870GC300013P \xf1\x892401', - b'\xf1\x870GC300046Q \xf1\x892802', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x875Q0959655AG\xf1\x890336\xf1\x82\x1316143231313500314617011730179333423100', - b'\xf1\x875Q0959655AG\xf1\x890338\xf1\x82\x1316143231313500314617011730179333423100', - b'\xf1\x875Q0959655AR\xf1\x890317\xf1\x82\x1331310031333334313132573732379333313100', - b'\xf1\x875Q0959655BJ\xf1\x890336\xf1\x82\x1312110031333300314232583732379333423100', - b'\xf1\x875Q0959655BJ\xf1\x890339\xf1\x82\x1331310031333334313132013730379333423100', - b'\xf1\x875Q0959655BM\xf1\x890403\xf1\x82\x1316143231313500314641011750179333423100', - b'\xf1\x875Q0959655BS\xf1\x890403\xf1\x82\x1312110031333300314240013750379333423100', - b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x1312110031333300314240583752379333423100', - b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x1331310031333334313140013750379333423100', - b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x1331310031333334313140573752379333423100', - b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x1331310031333336313140013950399333423100', - b'\xf1\x875Q0959655CB\xf1\x890421\xf1\x82\x1316143231313500314647021750179333613100', - b'\xf1\x875Q0959655CD\xf1\x890421\xf1\x82\x13123112313333003145406F6154619333613100', - b'\xf1\x875Q0959655CG\xf1\x890421\xf1\x82\x1331310031333300314240024050409333613100', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x875Q0909143M \xf1\x892041\xf1\x820529A6060603', - b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820527A6050705', - b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820527A6070705', - b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521A60604A1', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567A6000600', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567A6017A00', - b'\xf1\x875QF909144A \xf1\x895581\xf1\x82\x0571A60834A1', - b'\xf1\x875QF909144B \xf1\x895582\xf1\x82\x0571A60634A1', - b'\xf1\x875QF909144B \xf1\x895582\xf1\x82\x0571A62A32A1', - b'\xf1\x875QM907144D \xf1\x891063\xf1\x82\x002RA60A2ROM', - b'\xf1\x875QM907144D \xf1\x891063\xf1\x82\x002SA6092SOM', - b'\xf1\x875QM909144B \xf1\x891081\xf1\x82\x0521A60604A1', - b'\xf1\x875QM909144B \xf1\x891081\xf1\x82\x0521A60804A1', - b'\xf1\x875QM909144C \xf1\x891082\xf1\x82\x0521A60604A1', - b'\xf1\x875QM909144C \xf1\x891082\xf1\x82\x0521A60804A1', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x872Q0907572AB\xf1\x890397', - b'\xf1\x872Q0907572J \xf1\x890156', - b'\xf1\x872Q0907572M \xf1\x890233', - b'\xf1\x872Q0907572Q \xf1\x890342', - b'\xf1\x872Q0907572R \xf1\x890372', - b'\xf1\x872Q0907572T \xf1\x890383', - ], - }, - CAR.VOLKSWAGEN_TOURAN_MK2: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704E906025BE\xf1\x890720', - b'\xf1\x8704E906027HQ\xf1\x893746', - b'\xf1\x8704L906026HM\xf1\x893017', - b'\xf1\x8705E906018CQ\xf1\x890808', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300020A \xf1\x891936', - b'\xf1\x870CW300041E \xf1\x891005', - b'\xf1\x870CW300041Q \xf1\x891606', - b'\xf1\x870CW300051M \xf1\x891926', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x875Q0959655AS\xf1\x890318\xf1\x82\x1336350021353335314132014730479333313100', - b'\xf1\x875Q0959655AS\xf1\x890318\xf1\x82\x13363500213533353141324C4732479333313100', - b'\xf1\x875Q0959655CH\xf1\x890421\xf1\x82\x1336350021353336314740025250529333613100', - b'\xf1\x875QD959655AJ\xf1\x890421\xf1\x82\x1336350021313300314240023330339333663100', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820531B0062105', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567A8090400', - b'\xf1\x875QD909144F \xf1\x891082\xf1\x82\x0521A00642A1', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x873Q0907572C \xf1\x890195', - b'\xf1\x875Q0907572R \xf1\x890771', - ], - }, - CAR.VOLKSWAGEN_TRANSPORTER_T61: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704L906056AG\xf1\x899970', - b'\xf1\x8704L906056AL\xf1\x899970', - b'\xf1\x8704L906057AP\xf1\x891186', - b'\xf1\x8704L906057N \xf1\x890413', - b'\xf1\x8705L906023E \xf1\x891352', - b'\xf1\x8705L906023MR\xf1\x892582', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870BT300012E \xf1\x893105', - b'\xf1\x870BT300012G \xf1\x893102', - b'\xf1\x870BT300046R \xf1\x893102', - b'\xf1\x870DV300012B \xf1\x893701', - b'\xf1\x870DV300012B \xf1\x893702', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x872Q0959655AE\xf1\x890506\xf1\x82\x1316170411110411--04041704161611152S1411', - b'\xf1\x872Q0959655AE\xf1\x890506\xf1\x82\x1316170411110411--04041704171711152S1411', - b'\xf1\x872Q0959655AF\xf1\x890506\xf1\x82\x1316171111110411--04041711121211152S1413', - b'\xf1\x872Q0959655AQ\xf1\x890511\xf1\x82\x1316170411110411--0404170426261215391421', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x877LA909144F \xf1\x897150\xf1\x82\x0532380518A2', - b'\xf1\x877LA909144F \xf1\x897150\xf1\x82\x05323A5519A2', - b'\xf1\x877LA909144G \xf1\x897160\xf1\x82\x05333A5519A2', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x872Q0907572R \xf1\x890372', - ], - }, - CAR.VOLKSWAGEN_TROC_MK1: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8705E906018AT\xf1\x899640', - b'\xf1\x8705E906018CK\xf1\x890863', - b'\xf1\x8705E906018P \xf1\x896020', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300041S \xf1\x891615', - b'\xf1\x870CW300050J \xf1\x891911', - b'\xf1\x870CW300051M \xf1\x891925', - b'\xf1\x870CW300051M \xf1\x891928', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x873Q0959655BH\xf1\x890712\xf1\x82\x0e1111001111001105111111052900', - b'\xf1\x875Q0959655BT\xf1\x890403\xf1\x82\x1311110012333300314240681152119333463100', - b'\xf1\x875Q0959655CF\xf1\x890421\xf1\x82\x1311110012333300314240021150119333613100', - b'\xf1\x875Q0959655CG\xf1\x890421\xf1\x82\x13111100123333003142404M1152119333613100', - b'\xf1\x875Q0959655CG\xf1\x890421\xf1\x82\x13111100123333003142404M1154119333613100', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x875Q0909144AA\xf1\x891081\xf1\x82\x0521060403A1', - b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521060405A1', - b'\xf1\x875WA907144M \xf1\x891051\xf1\x82\x001T06081T7N', - b'\xf1\x875WA907144Q \xf1\x891063\xf1\x82\x001O06081OOM', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x872Q0907572M \xf1\x890233', - b'\xf1\x872Q0907572T \xf1\x890383', - ], - }, - CAR.AUDI_A3_MK3: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704E906023AN\xf1\x893695', - b'\xf1\x8704E906023AR\xf1\x893440', - b'\xf1\x8704E906023BL\xf1\x895190', - b'\xf1\x8704E906027CJ\xf1\x897798', - b'\xf1\x8704L997022N \xf1\x899459', - b'\xf1\x875G0906259A \xf1\x890004', - b'\xf1\x875G0906259D \xf1\x890002', - b'\xf1\x875G0906259L \xf1\x890002', - b'\xf1\x875G0906259Q \xf1\x890002', - b'\xf1\x878V0906259E \xf1\x890001', - b'\xf1\x878V0906259F \xf1\x890002', - b'\xf1\x878V0906259H \xf1\x890002', - b'\xf1\x878V0906259J \xf1\x890002', - b'\xf1\x878V0906259K \xf1\x890001', - b'\xf1\x878V0906264B \xf1\x890003', - b'\xf1\x878V0907115B \xf1\x890007', - b'\xf1\x878V0907404A \xf1\x890005', - b'\xf1\x878V0907404G \xf1\x890005', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300044T \xf1\x895245', - b'\xf1\x870CW300048 \xf1\x895201', - b'\xf1\x870D9300012 \xf1\x894912', - b'\xf1\x870D9300012 \xf1\x894931', - b'\xf1\x870D9300012K \xf1\x894513', - b'\xf1\x870D9300012L \xf1\x894521', - b'\xf1\x870D9300013B \xf1\x894902', - b'\xf1\x870D9300013B \xf1\x894931', - b'\xf1\x870D9300041N \xf1\x894512', - b'\xf1\x870D9300043T \xf1\x899699', - b'\xf1\x870DD300046 \xf1\x891604', - b'\xf1\x870DD300046A \xf1\x891602', - b'\xf1\x870DD300046F \xf1\x891602', - b'\xf1\x870DD300046G \xf1\x891601', - b'\xf1\x870DL300012E \xf1\x892012', - b'\xf1\x870DL300012H \xf1\x892112', - b'\xf1\x870GC300011 \xf1\x890403', - b'\xf1\x870GC300013M \xf1\x892402', - b'\xf1\x870GC300042J \xf1\x891402', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x875Q0959655AB\xf1\x890388\xf1\x82\x111111001111111206110412111321139114', - b'\xf1\x875Q0959655AM\xf1\x890315\xf1\x82\x1311111111111111311411011231129321212100', - b'\xf1\x875Q0959655AM\xf1\x890318\xf1\x82\x1311111111111112311411011531159321212100', - b'\xf1\x875Q0959655AR\xf1\x890315\xf1\x82\x1311110011131115311211012331239321212100', - b'\xf1\x875Q0959655BJ\xf1\x890339\xf1\x82\x1311110011131100311111011731179321342100', - b'\xf1\x875Q0959655J \xf1\x890825\xf1\x82\x13111112111111--171115141112221291163221', - b'\xf1\x875Q0959655J \xf1\x890825\xf1\x82\x13111112111111--241115141112221291163221', - b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13111112111111--241115141112221291163221', - b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13121111111111--341117141212231291163221', - b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13121111111211--261117141112231291163221', - b'\xf1\x875Q0959655N \xf1\x890361\xf1\x82\x111212001112110004110411111421149114', - b'\xf1\x875Q0959655N \xf1\x890361\xf1\x82\x111212001112111104110411111521159114', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x873Q0909144F \xf1\x895043\xf1\x82\x0561G01A13A0', - b'\xf1\x873Q0909144H \xf1\x895061\xf1\x82\x0566G0HA14A1', - b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566G0HA14A1', - b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571G01A16A1', - b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571G0HA16A1', - b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571G0JA13A1', - b'\xf1\x873Q0909144L \xf1\x895081\xf1\x82\x0571G0JA14A1', - b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521G0G809A1', - b'\xf1\x875Q0909144P \xf1\x891043\xf1\x82\x0503G00303A0', - b'\xf1\x875Q0909144P \xf1\x891043\xf1\x82\x0503G00803A0', - b'\xf1\x875Q0909144P \xf1\x891043\xf1\x82\x0503G0G803A0', - b'\xf1\x875Q0909144R \xf1\x891061\xf1\x82\x0516G00804A1', - b'\xf1\x875Q0909144S \xf1\x891063\xf1\x82\x0516G00804A1', - b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521G00807A1', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x875Q0907567M \xf1\x890398\xf1\x82\x0101', - b'\xf1\x875Q0907567N \xf1\x890400\xf1\x82\x0101', - b'\xf1\x875Q0907572D \xf1\x890304\xf1\x82\x0101', - b'\xf1\x875Q0907572F \xf1\x890400\xf1\x82\x0101', - b'\xf1\x875Q0907572G \xf1\x890571', - b'\xf1\x875Q0907572H \xf1\x890620', - b'\xf1\x875Q0907572P \xf1\x890682', - ], - }, - CAR.AUDI_Q2_MK1: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704E906027JT\xf1\x894145', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300041F \xf1\x891006', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x875Q0959655BD\xf1\x890336\xf1\x82\x1311111111111100311211011231129321312111', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571F60511A1', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572M \xf1\x890233', - ], - }, - CAR.AUDI_Q3_MK2: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8705E906018N \xf1\x899970', - b'\xf1\x8705L906022M \xf1\x890901', - b'\xf1\x8783A906259 \xf1\x890001', - b'\xf1\x8783A906259 \xf1\x890005', - b'\xf1\x8783A906259C \xf1\x890002', - b'\xf1\x8783A906259D \xf1\x890001', - b'\xf1\x8783A906259F \xf1\x890001', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x8709G927158CN\xf1\x893608', - b'\xf1\x8709G927158FL\xf1\x893758', - b'\xf1\x8709G927158GG\xf1\x893825', - b'\xf1\x8709G927158GP\xf1\x893937', - b'\xf1\x870GC300045D \xf1\x892802', - b'\xf1\x870GC300046F \xf1\x892701', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x875Q0959655BF\xf1\x890403\xf1\x82\x1321211111211200311121232152219321422111', - b'\xf1\x875Q0959655BQ\xf1\x890421\xf1\x82\x132121111121120031112124218A219321532111', - b'\xf1\x875Q0959655BQ\xf1\x890421\xf1\x82\x132121111121120031112124218C219321532111', - b'\xf1\x875Q0959655CC\xf1\x890421\xf1\x82\x131111111111120031111224118A119321532111', - b'\xf1\x875Q0959655CC\xf1\x890421\xf1\x82\x131111111111120031111237116A119321532111', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567G6000300', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567G6000800', - b'\xf1\x875QF909144B \xf1\x895582\xf1\x82\x0571G60533A1', - b'\xf1\x875QF909144B \xf1\x895582\xf1\x82\x0571G60733A1', - b'\xf1\x875TA907145D \xf1\x891051\xf1\x82\x001PG60A1P7N', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x872Q0907572R \xf1\x890372', - b'\xf1\x872Q0907572T \xf1\x890383', - ], - }, - CAR.SEAT_ATECA_MK1: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704E906027KA\xf1\x893749', - b'\xf1\x8704L906021EL\xf1\x897542', - b'\xf1\x8704L906026BP\xf1\x891198', - b'\xf1\x8704L906026BP\xf1\x897608', - b'\xf1\x8704L906056CR\xf1\x892181', - b'\xf1\x8704L906056CR\xf1\x892797', - b'\xf1\x8705E906018AS\xf1\x899596', - b'\xf1\x8781A906259B \xf1\x890003', - b'\xf1\x878V0906264H \xf1\x890005', - b'\xf1\x878V0907115E \xf1\x890002', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300041D \xf1\x891004', - b'\xf1\x870CW300041G \xf1\x891003', - b'\xf1\x870CW300050J \xf1\x891908', - b'\xf1\x870D9300014S \xf1\x895202', - b'\xf1\x870D9300042M \xf1\x895016', - b'\xf1\x870GC300014P \xf1\x892801', - b'\xf1\x870GC300043A \xf1\x892304', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x873Q0959655AC\xf1\x890189\xf1\x82\r11110011110011021511110200', - b'\xf1\x873Q0959655AS\xf1\x890200\xf1\x82\r11110011110011021511110200', - b'\xf1\x873Q0959655AS\xf1\x890200\xf1\x82\r12110012120012021612110200', - b'\xf1\x873Q0959655BH\xf1\x890703\xf1\x82\x0e1212001211001305121211052900', - b'\xf1\x873Q0959655BH\xf1\x890703\xf1\x82\x0e1312001313001305171311052900', - b'\xf1\x873Q0959655BH\xf1\x890712\xf1\x82\x0e1312001313001305171311052900', - b'\xf1\x873Q0959655CM\xf1\x890720\xf1\x82\x0e1312001313001305171311052900', - b'\xf1\x875QF959655AT\xf1\x890755\xf1\x82\x1311110011110011111100110200--1113121149', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x873Q0909144L \xf1\x895081\xf1\x82\x0571N60511A1', - b'\xf1\x875Q0909144AA\xf1\x891081\xf1\x82\x0521N01842A1', - b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521N01342A1', - b'\xf1\x875Q0909144P \xf1\x891043\xf1\x82\x0511N01805A0', - b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521N01309A1', - b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521N05808A1', - b'\xf1\x875WA907145M \xf1\x891051\xf1\x82\x0013N619137N', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x872Q0907572M \xf1\x890233', - b'\xf1\x875Q0907572B \xf1\x890200\xf1\x82\x0101', - b'\xf1\x875Q0907572H \xf1\x890620', - b'\xf1\x875Q0907572K \xf1\x890402\xf1\x82\x0101', - b'\xf1\x875Q0907572P \xf1\x890682', - b'\xf1\x875Q0907572R \xf1\x890771', - ], - }, - CAR.SKODA_FABIA_MK4: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8705E906018CF\xf1\x891905', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300051M \xf1\x891936', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x875QF959655AT\xf1\x890755\xf1\x82\x1311110011110011111100110200--1111120749', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x872Q1909144S \xf1\x896042', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - ], - }, - CAR.SKODA_KAMIQ_MK1: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704C906025AK\xf1\x897053', - b'\xf1\x8705C906032M \xf1\x891333', - b'\xf1\x8705C906032M \xf1\x892365', - b'\xf1\x8705E906013CK\xf1\x892540', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300020 \xf1\x891906', - b'\xf1\x870CW300020 \xf1\x891907', - b'\xf1\x870CW300020T \xf1\x892204', - b'\xf1\x870CW300050 \xf1\x891709', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x872Q0959655AJ\xf1\x890250\xf1\x82\x1211110411110411--04040404131111112H14', - b'\xf1\x872Q0959655AM\xf1\x890351\xf1\x82\x12111104111104112104040404111111112H14', - b'\xf1\x872Q0959655AM\xf1\x890351\xf1\x82\x122221042111042121040404042E2711152H14', - b'\xf1\x872Q0959655AS\xf1\x890411\xf1\x82\x1311150411110411210404040417151215391413', - b'\xf1\x872Q0959655BJ\xf1\x890412\xf1\x82\x132223042111042121040404042B251215391423', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x872Q1909144AB\xf1\x896050', - b'\xf1\x872Q1909144M \xf1\x896041', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x872Q0907572R \xf1\x890372', - b'\xf1\x872Q0907572T \xf1\x890383', - ], - }, - CAR.SKODA_KAROQ_MK1: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8705E906013CL\xf1\x892541', - b'\xf1\x8705E906013H \xf1\x892407', - b'\xf1\x8705E906018P \xf1\x895472', - b'\xf1\x8705E906018P \xf1\x896020', - b'\xf1\x8705L906022BS\xf1\x890913', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300020T \xf1\x892202', - b'\xf1\x870CW300041S \xf1\x891615', - b'\xf1\x870GC300014L \xf1\x892802', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x873Q0959655BH\xf1\x890703\xf1\x82\x0e1213001211001101131112012100', - b'\xf1\x873Q0959655BH\xf1\x890712\xf1\x82\x0e1213001211001101131122012100', - b'\xf1\x873Q0959655DE\xf1\x890731\xf1\x82\x0e1213001211001101131121012J00', - b'\xf1\x875QF959655AT\xf1\x890755\xf1\x82\x1312110012120011111100010200--2521210749', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x875Q0910143B \xf1\x892201\xf1\x82\x0563T6090500', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567T6100500', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567T6100600', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567T6100700', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x872Q0907572AB\xf1\x890397', - b'\xf1\x872Q0907572M \xf1\x890233', - b'\xf1\x872Q0907572T \xf1\x890383', - ], - }, - CAR.SKODA_KODIAQ_MK1: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704E906027DD\xf1\x893123', - b'\xf1\x8704E906027LD\xf1\x893433', - b'\xf1\x8704E906027NB\xf1\x896517', - b'\xf1\x8704E906027NB\xf1\x899504', - b'\xf1\x8704L906026DE\xf1\x895418', - b'\xf1\x8704L906026EJ\xf1\x893661', - b'\xf1\x8704L906026HT\xf1\x893617', - b'\xf1\x8705E906018DJ\xf1\x890915', - b'\xf1\x8705E906018DJ\xf1\x891903', - b'\xf1\x8705L906022GM\xf1\x893411', - b'\xf1\x875NA906259E \xf1\x890003', - b'\xf1\x875NA907115D \xf1\x890003', - b'\xf1\x875NA907115E \xf1\x890003', - b'\xf1\x875NA907115E \xf1\x890005', - b'\xf1\x8783A907115E \xf1\x890001', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870D9300014S \xf1\x895201', - b'\xf1\x870D9300043 \xf1\x895202', - b'\xf1\x870DL300011N \xf1\x892014', - b'\xf1\x870DL300012G \xf1\x892006', - b'\xf1\x870DL300012M \xf1\x892107', - b'\xf1\x870DL300012N \xf1\x892110', - b'\xf1\x870DL300013G \xf1\x892119', - b'\xf1\x870GC300014N \xf1\x892801', - b'\xf1\x870GC300018S \xf1\x892803', - b'\xf1\x870GC300019H \xf1\x892806', - b'\xf1\x870GC300046Q \xf1\x892802', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x873Q0959655AN\xf1\x890306\xf1\x82\r11110011110011031111310311', - b'\xf1\x873Q0959655AP\xf1\x890306\xf1\x82\r11110011110011421111314211', - b'\xf1\x873Q0959655BH\xf1\x890703\xf1\x82\x0e1213001211001205212111052100', - b'\xf1\x873Q0959655BJ\xf1\x890703\xf1\x82\x0e1213001211001205212111052100', - b'\xf1\x873Q0959655BK\xf1\x890703\xf1\x82\x0e1213001211001244212111442100', - b'\xf1\x873Q0959655CN\xf1\x890720\xf1\x82\x0e1213001211001205212112052100', - b'\xf1\x873Q0959655CQ\xf1\x890720\xf1\x82\x0e1213111211001205212112052111', - b'\xf1\x873Q0959655DJ\xf1\x890731\xf1\x82\x0e1513001511001205232113052J00', - b'\xf1\x875QF959655AT\xf1\x890755\xf1\x82\x1311110011110011111100010200--1121240749', - b'\xf1\x875QF959655AT\xf1\x890755\xf1\x82\x1311110011110011111100010200--1121246149', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820527T6050405', - b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820527T6060405', - b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820527T6070405', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567T600G500', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567T600G600', - b'\xf1\x875TA907145F \xf1\x891063\xf1\x82\x0025T6BA25OM', - b'\xf1\x875TA907145F \xf1\x891063\xf1\x82\x002LT61A2LOM', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x872Q0907572AA\xf1\x890396', - b'\xf1\x872Q0907572AB\xf1\x890397', - b'\xf1\x872Q0907572M \xf1\x890233', - b'\xf1\x872Q0907572Q \xf1\x890342', - b'\xf1\x872Q0907572R \xf1\x890372', - b'\xf1\x872Q0907572T \xf1\x890383', - ], - }, - CAR.SKODA_OCTAVIA_MK3: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704C906025L \xf1\x896198', - b'\xf1\x8704E906016ER\xf1\x895823', - b'\xf1\x8704E906027HD\xf1\x893742', - b'\xf1\x8704E906027MH\xf1\x894786', - b'\xf1\x8704L906021DT\xf1\x898127', - b'\xf1\x8704L906021ER\xf1\x898361', - b'\xf1\x8704L906026BP\xf1\x897608', - b'\xf1\x8704L906026BS\xf1\x891541', - b'\xf1\x8704L906026BT\xf1\x897612', - b'\xf1\x875G0906259C \xf1\x890002', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300041L \xf1\x891601', - b'\xf1\x870CW300041N \xf1\x891605', - b'\xf1\x870CW300043B \xf1\x891601', - b'\xf1\x870CW300043P \xf1\x891605', - b'\xf1\x870D9300012H \xf1\x894518', - b'\xf1\x870D9300014T \xf1\x895221', - b'\xf1\x870D9300041C \xf1\x894936', - b'\xf1\x870D9300041H \xf1\x895220', - b'\xf1\x870D9300041J \xf1\x894902', - b'\xf1\x870D9300041P \xf1\x894507', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x873Q0959655AC\xf1\x890200\xf1\x82\r11120011100010022212110200', - b'\xf1\x873Q0959655AK\xf1\x890306\xf1\x82\r31210031210021033733310331', - b'\xf1\x873Q0959655AP\xf1\x890305\xf1\x82\r11110011110011213331312131', - b'\xf1\x873Q0959655AQ\xf1\x890200\xf1\x82\r11120011100010312212113100', - b'\xf1\x873Q0959655AS\xf1\x890200\xf1\x82\r11120011100010022212110200', - b'\xf1\x873Q0959655BH\xf1\x890703\xf1\x82\x0e3221003221002105755331052100', - b'\xf1\x873Q0959655CM\xf1\x890720\xf1\x82\x0e3221003221002105755331052100', - b'\xf1\x873Q0959655CN\xf1\x890720\xf1\x82\x0e3221003221002105755331052100', - b'\xf1\x875QD959655 \xf1\x890388\xf1\x82\x111101000011110006110411111111119111', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x873Q0909144J \xf1\x895063\xf1\x82\x0566A01513A1', - b'\xf1\x875Q0909144AA\xf1\x891081\xf1\x82\x0521T00403A1', - b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521T00403A1', - b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521T00603A1', - b'\xf1\x875Q0909144R \xf1\x891061\xf1\x82\x0516A00604A1', - b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\x0521T00601A1', - b'\xf1\x875QD909144E \xf1\x891081\xf1\x82\x0521T00503A1', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x875Q0907567P \xf1\x890100\xf1\x82\x0101', - b'\xf1\x875Q0907572D \xf1\x890304\xf1\x82\x0101', - b'\xf1\x875Q0907572F \xf1\x890400\xf1\x82\x0101', - b'\xf1\x875Q0907572H \xf1\x890620', - b'\xf1\x875Q0907572J \xf1\x890654', - b'\xf1\x875Q0907572K \xf1\x890402\xf1\x82\x0101', - b'\xf1\x875Q0907572P \xf1\x890682', - b'\xf1\x875Q0907572R \xf1\x890771', - ], - }, - CAR.SKODA_SUPERB_MK3: { - (Ecu.engine, 0x7e0, None): [ - b'\xf1\x8704E906027BS\xf1\x892887', - b'\xf1\x8704E906027BT\xf1\x899042', - b'\xf1\x8704L906026ET\xf1\x891343', - b'\xf1\x8704L906026ET\xf1\x891990', - b'\xf1\x8704L906026FP\xf1\x891196', - b'\xf1\x8704L906026KA\xf1\x896014', - b'\xf1\x8704L906026KB\xf1\x894071', - b'\xf1\x8704L906026KD\xf1\x894798', - b'\xf1\x8704L906026MT\xf1\x893076', - b'\xf1\x8705L906022BK\xf1\x899971', - b'\xf1\x873G0906259 \xf1\x890004', - b'\xf1\x873G0906259B \xf1\x890002', - b'\xf1\x873G0906259L \xf1\x890003', - b'\xf1\x873G0906264A \xf1\x890002', - ], - (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x870CW300042H \xf1\x891601', - b'\xf1\x870CW300043B \xf1\x891603', - b'\xf1\x870CW300049Q \xf1\x890906', - b'\xf1\x870D9300011T \xf1\x894801', - b'\xf1\x870D9300012 \xf1\x894940', - b'\xf1\x870D9300013A \xf1\x894905', - b'\xf1\x870D9300014K \xf1\x895006', - b'\xf1\x870D9300041H \xf1\x894905', - b'\xf1\x870D9300042M \xf1\x895013', - b'\xf1\x870D9300043F \xf1\x895202', - b'\xf1\x870GC300013K \xf1\x892403', - b'\xf1\x870GC300014M \xf1\x892801', - b'\xf1\x870GC300019G \xf1\x892803', - b'\xf1\x870GC300043 \xf1\x892301', - b'\xf1\x870GC300046D \xf1\x892402', - ], - (Ecu.srs, 0x715, None): [ - b'\xf1\x875Q0959655AE\xf1\x890130\xf1\x82\x12111200111121001121110012211292221111', - b'\xf1\x875Q0959655AE\xf1\x890130\xf1\x82\x12111200111121001121118112231292221111', - b'\xf1\x875Q0959655AK\xf1\x890130\xf1\x82\x12111200111121001121110012211292221111', - b'\xf1\x875Q0959655AS\xf1\x890317\xf1\x82\x1331310031313100313131823133319331313100', - b'\xf1\x875Q0959655AT\xf1\x890317\xf1\x82\x1331310031313100313131013131319331313100', - b'\xf1\x875Q0959655BH\xf1\x890336\xf1\x82\x1331310031313100313131013141319331413100', - b'\xf1\x875Q0959655BK\xf1\x890336\xf1\x82\x1331310031313100313131013141319331413100', - b'\xf1\x875Q0959655BS\xf1\x890403\xf1\x82\x1333310031313100313152015351539331423100', - b'\xf1\x875Q0959655CA\xf1\x890403\xf1\x82\x1331310031313100313151013141319331423100', - b'\xf1\x875Q0959655CA\xf1\x890403\xf1\x82\x1331310031313100313151823143319331423100', - b'\xf1\x875Q0959655CH\xf1\x890421\xf1\x82\x1333310031313100313152025350539331463100', - b'\xf1\x875Q0959655CH\xf1\x890421\xf1\x82\x1333310031313100313152855372539331463100', - ], - (Ecu.eps, 0x712, None): [ - b'\xf1\x875Q0909143K \xf1\x892033\xf1\x820514UZ070203', - b'\xf1\x875Q0909143M \xf1\x892041\xf1\x820522UZ050303', - b'\xf1\x875Q0909143M \xf1\x892041\xf1\x820522UZ070303', - b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820526UZ060505', - b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820526UZ070505', - b'\xf1\x875Q0910143B \xf1\x892201\xf1\x82\x0563UZ060600', - b'\xf1\x875Q0910143B \xf1\x892201\xf1\x82\x0563UZ060700', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567UZ070500', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567UZ070600', - b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567UZ070700', - ], - (Ecu.fwdRadar, 0x757, None): [ - b'\xf1\x873Q0907572B \xf1\x890192', - b'\xf1\x873Q0907572B \xf1\x890194', - b'\xf1\x873Q0907572C \xf1\x890195', - b'\xf1\x875Q0907572R \xf1\x890771', - b'\xf1\x875Q0907572S \xf1\x890780', - ], - }, -} diff --git a/car/volkswagen/interface.py b/car/volkswagen/interface.py deleted file mode 100644 index 91cd300e92..0000000000 --- a/car/volkswagen/interface.py +++ /dev/null @@ -1,133 +0,0 @@ -from cereal import car -from panda import Panda -from openpilot.selfdrive.car import get_safety_config -from openpilot.selfdrive.car.interfaces import CarInterfaceBase -from openpilot.selfdrive.car.volkswagen.values import CAR, CANBUS, CarControllerParams, NetworkLocation, TransmissionType, GearShifter, VolkswagenFlags - -ButtonType = car.CarState.ButtonEvent.Type -EventName = car.CarEvent.EventName - - -class CarInterface(CarInterfaceBase): - def __init__(self, CP, CarController, CarState): - super().__init__(CP, CarController, CarState) - - if CP.networkLocation == NetworkLocation.fwdCamera: - self.ext_bus = CANBUS.pt - self.cp_ext = self.cp - else: - self.ext_bus = CANBUS.cam - self.cp_ext = self.cp_cam - - @staticmethod - def _get_params(ret, candidate: CAR, fingerprint, car_fw, experimental_long, docs): - ret.carName = "volkswagen" - ret.radarUnavailable = True - - if ret.flags & VolkswagenFlags.PQ: - # Set global PQ35/PQ46/NMS parameters - ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.volkswagenPq)] - ret.enableBsm = 0x3BA in fingerprint[0] # SWA_1 - - if 0x440 in fingerprint[0] or docs: # Getriebe_1 - ret.transmissionType = TransmissionType.automatic - else: - ret.transmissionType = TransmissionType.manual - - if any(msg in fingerprint[1] for msg in (0x1A0, 0xC2)): # Bremse_1, Lenkwinkel_1 - ret.networkLocation = NetworkLocation.gateway - else: - ret.networkLocation = NetworkLocation.fwdCamera - - # The PQ port is in dashcam-only mode due to a fixed six-minute maximum timer on HCA steering. An unsupported - # EPS flash update to work around this timer, and enable steering down to zero, is available from: - # https://github.com/pd0wm/pq-flasher - # It is documented in a four-part blog series: - # https://blog.willemmelching.nl/carhacking/2022/01/02/vw-part1/ - # Panda ALLOW_DEBUG firmware required. - ret.dashcamOnly = True - - else: - # Set global MQB parameters - ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.volkswagen)] - ret.enableBsm = 0x30F in fingerprint[0] # SWA_01 - - if 0xAD in fingerprint[0] or docs: # Getriebe_11 - ret.transmissionType = TransmissionType.automatic - elif 0x187 in fingerprint[0]: # EV_Gearshift - ret.transmissionType = TransmissionType.direct - else: - ret.transmissionType = TransmissionType.manual - - if any(msg in fingerprint[1] for msg in (0x40, 0x86, 0xB2, 0xFD)): # Airbag_01, LWI_01, ESP_19, ESP_21 - ret.networkLocation = NetworkLocation.gateway - else: - ret.networkLocation = NetworkLocation.fwdCamera - - if 0x126 in fingerprint[2]: # HCA_01 - ret.flags |= VolkswagenFlags.STOCK_HCA_PRESENT.value - - # Global lateral tuning defaults, can be overridden per-vehicle - - ret.steerLimitTimer = 0.4 - if ret.flags & VolkswagenFlags.PQ: - ret.steerActuatorDelay = 0.2 - CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) - else: - ret.steerActuatorDelay = 0.1 - ret.lateralTuning.pid.kpBP = [0.] - ret.lateralTuning.pid.kiBP = [0.] - ret.lateralTuning.pid.kf = 0.00006 - ret.lateralTuning.pid.kpV = [0.6] - ret.lateralTuning.pid.kiV = [0.2] - - # Global longitudinal tuning defaults, can be overridden per-vehicle - - ret.experimentalLongitudinalAvailable = ret.networkLocation == NetworkLocation.gateway or docs - if experimental_long: - # Proof-of-concept, prep for E2E only. No radar points available. Panda ALLOW_DEBUG firmware required. - ret.openpilotLongitudinalControl = True - ret.safetyConfigs[0].safetyParam |= Panda.FLAG_VOLKSWAGEN_LONG_CONTROL - if ret.transmissionType == TransmissionType.manual: - ret.minEnableSpeed = 4.5 - - ret.pcmCruise = not ret.openpilotLongitudinalControl - ret.stoppingControl = True - ret.stopAccel = -0.55 - ret.vEgoStarting = 0.1 - ret.vEgoStopping = 0.5 - ret.longitudinalTuning.kpV = [0.1] - ret.longitudinalTuning.kiV = [0.0] - ret.autoResumeSng = ret.minEnableSpeed == -1 - - return ret - - # returns a car.CarState - def _update(self, c): - ret = self.CS.update(self.cp, self.cp_cam, self.cp_ext, self.CP.transmissionType) - - events = self.create_common_events(ret, extra_gears=[GearShifter.eco, GearShifter.sport, GearShifter.manumatic], - pcm_enable=not self.CS.CP.openpilotLongitudinalControl, - enable_buttons=(ButtonType.setCruise, ButtonType.resumeCruise)) - - # Low speed steer alert hysteresis logic - if (self.CP.minSteerSpeed - 1e-3) > CarControllerParams.DEFAULT_MIN_STEER_SPEED and ret.vEgo < (self.CP.minSteerSpeed + 1.): - self.low_speed_alert = True - elif ret.vEgo > (self.CP.minSteerSpeed + 2.): - self.low_speed_alert = False - if self.low_speed_alert: - events.add(EventName.belowSteerSpeed) - - if self.CS.CP.openpilotLongitudinalControl: - if ret.vEgo < self.CP.minEnableSpeed + 0.5: - events.add(EventName.belowEngageSpeed) - if c.enabled and ret.vEgo < self.CP.minEnableSpeed: - events.add(EventName.speedTooLow) - - if self.CC.eps_timer_soft_disable_alert: - events.add(EventName.steerTimeLimit) - - ret.events = events.to_msg() - - return ret - diff --git a/car/volkswagen/mqbcan.py b/car/volkswagen/mqbcan.py deleted file mode 100644 index 763908b6b2..0000000000 --- a/car/volkswagen/mqbcan.py +++ /dev/null @@ -1,137 +0,0 @@ -def create_steering_control(packer, bus, apply_steer, lkas_enabled): - values = { - "HCA_01_Status_HCA": 5 if lkas_enabled else 3, - "HCA_01_LM_Offset": abs(apply_steer), - "HCA_01_LM_OffSign": 1 if apply_steer < 0 else 0, - "HCA_01_Vib_Freq": 18, - "HCA_01_Sendestatus": 1 if lkas_enabled else 0, - "EA_ACC_Wunschgeschwindigkeit": 327.36, - } - return packer.make_can_msg("HCA_01", bus, values) - - -def create_eps_update(packer, bus, eps_stock_values, ea_simulated_torque): - values = {s: eps_stock_values[s] for s in [ - "COUNTER", # Sync counter value to EPS output - "EPS_Lenkungstyp", # EPS rack type - "EPS_Berechneter_LW", # Absolute raw steering angle - "EPS_VZ_BLW", # Raw steering angle sign - "EPS_HCA_Status", # EPS HCA control status - ]} - - values.update({ - # Absolute driver torque input and sign, with EA inactivity mitigation - "EPS_Lenkmoment": abs(ea_simulated_torque), - "EPS_VZ_Lenkmoment": 1 if ea_simulated_torque < 0 else 0, - }) - - return packer.make_can_msg("LH_EPS_03", bus, values) - - -def create_lka_hud_control(packer, bus, ldw_stock_values, lat_active, steering_pressed, hud_alert, hud_control): - values = {} - if len(ldw_stock_values): - values = {s: ldw_stock_values[s] for s in [ - "LDW_SW_Warnung_links", # Blind spot in warning mode on left side due to lane departure - "LDW_SW_Warnung_rechts", # Blind spot in warning mode on right side due to lane departure - "LDW_Seite_DLCTLC", # Direction of most likely lane departure (left or right) - "LDW_DLC", # Lane departure, distance to line crossing - "LDW_TLC", # Lane departure, time to line crossing - ]} - - values.update({ - "LDW_Status_LED_gelb": 1 if lat_active and steering_pressed else 0, - "LDW_Status_LED_gruen": 1 if lat_active and not steering_pressed else 0, - "LDW_Lernmodus_links": 3 if hud_control.leftLaneDepart else 1 + hud_control.leftLaneVisible, - "LDW_Lernmodus_rechts": 3 if hud_control.rightLaneDepart else 1 + hud_control.rightLaneVisible, - "LDW_Texte": hud_alert, - }) - return packer.make_can_msg("LDW_02", bus, values) - - -def create_acc_buttons_control(packer, bus, gra_stock_values, cancel=False, resume=False): - values = {s: gra_stock_values[s] for s in [ - "GRA_Hauptschalter", # ACC button, on/off - "GRA_Typ_Hauptschalter", # ACC main button type - "GRA_Codierung", # ACC button configuration/coding - "GRA_Tip_Stufe_2", # unknown related to stalk type - "GRA_ButtonTypeInfo", # unknown related to stalk type - ]} - - values.update({ - "COUNTER": (gra_stock_values["COUNTER"] + 1) % 16, - "GRA_Abbrechen": cancel, - "GRA_Tip_Wiederaufnahme": resume, - }) - - return packer.make_can_msg("GRA_ACC_01", bus, values) - - -def acc_control_value(main_switch_on, acc_faulted, long_active): - if acc_faulted: - acc_control = 6 - elif long_active: - acc_control = 3 - elif main_switch_on: - acc_control = 2 - else: - acc_control = 0 - - return acc_control - - -def acc_hud_status_value(main_switch_on, acc_faulted, long_active): - # TODO: happens to resemble the ACC control value for now, but extend this for init/gas override later - return acc_control_value(main_switch_on, acc_faulted, long_active) - - -def create_acc_accel_control(packer, bus, acc_type, acc_enabled, accel, acc_control, stopping, starting, esp_hold): - commands = [] - - acc_06_values = { - "ACC_Typ": acc_type, - "ACC_Status_ACC": acc_control, - "ACC_StartStopp_Info": acc_enabled, - "ACC_Sollbeschleunigung_02": accel if acc_enabled else 3.01, - "ACC_zul_Regelabw_unten": 0.2, # TODO: dynamic adjustment of comfort-band - "ACC_zul_Regelabw_oben": 0.2, # TODO: dynamic adjustment of comfort-band - "ACC_neg_Sollbeschl_Grad_02": 4.0 if acc_enabled else 0, # TODO: dynamic adjustment of jerk limits - "ACC_pos_Sollbeschl_Grad_02": 4.0 if acc_enabled else 0, # TODO: dynamic adjustment of jerk limits - "ACC_Anfahren": starting, - "ACC_Anhalten": stopping, - } - commands.append(packer.make_can_msg("ACC_06", bus, acc_06_values)) - - if starting: - acc_hold_type = 4 # hold release / startup - elif esp_hold: - acc_hold_type = 3 # hold standby - elif stopping: - acc_hold_type = 1 # hold request - else: - acc_hold_type = 0 - - acc_07_values = { - "ACC_Anhalteweg": 0.3 if stopping else 20.46, # Distance to stop (stopping coordinator handles terminal roll-out) - "ACC_Freilauf_Info": 2 if acc_enabled else 0, - "ACC_Folgebeschl": 3.02, # Not using secondary controller accel unless and until we understand its impact - "ACC_Sollbeschleunigung_02": accel if acc_enabled else 3.01, - "ACC_Anforderung_HMS": acc_hold_type, - "ACC_Anfahren": starting, - "ACC_Anhalten": stopping, - } - commands.append(packer.make_can_msg("ACC_07", bus, acc_07_values)) - - return commands - - -def create_acc_hud_control(packer, bus, acc_hud_status, set_speed, lead_distance, distance): - values = { - "ACC_Status_Anzeige": acc_hud_status, - "ACC_Wunschgeschw_02": set_speed if set_speed < 250 else 327.36, - "ACC_Gesetzte_Zeitluecke": distance + 2, - "ACC_Display_Prio": 3, - "ACC_Abstandsindex": lead_distance, - } - - return packer.make_can_msg("ACC_02", bus, values) diff --git a/car/volkswagen/pqcan.py b/car/volkswagen/pqcan.py deleted file mode 100644 index f8d161b970..0000000000 --- a/car/volkswagen/pqcan.py +++ /dev/null @@ -1,105 +0,0 @@ -def create_steering_control(packer, bus, apply_steer, lkas_enabled): - values = { - "LM_Offset": abs(apply_steer), - "LM_OffSign": 1 if apply_steer < 0 else 0, - "HCA_Status": 5 if (lkas_enabled and apply_steer != 0) else 3, - "Vib_Freq": 16, - } - - return packer.make_can_msg("HCA_1", bus, values) - - -def create_lka_hud_control(packer, bus, ldw_stock_values, lat_active, steering_pressed, hud_alert, hud_control): - values = {} - if len(ldw_stock_values): - values = {s: ldw_stock_values[s] for s in [ - "LDW_SW_Warnung_links", # Blind spot in warning mode on left side due to lane departure - "LDW_SW_Warnung_rechts", # Blind spot in warning mode on right side due to lane departure - "LDW_Seite_DLCTLC", # Direction of most likely lane departure (left or right) - "LDW_DLC", # Lane departure, distance to line crossing - "LDW_TLC", # Lane departure, time to line crossing - ]} - - values.update({ - "LDW_Lampe_gelb": 1 if lat_active and steering_pressed else 0, - "LDW_Lampe_gruen": 1 if lat_active and not steering_pressed else 0, - "LDW_Lernmodus_links": 3 if hud_control.leftLaneDepart else 1 + hud_control.leftLaneVisible, - "LDW_Lernmodus_rechts": 3 if hud_control.rightLaneDepart else 1 + hud_control.rightLaneVisible, - "LDW_Textbits": hud_alert, - }) - - return packer.make_can_msg("LDW_Status", bus, values) - - -def create_acc_buttons_control(packer, bus, gra_stock_values, cancel=False, resume=False): - values = {s: gra_stock_values[s] for s in [ - "GRA_Hauptschalt", # ACC button, on/off - "GRA_Typ_Hauptschalt", # ACC button, momentary vs latching - "GRA_Kodierinfo", # ACC button, configuration - "GRA_Sender", # ACC button, CAN message originator - ]} - - values.update({ - "COUNTER": (gra_stock_values["COUNTER"] + 1) % 16, - "GRA_Abbrechen": cancel, - "GRA_Recall": resume, - }) - - return packer.make_can_msg("GRA_Neu", bus, values) - - -def acc_control_value(main_switch_on, acc_faulted, long_active): - if long_active: - acc_control = 1 - elif main_switch_on: - acc_control = 2 - else: - acc_control = 0 - - return acc_control - - -def acc_hud_status_value(main_switch_on, acc_faulted, long_active): - if acc_faulted: - hud_status = 6 - elif long_active: - hud_status = 3 - elif main_switch_on: - hud_status = 2 - else: - hud_status = 0 - - return hud_status - - -def create_acc_accel_control(packer, bus, acc_type, acc_enabled, accel, acc_control, stopping, starting, esp_hold): - commands = [] - - values = { - "ACS_Sta_ADR": acc_control, - "ACS_StSt_Info": acc_enabled, - "ACS_Typ_ACC": acc_type, - "ACS_Anhaltewunsch": acc_type == 1 and stopping, - "ACS_FreigSollB": acc_enabled, - "ACS_Sollbeschl": accel if acc_enabled else 3.01, - "ACS_zul_Regelabw": 0.2 if acc_enabled else 1.27, - "ACS_max_AendGrad": 3.0 if acc_enabled else 5.08, - } - - commands.append(packer.make_can_msg("ACC_System", bus, values)) - - return commands - - -def create_acc_hud_control(packer, bus, acc_hud_status, set_speed, lead_distance, distance): - values = { - "ACA_StaACC": acc_hud_status, - "ACA_Zeitluecke": distance + 2, - "ACA_V_Wunsch": set_speed, - "ACA_gemZeitl": lead_distance, - "ACA_PrioDisp": 3, - # TODO: restore dynamic pop-to-foreground/highlight behavior with ACA_PrioDisp and ACA_AnzDisplay - # TODO: ACA_kmh_mph handling probably needed to resolve rounding errors in displayed setpoint - } - - return packer.make_can_msg("ACC_GRA_Anzeige", bus, values) diff --git a/car/volkswagen/radar_interface.py b/car/volkswagen/radar_interface.py deleted file mode 100644 index e654bd61fd..0000000000 --- a/car/volkswagen/radar_interface.py +++ /dev/null @@ -1,4 +0,0 @@ -from openpilot.selfdrive.car.interfaces import RadarInterfaceBase - -class RadarInterface(RadarInterfaceBase): - pass diff --git a/car/volkswagen/tests/test_volkswagen.py b/car/volkswagen/tests/test_volkswagen.py deleted file mode 100644 index 0002578105..0000000000 --- a/car/volkswagen/tests/test_volkswagen.py +++ /dev/null @@ -1,60 +0,0 @@ -import random -import re - -from cereal import car -from openpilot.selfdrive.car.volkswagen.values import CAR, FW_QUERY_CONFIG, WMI -from openpilot.selfdrive.car.volkswagen.fingerprints import FW_VERSIONS - -Ecu = car.CarParams.Ecu - -CHASSIS_CODE_PATTERN = re.compile('[A-Z0-9]{2}') -# TODO: determine the unknown groups -SPARE_PART_FW_PATTERN = re.compile(b'\xf1\x87(?P[0-9][0-9A-Z]{2})(?P[0-9][0-9A-Z][0-9])(?P[0-9A-Z]{2}[0-9])([A-Z0-9]| )') - - -class TestVolkswagenPlatformConfigs: - def test_spare_part_fw_pattern(self, subtests): - # Relied on for determining if a FW is likely VW - for platform, ecus in FW_VERSIONS.items(): - with subtests.test(platform=platform.value): - for fws in ecus.values(): - for fw in fws: - assert SPARE_PART_FW_PATTERN.match(fw) is not None, f"Bad FW: {fw}" - - def test_chassis_codes(self, subtests): - for platform in CAR: - with subtests.test(platform=platform.value): - assert len(platform.config.wmis) > 0, "WMIs not set" - assert len(platform.config.chassis_codes) > 0, "Chassis codes not set" - assert all(CHASSIS_CODE_PATTERN.match(cc) for cc in \ - platform.config.chassis_codes), "Bad chassis codes" - - # No two platforms should share chassis codes - for comp in CAR: - if platform == comp: - continue - assert set() == platform.config.chassis_codes & comp.config.chassis_codes, \ - f"Shared chassis codes: {comp}" - - def test_custom_fuzzy_fingerprinting(self, subtests): - all_radar_fw = list({fw for ecus in FW_VERSIONS.values() for fw in ecus[Ecu.fwdRadar, 0x757, None]}) - - for platform in CAR: - with subtests.test(platform=platform.name): - for wmi in WMI: - for chassis_code in platform.config.chassis_codes | {"00"}: - vin = ["0"] * 17 - vin[0:3] = wmi - vin[6:8] = chassis_code - vin = "".join(vin) - - # Check a few FW cases - expected, unexpected - for radar_fw in random.sample(all_radar_fw, 5) + [b'\xf1\x875Q0907572G \xf1\x890571', b'\xf1\x877H9907572AA\xf1\x890396']: - should_match = ((wmi in platform.config.wmis and chassis_code in platform.config.chassis_codes) and - radar_fw in all_radar_fw) - - live_fws = {(0x757, None): [radar_fw]} - matches = FW_QUERY_CONFIG.match_fw_to_car_fuzzy(live_fws, vin, FW_VERSIONS) - - expected_matches = {platform} if should_match else set() - assert expected_matches == matches, "Bad match" diff --git a/car/volkswagen/values.py b/car/volkswagen/values.py deleted file mode 100644 index 4d317176be..0000000000 --- a/car/volkswagen/values.py +++ /dev/null @@ -1,516 +0,0 @@ -from collections import defaultdict, namedtuple -from dataclasses import dataclass, field -from enum import Enum, IntFlag, StrEnum - -from cereal import car -from panda.python import uds -from opendbc.can.can_define import CANDefine -from openpilot.common.conversions import Conversions as CV -from openpilot.selfdrive.car import dbc_dict, CarSpecs, DbcDict, PlatformConfig, Platforms -from openpilot.selfdrive.car.docs_definitions import CarFootnote, CarHarness, CarDocs, CarParts, Column, \ - Device -from openpilot.selfdrive.car.fw_query_definitions import EcuAddrSubAddr, FwQueryConfig, Request, p16 - -Ecu = car.CarParams.Ecu -NetworkLocation = car.CarParams.NetworkLocation -TransmissionType = car.CarParams.TransmissionType -GearShifter = car.CarState.GearShifter -Button = namedtuple('Button', ['event_type', 'can_addr', 'can_msg', 'values']) - - -class CarControllerParams: - STEER_STEP = 2 # HCA_01/HCA_1 message frequency 50Hz - ACC_CONTROL_STEP = 2 # ACC_06/ACC_07/ACC_System frequency 50Hz - - # Documented lateral limits: 3.00 Nm max, rate of change 5.00 Nm/sec. - # MQB vs PQ maximums are shared, but rate-of-change limited differently - # based on safety requirements driven by lateral accel testing. - - STEER_MAX = 300 # Max heading control assist torque 3.00 Nm - STEER_DRIVER_MULTIPLIER = 3 # weight driver torque heavily - STEER_DRIVER_FACTOR = 1 # from dbc - - STEER_TIME_MAX = 360 # Max time that EPS allows uninterrupted HCA steering control - STEER_TIME_ALERT = STEER_TIME_MAX - 10 # If mitigation fails, time to soft disengage before EPS timer expires - STEER_TIME_STUCK_TORQUE = 1.9 # EPS limits same torque to 6 seconds, reset timer 3x within that period - - DEFAULT_MIN_STEER_SPEED = 0.4 # m/s, newer EPS racks fault below this speed, don't show a low speed alert - - ACCEL_MAX = 2.0 # 2.0 m/s max acceleration - ACCEL_MIN = -3.5 # 3.5 m/s max deceleration - - def __init__(self, CP): - can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) - - if CP.flags & VolkswagenFlags.PQ: - self.LDW_STEP = 5 # LDW_1 message frequency 20Hz - self.ACC_HUD_STEP = 4 # ACC_GRA_Anzeige frequency 25Hz - self.STEER_DRIVER_ALLOWANCE = 80 # Driver intervention threshold 0.8 Nm - self.STEER_DELTA_UP = 6 # Max HCA reached in 1.00s (STEER_MAX / (50Hz * 1.00)) - self.STEER_DELTA_DOWN = 10 # Min HCA reached in 0.60s (STEER_MAX / (50Hz * 0.60)) - - if CP.transmissionType == TransmissionType.automatic: - self.shifter_values = can_define.dv["Getriebe_1"]["Waehlhebelposition__Getriebe_1_"] - self.hca_status_values = can_define.dv["Lenkhilfe_2"]["LH2_Sta_HCA"] - - self.BUTTONS = [ - Button(car.CarState.ButtonEvent.Type.setCruise, "GRA_Neu", "GRA_Neu_Setzen", [1]), - Button(car.CarState.ButtonEvent.Type.resumeCruise, "GRA_Neu", "GRA_Recall", [1]), - Button(car.CarState.ButtonEvent.Type.accelCruise, "GRA_Neu", "GRA_Up_kurz", [1]), - Button(car.CarState.ButtonEvent.Type.decelCruise, "GRA_Neu", "GRA_Down_kurz", [1]), - Button(car.CarState.ButtonEvent.Type.cancel, "GRA_Neu", "GRA_Abbrechen", [1]), - Button(car.CarState.ButtonEvent.Type.gapAdjustCruise, "GRA_Neu", "GRA_Zeitluecke", [1]), - ] - - self.LDW_MESSAGES = { - "none": 0, # Nothing to display - "laneAssistUnavail": 1, # "Lane Assist currently not available." - "laneAssistUnavailSysError": 2, # "Lane Assist system error" - "laneAssistUnavailNoSensorView": 3, # "Lane Assist not available. No sensor view." - "laneAssistTakeOver": 4, # "Lane Assist: Please Take Over Steering" - "laneAssistDeactivTrailer": 5, # "Lane Assist: no function with trailer" - } - - else: - self.LDW_STEP = 10 # LDW_02 message frequency 10Hz - self.ACC_HUD_STEP = 6 # ACC_02 message frequency 16Hz - self.STEER_DRIVER_ALLOWANCE = 80 # Driver intervention threshold 0.8 Nm - self.STEER_DELTA_UP = 4 # Max HCA reached in 1.50s (STEER_MAX / (50Hz * 1.50)) - self.STEER_DELTA_DOWN = 10 # Min HCA reached in 0.60s (STEER_MAX / (50Hz * 0.60)) - - if CP.transmissionType == TransmissionType.automatic: - self.shifter_values = can_define.dv["Getriebe_11"]["GE_Fahrstufe"] - elif CP.transmissionType == TransmissionType.direct: - self.shifter_values = can_define.dv["EV_Gearshift"]["GearPosition"] - self.hca_status_values = can_define.dv["LH_EPS_03"]["EPS_HCA_Status"] - - self.BUTTONS = [ - Button(car.CarState.ButtonEvent.Type.setCruise, "GRA_ACC_01", "GRA_Tip_Setzen", [1]), - Button(car.CarState.ButtonEvent.Type.resumeCruise, "GRA_ACC_01", "GRA_Tip_Wiederaufnahme", [1]), - Button(car.CarState.ButtonEvent.Type.accelCruise, "GRA_ACC_01", "GRA_Tip_Hoch", [1]), - Button(car.CarState.ButtonEvent.Type.decelCruise, "GRA_ACC_01", "GRA_Tip_Runter", [1]), - Button(car.CarState.ButtonEvent.Type.cancel, "GRA_ACC_01", "GRA_Abbrechen", [1]), - Button(car.CarState.ButtonEvent.Type.gapAdjustCruise, "GRA_ACC_01", "GRA_Verstellung_Zeitluecke", [1]), - ] - - self.LDW_MESSAGES = { - "none": 0, # Nothing to display - "laneAssistUnavailChime": 1, # "Lane Assist currently not available." with chime - "laneAssistUnavailNoSensorChime": 3, # "Lane Assist not available. No sensor view." with chime - "laneAssistTakeOverUrgent": 4, # "Lane Assist: Please Take Over Steering" with urgent beep - "emergencyAssistUrgent": 6, # "Emergency Assist: Please Take Over Steering" with urgent beep - "laneAssistTakeOverChime": 7, # "Lane Assist: Please Take Over Steering" with chime - "laneAssistTakeOver": 8, # "Lane Assist: Please Take Over Steering" silent - "emergencyAssistChangingLanes": 9, # "Emergency Assist: Changing lanes..." with urgent beep - "laneAssistDeactivated": 10, # "Lane Assist deactivated." silent with persistent icon afterward - } - - -class CANBUS: - pt = 0 - cam = 2 - - -class WMI(StrEnum): - VOLKSWAGEN_USA_SUV = "1V2" - VOLKSWAGEN_USA_CAR = "1VW" - VOLKSWAGEN_MEXICO_SUV = "3VV" - VOLKSWAGEN_MEXICO_CAR = "3VW" - VOLKSWAGEN_ARGENTINA = "8AW" - VOLKSWAGEN_BRASIL = "9BW" - SAIC_VOLKSWAGEN = "LSV" - SKODA = "TMB" - SEAT = "VSS" - AUDI_EUROPE_MPV = "WA1" - AUDI_GERMANY_CAR = "WAU" - MAN = "WMA" - AUDI_SPORT = "WUA" - VOLKSWAGEN_COMMERCIAL = "WV1" - VOLKSWAGEN_COMMERCIAL_BUS_VAN = "WV2" - VOLKSWAGEN_EUROPE_SUV = "WVG" - VOLKSWAGEN_EUROPE_CAR = "WVW" - VOLKSWAGEN_GROUP_RUS = "XW8" - - -class VolkswagenFlags(IntFlag): - # Detected flags - STOCK_HCA_PRESENT = 1 - - # Static flags - PQ = 2 - - -@dataclass -class VolkswagenMQBPlatformConfig(PlatformConfig): - dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict('vw_mqb_2010', None)) - # Volkswagen uses the VIN WMI and chassis code to match in the absence of the comma power - # on camera-integrated cars, as we lose too many ECUs to reliably identify the vehicle - chassis_codes: set[str] = field(default_factory=set) - wmis: set[WMI] = field(default_factory=set) - - -@dataclass -class VolkswagenPQPlatformConfig(VolkswagenMQBPlatformConfig): - dbc_dict: DbcDict = field(default_factory=lambda: dbc_dict('vw_golf_mk4', None)) - - def init(self): - self.flags |= VolkswagenFlags.PQ - - -@dataclass(frozen=True, kw_only=True) -class VolkswagenCarSpecs(CarSpecs): - centerToFrontRatio: float = 0.45 - steerRatio: float = 15.6 - minSteerSpeed: float = CarControllerParams.DEFAULT_MIN_STEER_SPEED - - -class Footnote(Enum): - KAMIQ = CarFootnote( - "Not including the China market Kamiq, which is based on the (currently) unsupported PQ34 platform.", - Column.MODEL) - PASSAT = CarFootnote( - "Refers only to the MQB-based European B8 Passat, not the NMS Passat in the USA/China/Mideast markets.", - Column.MODEL) - SKODA_HEATED_WINDSHIELD = CarFootnote( - "Some Škoda vehicles are equipped with heated windshields, which are known " + - "to block GPS signal needed for some comma 3X functionality.", - Column.MODEL) - VW_EXP_LONG = CarFootnote( - "Only available for vehicles using a gateway (J533) harness. At this time, vehicles using a camera harness " + - "are limited to using stock ACC.", - Column.LONGITUDINAL) - VW_MQB_A0 = CarFootnote( - "Model-years 2022 and beyond may have a combined CAN gateway and BCM, which is supported by openpilot " + - "in software, but doesn't yet have a harness available from the comma store.", - Column.HARDWARE) - - -@dataclass -class VWCarDocs(CarDocs): - package: str = "Adaptive Cruise Control (ACC) & Lane Assist" - car_parts: CarParts = field(default_factory=CarParts.common([CarHarness.j533])) - - def init_make(self, CP: car.CarParams): - self.footnotes.append(Footnote.VW_EXP_LONG) - if "SKODA" in CP.carFingerprint: - self.footnotes.append(Footnote.SKODA_HEATED_WINDSHIELD) - - if CP.carFingerprint in (CAR.VOLKSWAGEN_CRAFTER_MK2, CAR.VOLKSWAGEN_TRANSPORTER_T61): - self.car_parts = CarParts([Device.threex_angled_mount, CarHarness.j533]) - - if abs(CP.minSteerSpeed - CarControllerParams.DEFAULT_MIN_STEER_SPEED) < 1e-3: - self.min_steer_speed = 0 - - -# Check the 7th and 8th characters of the VIN before adding a new CAR. If the -# chassis code is already listed below, don't add a new CAR, just add to the -# FW_VERSIONS for that existing CAR. - -class CAR(Platforms): - config: VolkswagenMQBPlatformConfig | VolkswagenPQPlatformConfig - - VOLKSWAGEN_ARTEON_MK1 = VolkswagenMQBPlatformConfig( - [ - VWCarDocs("Volkswagen Arteon 2018-23", video_link="https://youtu.be/FAomFKPFlDA"), - VWCarDocs("Volkswagen Arteon R 2020-23", video_link="https://youtu.be/FAomFKPFlDA"), - VWCarDocs("Volkswagen Arteon eHybrid 2020-23", video_link="https://youtu.be/FAomFKPFlDA"), - VWCarDocs("Volkswagen Arteon Shooting Brake 2020-23", video_link="https://youtu.be/FAomFKPFlDA"), - VWCarDocs("Volkswagen CC 2018-22", video_link="https://youtu.be/FAomFKPFlDA"), - ], - VolkswagenCarSpecs(mass=1733, wheelbase=2.84), - chassis_codes={"AN", "3H"}, - wmis={WMI.VOLKSWAGEN_EUROPE_CAR}, - ) - VOLKSWAGEN_ATLAS_MK1 = VolkswagenMQBPlatformConfig( - [ - VWCarDocs("Volkswagen Atlas 2018-23"), - VWCarDocs("Volkswagen Atlas Cross Sport 2020-22"), - VWCarDocs("Volkswagen Teramont 2018-22"), - VWCarDocs("Volkswagen Teramont Cross Sport 2021-22"), - VWCarDocs("Volkswagen Teramont X 2021-22"), - ], - VolkswagenCarSpecs(mass=2011, wheelbase=2.98), - chassis_codes={"CA"}, - wmis={WMI.VOLKSWAGEN_USA_SUV, WMI.VOLKSWAGEN_EUROPE_SUV}, - ) - VOLKSWAGEN_CADDY_MK3 = VolkswagenPQPlatformConfig( - [ - VWCarDocs("Volkswagen Caddy 2019"), - VWCarDocs("Volkswagen Caddy Maxi 2019"), - ], - VolkswagenCarSpecs(mass=1613, wheelbase=2.6, minSteerSpeed=21 * CV.KPH_TO_MS), - chassis_codes={"2K"}, - wmis={WMI.VOLKSWAGEN_COMMERCIAL_BUS_VAN}, - ) - VOLKSWAGEN_CRAFTER_MK2 = VolkswagenMQBPlatformConfig( - [ - VWCarDocs("Volkswagen Crafter 2017-23", video_link="https://youtu.be/4100gLeabmo"), - VWCarDocs("Volkswagen e-Crafter 2018-23", video_link="https://youtu.be/4100gLeabmo"), - VWCarDocs("Volkswagen Grand California 2019-23", video_link="https://youtu.be/4100gLeabmo"), - VWCarDocs("MAN TGE 2017-23", video_link="https://youtu.be/4100gLeabmo"), - VWCarDocs("MAN eTGE 2020-23", video_link="https://youtu.be/4100gLeabmo"), - ], - VolkswagenCarSpecs(mass=2100, wheelbase=3.64, minSteerSpeed=50 * CV.KPH_TO_MS), - chassis_codes={"SY", "SZ"}, - wmis={WMI.VOLKSWAGEN_COMMERCIAL, WMI.MAN}, - ) - VOLKSWAGEN_GOLF_MK7 = VolkswagenMQBPlatformConfig( - [ - VWCarDocs("Volkswagen e-Golf 2014-20"), - VWCarDocs("Volkswagen Golf 2015-20", auto_resume=False), - VWCarDocs("Volkswagen Golf Alltrack 2015-19", auto_resume=False), - VWCarDocs("Volkswagen Golf GTD 2015-20"), - VWCarDocs("Volkswagen Golf GTE 2015-20"), - VWCarDocs("Volkswagen Golf GTI 2015-21", auto_resume=False), - VWCarDocs("Volkswagen Golf R 2015-19"), - VWCarDocs("Volkswagen Golf SportsVan 2015-20"), - ], - VolkswagenCarSpecs(mass=1397, wheelbase=2.62), - chassis_codes={"5G", "AU", "BA", "BE"}, - wmis={WMI.VOLKSWAGEN_MEXICO_CAR, WMI.VOLKSWAGEN_EUROPE_CAR}, - ) - VOLKSWAGEN_JETTA_MK7 = VolkswagenMQBPlatformConfig( - [ - VWCarDocs("Volkswagen Jetta 2018-24"), - VWCarDocs("Volkswagen Jetta GLI 2021-24"), - ], - VolkswagenCarSpecs(mass=1328, wheelbase=2.71), - chassis_codes={"BU"}, - wmis={WMI.VOLKSWAGEN_MEXICO_CAR, WMI.VOLKSWAGEN_EUROPE_CAR}, - ) - VOLKSWAGEN_PASSAT_MK8 = VolkswagenMQBPlatformConfig( - [ - VWCarDocs("Volkswagen Passat 2015-22", footnotes=[Footnote.PASSAT]), - VWCarDocs("Volkswagen Passat Alltrack 2015-22"), - VWCarDocs("Volkswagen Passat GTE 2015-22"), - ], - VolkswagenCarSpecs(mass=1551, wheelbase=2.79), - chassis_codes={"3C", "3G"}, - wmis={WMI.VOLKSWAGEN_EUROPE_CAR}, - ) - VOLKSWAGEN_PASSAT_NMS = VolkswagenPQPlatformConfig( - [VWCarDocs("Volkswagen Passat NMS 2017-22")], - VolkswagenCarSpecs(mass=1503, wheelbase=2.80, minSteerSpeed=50 * CV.KPH_TO_MS, minEnableSpeed=20 * CV.KPH_TO_MS), - chassis_codes={"A3"}, - wmis={WMI.VOLKSWAGEN_USA_CAR}, - ) - VOLKSWAGEN_POLO_MK6 = VolkswagenMQBPlatformConfig( - [ - VWCarDocs("Volkswagen Polo 2018-23", footnotes=[Footnote.VW_MQB_A0]), - VWCarDocs("Volkswagen Polo GTI 2018-23", footnotes=[Footnote.VW_MQB_A0]), - ], - VolkswagenCarSpecs(mass=1230, wheelbase=2.55), - chassis_codes={"AW"}, - wmis={WMI.VOLKSWAGEN_EUROPE_CAR}, - ) - VOLKSWAGEN_SHARAN_MK2 = VolkswagenPQPlatformConfig( - [ - VWCarDocs("Volkswagen Sharan 2018-22"), - VWCarDocs("SEAT Alhambra 2018-20"), - ], - VolkswagenCarSpecs(mass=1639, wheelbase=2.92, minSteerSpeed=50 * CV.KPH_TO_MS), - chassis_codes={"7N"}, - wmis={WMI.VOLKSWAGEN_EUROPE_CAR}, - ) - VOLKSWAGEN_TAOS_MK1 = VolkswagenMQBPlatformConfig( - [VWCarDocs("Volkswagen Taos 2022-23")], - VolkswagenCarSpecs(mass=1498, wheelbase=2.69), - chassis_codes={"B2"}, - wmis={WMI.VOLKSWAGEN_MEXICO_SUV, WMI.VOLKSWAGEN_ARGENTINA}, - ) - VOLKSWAGEN_TCROSS_MK1 = VolkswagenMQBPlatformConfig( - [VWCarDocs("Volkswagen T-Cross 2021", footnotes=[Footnote.VW_MQB_A0])], - VolkswagenCarSpecs(mass=1150, wheelbase=2.60), - chassis_codes={"C1"}, - wmis={WMI.VOLKSWAGEN_EUROPE_SUV}, - ) - VOLKSWAGEN_TIGUAN_MK2 = VolkswagenMQBPlatformConfig( - [ - VWCarDocs("Volkswagen Tiguan 2018-24"), - VWCarDocs("Volkswagen Tiguan eHybrid 2021-23"), - ], - VolkswagenCarSpecs(mass=1715, wheelbase=2.74), - chassis_codes={"5N", "AD", "AX", "BW"}, - wmis={WMI.VOLKSWAGEN_EUROPE_SUV, WMI.VOLKSWAGEN_MEXICO_SUV}, - ) - VOLKSWAGEN_TOURAN_MK2 = VolkswagenMQBPlatformConfig( - [VWCarDocs("Volkswagen Touran 2016-23")], - VolkswagenCarSpecs(mass=1516, wheelbase=2.79), - chassis_codes={"1T"}, - wmis={WMI.VOLKSWAGEN_EUROPE_SUV}, - ) - VOLKSWAGEN_TRANSPORTER_T61 = VolkswagenMQBPlatformConfig( - [ - VWCarDocs("Volkswagen Caravelle 2020"), - VWCarDocs("Volkswagen California 2021-23"), - ], - VolkswagenCarSpecs(mass=1926, wheelbase=3.00, minSteerSpeed=14.0), - chassis_codes={"7H", "7L"}, - wmis={WMI.VOLKSWAGEN_COMMERCIAL_BUS_VAN}, - ) - VOLKSWAGEN_TROC_MK1 = VolkswagenMQBPlatformConfig( - [VWCarDocs("Volkswagen T-Roc 2018-23")], - VolkswagenCarSpecs(mass=1413, wheelbase=2.63), - chassis_codes={"A1"}, - wmis={WMI.VOLKSWAGEN_EUROPE_SUV}, - ) - AUDI_A3_MK3 = VolkswagenMQBPlatformConfig( - [ - VWCarDocs("Audi A3 2014-19"), - VWCarDocs("Audi A3 Sportback e-tron 2017-18"), - VWCarDocs("Audi RS3 2018"), - VWCarDocs("Audi S3 2015-17"), - ], - VolkswagenCarSpecs(mass=1335, wheelbase=2.61), - chassis_codes={"8V", "FF"}, - wmis={WMI.AUDI_GERMANY_CAR, WMI.AUDI_SPORT}, - ) - AUDI_Q2_MK1 = VolkswagenMQBPlatformConfig( - [VWCarDocs("Audi Q2 2018")], - VolkswagenCarSpecs(mass=1205, wheelbase=2.61), - chassis_codes={"GA"}, - wmis={WMI.AUDI_GERMANY_CAR}, - ) - AUDI_Q3_MK2 = VolkswagenMQBPlatformConfig( - [VWCarDocs("Audi Q3 2019-23")], - VolkswagenCarSpecs(mass=1623, wheelbase=2.68), - chassis_codes={"8U", "F3", "FS"}, - wmis={WMI.AUDI_EUROPE_MPV, WMI.AUDI_GERMANY_CAR}, - ) - SEAT_ATECA_MK1 = VolkswagenMQBPlatformConfig( - [ - VWCarDocs("CUPRA Ateca 2018-23"), - VWCarDocs("SEAT Ateca 2016-23"), - VWCarDocs("SEAT Leon 2014-20"), - ], - VolkswagenCarSpecs(mass=1300, wheelbase=2.64), - chassis_codes={"5F"}, - wmis={WMI.SEAT}, - ) - SKODA_FABIA_MK4 = VolkswagenMQBPlatformConfig( - [VWCarDocs("Škoda Fabia 2022-23", footnotes=[Footnote.VW_MQB_A0])], - VolkswagenCarSpecs(mass=1266, wheelbase=2.56), - chassis_codes={"PJ"}, - wmis={WMI.SKODA}, - ) - SKODA_KAMIQ_MK1 = VolkswagenMQBPlatformConfig( - [ - VWCarDocs("Škoda Kamiq 2021-23", footnotes=[Footnote.VW_MQB_A0, Footnote.KAMIQ]), - VWCarDocs("Škoda Scala 2020-23", footnotes=[Footnote.VW_MQB_A0]), - ], - VolkswagenCarSpecs(mass=1230, wheelbase=2.66), - chassis_codes={"NW"}, - wmis={WMI.SKODA}, - ) - SKODA_KAROQ_MK1 = VolkswagenMQBPlatformConfig( - [VWCarDocs("Škoda Karoq 2019-23")], - VolkswagenCarSpecs(mass=1278, wheelbase=2.66), - chassis_codes={"NU"}, - wmis={WMI.SKODA}, - ) - SKODA_KODIAQ_MK1 = VolkswagenMQBPlatformConfig( - [VWCarDocs("Škoda Kodiaq 2017-23")], - VolkswagenCarSpecs(mass=1569, wheelbase=2.79), - chassis_codes={"NS"}, - wmis={WMI.SKODA, WMI.VOLKSWAGEN_GROUP_RUS}, - ) - SKODA_OCTAVIA_MK3 = VolkswagenMQBPlatformConfig( - [ - VWCarDocs("Škoda Octavia 2015-19"), - VWCarDocs("Škoda Octavia RS 2016"), - VWCarDocs("Škoda Octavia Scout 2017-19"), - ], - VolkswagenCarSpecs(mass=1388, wheelbase=2.68), - chassis_codes={"NE"}, - wmis={WMI.SKODA}, - ) - SKODA_SUPERB_MK3 = VolkswagenMQBPlatformConfig( - [VWCarDocs("Škoda Superb 2015-22")], - VolkswagenCarSpecs(mass=1505, wheelbase=2.84), - chassis_codes={"3V", "NP"}, - wmis={WMI.SKODA}, - ) - - -def match_fw_to_car_fuzzy(live_fw_versions, vin, offline_fw_versions) -> set[str]: - candidates = set() - - # Compile all FW versions for each ECU - all_ecu_versions: dict[EcuAddrSubAddr, set[str]] = defaultdict(set) - for ecus in offline_fw_versions.values(): - for ecu, versions in ecus.items(): - all_ecu_versions[ecu] |= set(versions) - - # Check the WMI and chassis code to determine the platform - wmi = vin[:3] - chassis_code = vin[6:8] - - for platform in CAR: - valid_ecus = set() - for ecu in offline_fw_versions[platform]: - addr = ecu[1:] - if ecu[0] not in CHECK_FUZZY_ECUS: - continue - - # Sanity check that live FW is in the superset of all FW, Volkswagen ECU part numbers are commonly shared - found_versions = live_fw_versions.get(addr, []) - expected_versions = all_ecu_versions[ecu] - if not any(found_version in expected_versions for found_version in found_versions): - break - - valid_ecus.add(ecu[0]) - - if valid_ecus != CHECK_FUZZY_ECUS: - continue - - if wmi in platform.config.wmis and chassis_code in platform.config.chassis_codes: - candidates.add(platform) - - return {str(c) for c in candidates} - - -# These ECUs are required to match to gain a VIN match -# TODO: do we want to check camera when we add its FW? -CHECK_FUZZY_ECUS = {Ecu.fwdRadar} - -# All supported cars should return FW from the engine, srs, eps, and fwdRadar. Cars -# with a manual trans won't return transmission firmware, but all other cars will. -# -# The 0xF187 SW part number query should return in the form of N[NX][NX] NNN NNN [X[X]], -# where N=number, X=letter, and the trailing two letters are optional. Performance -# tuners sometimes tamper with that field (e.g. 8V0 9C0 BB0 1 from COBB/EQT). Tampered -# ECU SW part numbers are invalid for vehicle ID and compatibility checks. Try to have -# them repaired by the tuner before including them in openpilot. - -VOLKSWAGEN_VERSION_REQUEST_MULTI = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ - p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_SPARE_PART_NUMBER) + \ - p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_ECU_SOFTWARE_VERSION_NUMBER) + \ - p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_DATA_IDENTIFICATION) -VOLKSWAGEN_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) - -VOLKSWAGEN_RX_OFFSET = 0x6a - -FW_QUERY_CONFIG = FwQueryConfig( - requests=[request for bus, obd_multiplexing in [(1, True), (1, False), (0, False)] for request in [ - Request( - [VOLKSWAGEN_VERSION_REQUEST_MULTI], - [VOLKSWAGEN_VERSION_RESPONSE], - whitelist_ecus=[Ecu.srs, Ecu.eps, Ecu.fwdRadar, Ecu.fwdCamera], - rx_offset=VOLKSWAGEN_RX_OFFSET, - bus=bus, - obd_multiplexing=obd_multiplexing, - ), - Request( - [VOLKSWAGEN_VERSION_REQUEST_MULTI], - [VOLKSWAGEN_VERSION_RESPONSE], - whitelist_ecus=[Ecu.engine, Ecu.transmission], - bus=bus, - obd_multiplexing=obd_multiplexing, - ), - ]], - non_essential_ecus={Ecu.eps: list(CAR)}, - extra_ecus=[(Ecu.fwdCamera, 0x74f, None)], - match_fw_to_car_fuzzy=match_fw_to_car_fuzzy, -) - -DBC = CAR.create_dbc_map() From ee54454ee9cf1d9bd32d0085661e376d9fcb5742 Mon Sep 17 00:00:00 2001 From: deanlee Date: Mon, 25 Mar 2024 12:14:21 +0800 Subject: [PATCH 03/15] remove dependence on cereal --- SConstruct | 9 ----- can/SConscript | 4 +- can/common.h | 32 ++++++++-------- can/common.pxd | 11 +++++- can/parser.cc | 96 +++++++++++----------------------------------- can/parser_pyx.pyx | 26 ++++++++++++- 6 files changed, 74 insertions(+), 104 deletions(-) diff --git a/SConstruct b/SConstruct index 34e3061e78..2401720f17 100644 --- a/SConstruct +++ b/SConstruct @@ -6,8 +6,6 @@ import numpy as np zmq = 'zmq' arch = subprocess.check_output(["uname", "-m"], encoding='utf8').rstrip() -cereal_dir = Dir('.') - python_path = sysconfig.get_paths()['include'] cpppath = [ '#', @@ -56,11 +54,6 @@ env = Environment( common = '' Export('env', 'zmq', 'arch', 'common') -cereal = [File('#cereal/libcereal.a')] -messaging = [File('#cereal/libmessaging.a')] -Export('cereal', 'messaging') - - envCython = env.Clone() envCython["CPPPATH"] += [np.get_include()] envCython["CCFLAGS"] += ["-Wno-#warnings", "-Wno-shadow", "-Wno-deprecated-declarations"] @@ -80,6 +73,4 @@ envCython["LIBS"] = python_libs Export('envCython') - -SConscript(['cereal/SConscript']) SConscript(['opendbc/can/SConscript']) diff --git a/can/SConscript b/can/SConscript index 7e8fd270f6..3923bf3035 100644 --- a/can/SConscript +++ b/can/SConscript @@ -1,4 +1,4 @@ -Import('env', 'envCython', 'cereal', 'common') +Import('env', 'envCython', 'common') import os @@ -6,7 +6,7 @@ envDBC = env.Clone() dbc_file_path = '-DDBC_FILE_PATH=\'"%s"\'' % (envDBC.Dir("..").abspath) envDBC['CXXFLAGS'] += [dbc_file_path] src = ["dbc.cc", "parser.cc", "packer.cc", "common.cc"] -libs = [common, "capnp", "kj", "zmq"] +libs = [common, "zmq"] # shared library for openpilot libdbc = envDBC.SharedLibrary('libdbc', src, LIBS=libs) diff --git a/can/common.h b/can/common.h index 46b3159b9f..f06aa28e79 100644 --- a/can/common.h +++ b/can/common.h @@ -6,13 +6,6 @@ #include #include -#include -#include - -#ifndef DYNAMIC_CAPNP -#include "cereal/gen/cpp/log.capnp.h" -#endif - #include "opendbc/can/logger.h" #include "opendbc/can/common_dbc.h" @@ -34,6 +27,17 @@ unsigned int xor_checksum(uint32_t address, const Signal &sig, const std::vector unsigned int hkg_can_fd_checksum(uint32_t address, const Signal &sig, const std::vector &d); unsigned int pedal_checksum(uint32_t address, const Signal &sig, const std::vector &d); +struct CanFrame { + long src; + long address; + std::vector dat; +}; + +struct CanData { + uint64_t nanos; + std::vector frames; +}; + class MessageState { public: std::string name; @@ -60,8 +64,6 @@ class MessageState { class CANParser { private: const int bus; - kj::Array aligned_buf; - const DBC *dbc = NULL; std::unordered_map message_states; @@ -77,14 +79,12 @@ class CANParser { CANParser(int abus, const std::string& dbc_name, const std::vector> &messages); CANParser(int abus, const std::string& dbc_name, bool ignore_checksum, bool ignore_counter); - #ifndef DYNAMIC_CAPNP - void update_string(const std::string &data, bool sendcan); - void update_strings(const std::vector &data, std::vector &vals, bool sendcan); - void UpdateCans(uint64_t nanos, const capnp::List::Reader& cans); - #endif - void UpdateCans(uint64_t nanos, const capnp::DynamicStruct::Reader& cans); - void UpdateValid(uint64_t nanos); + void update(const std::vector &can_data, std::vector &vals); void query_latest(std::vector &vals, uint64_t last_ts = 0); + +protected: + void update_can(const CanData &can); + void UpdateValid(uint64_t nanos); }; class CANPacker { diff --git a/can/common.pxd b/can/common.pxd index 4dab92cd5f..70bf1571e7 100644 --- a/can/common.pxd +++ b/can/common.pxd @@ -67,11 +67,20 @@ cdef extern from "common_dbc.h": cdef extern from "common.h": cdef const DBC* dbc_lookup(const string) except + + cdef struct CanFrame: + long src + long address + vector[uint8_t] dat + + cdef struct CanData: + uint64_t nanos + vector[CanFrame] frames + cdef cppclass CANParser: bool can_valid bool bus_timeout CANParser(int, string, vector[pair[uint32_t, int]]) except + - void update_strings(vector[string]&, vector[SignalValue]&, bool) except + + void update(vector[CanData]&, vector[SignalValue]&) except + cdef cppclass CANPacker: CANPacker(string) diff --git a/can/parser.cc b/can/parser.cc index d36ec75bad..2dee09a9a2 100644 --- a/can/parser.cc +++ b/can/parser.cc @@ -93,7 +93,7 @@ bool MessageState::update_counter_generic(int64_t v, int cnt_size) { CANParser::CANParser(int abus, const std::string& dbc_name, const std::vector> &messages) - : bus(abus), aligned_buf(kj::heapArray(1024)) { + : bus(abus) { dbc = dbc_lookup(dbc_name); assert(dbc); @@ -157,109 +157,57 @@ CANParser::CANParser(int abus, const std::string& dbc_name, bool ignore_checksum } } -#ifndef DYNAMIC_CAPNP -void CANParser::update_string(const std::string &data, bool sendcan) { - // format for board, make copy due to alignment issues. - const size_t buf_size = (data.length() / sizeof(capnp::word)) + 1; - if (aligned_buf.size() < buf_size) { - aligned_buf = kj::heapArray(buf_size); - } - memcpy(aligned_buf.begin(), data.data(), data.length()); - - // extract the messages - capnp::FlatArrayMessageReader cmsg(aligned_buf.slice(0, buf_size)); - cereal::Event::Reader event = cmsg.getRoot(); - - if (first_nanos == 0) { - first_nanos = event.getLogMonoTime(); - } - last_nanos = event.getLogMonoTime(); - - auto cans = sendcan ? event.getSendcan() : event.getCan(); - UpdateCans(last_nanos, cans); - - UpdateValid(last_nanos); -} - -void CANParser::update_strings(const std::vector &data, std::vector &vals, bool sendcan) { +void CANParser::update(const std::vector &can_data, std::vector &vals) { uint64_t current_nanos = 0; - for (const auto &d : data) { - update_string(d, sendcan); + for (const auto &c : can_data) { + if (first_nanos == 0) { + first_nanos = c.nanos; + } if (current_nanos == 0) { - current_nanos = last_nanos; + current_nanos = c.nanos; } + last_nanos = c.nanos; + + update_can(c); + UpdateValid(last_nanos); } + query_latest(vals, current_nanos); } -void CANParser::UpdateCans(uint64_t nanos, const capnp::List::Reader& cans) { - //DEBUG("got %d messages\n", cans.size()); - +void CANParser::update_can(const CanData &can) { bool bus_empty = true; - - // parse the messages - for (const auto cmsg : cans) { - if (cmsg.getSrc() != bus) { + for (const auto &frame : can.frames) { + if (frame.src != bus) { // DEBUG("skip %d: wrong bus\n", cmsg.getAddress()); continue; } bus_empty = false; - auto state_it = message_states.find(cmsg.getAddress()); + auto state_it = message_states.find(frame.address); if (state_it == message_states.end()) { // DEBUG("skip %d: not specified\n", cmsg.getAddress()); continue; } - - auto dat = cmsg.getDat(); - - if (dat.size() > 64) { - DEBUG("got message longer than 64 bytes: 0x%X %zu\n", cmsg.getAddress(), dat.size()); + if (frame.dat.size() > 64) { + DEBUG("got message longer than 64 bytes: 0x%X %zu\n", frame.address, frame.dat.size()); continue; } // TODO: this actually triggers for some cars. fix and enable this - //if (dat.size() != state_it->second.size) { + // if (dat.size() != state_it->second.size) { // DEBUG("got message with unexpected length: expected %d, got %zu for %d", state_it->second.size, dat.size(), cmsg.getAddress()); // continue; //} - // TODO: can remove when we ignore unexpected can msg lengths - // make sure the data_size is not less than state_it->second.size - size_t data_size = std::max(dat.size(), state_it->second.size); - std::vector data(data_size, 0); - memcpy(data.data(), dat.begin(), dat.size()); - state_it->second.parse(nanos, data); + state_it->second.parse(can.nanos, frame.dat); } // update bus timeout if (!bus_empty) { - last_nonempty_nanos = nanos; + last_nonempty_nanos = can.nanos; } - bus_timeout = (nanos - last_nonempty_nanos) > bus_timeout_threshold; -} -#endif - -void CANParser::UpdateCans(uint64_t nanos, const capnp::DynamicStruct::Reader& cmsg) { - // assume message struct is `cereal::CanData` and parse - assert(cmsg.has("address") && cmsg.has("src") && cmsg.has("dat") && cmsg.has("busTime")); - - if (cmsg.get("src").as() != bus) { - DEBUG("skip %d: wrong bus\n", cmsg.get("address").as()); - return; - } - - auto state_it = message_states.find(cmsg.get("address").as()); - if (state_it == message_states.end()) { - DEBUG("skip %d: not specified\n", cmsg.get("address").as()); - return; - } - - auto dat = cmsg.get("dat").as(); - if (dat.size() > 64) return; // shouldn't ever happen - std::vector data(dat.size(), 0); - memcpy(data.data(), dat.begin(), dat.size()); - state_it->second.parse(nanos, data); + bus_timeout = (can.nanos - last_nonempty_nanos) > bus_timeout_threshold; } void CANParser::UpdateValid(uint64_t nanos) { diff --git a/can/parser_pyx.pyx b/can/parser_pyx.pyx index a5b802dfce..e7a83122b3 100644 --- a/can/parser_pyx.pyx +++ b/can/parser_pyx.pyx @@ -8,9 +8,11 @@ from libcpp.vector cimport vector from libc.stdint cimport uint32_t from .common cimport CANParser as cpp_CANParser -from .common cimport dbc_lookup, SignalValue, DBC +from .common cimport dbc_lookup, SignalValue, DBC, CanData, CanFrame import numbers +import capnp +from cereal import log from collections import defaultdict @@ -69,6 +71,26 @@ cdef class CANParser: for address in self.addresses: self.vl_all[address].clear() + cdef CanFrame* frame + cdef CanData* can_data + cdef vector[CanData] can_data_array + + can_data_array.reserve(len(strings)) + try: + for s in strings: + with log.Event.from_bytes(s) as msg: + can_event = msg.sendCan if sendcan else msg.can + can_data = &(can_data_array.emplace_back()) + can_data.nanos = msg.logMonoTime + can_data.frames.reserve(len(can_event)) + for c in can_event: + frame = &(can_data.frames.emplace_back()) + frame.src = c.src + frame.address = c.address + frame.dat = c.dat + except capnp.lib.capnp.KjException as ex: + raise RuntimeError(str(ex)) + cdef vector[SignalValue] new_vals cur_address = -1 vl = {} @@ -76,7 +98,7 @@ cdef class CANParser: ts_nanos = {} updated_addrs = set() - self.can.update_strings(strings, new_vals, sendcan) + self.can.update(can_data_array, new_vals) cdef vector[SignalValue].iterator it = new_vals.begin() cdef SignalValue* cv while it != new_vals.end(): From 4c2924df3cc3bd9f847cdfb3dd968a4ab49e28f8 Mon Sep 17 00:00:00 2001 From: deanlee Date: Mon, 25 Mar 2024 16:09:20 +0800 Subject: [PATCH 04/15] parse can strings in a c++ helper function --- can/SConscript | 3 ++- can/parser_pyx.pyx | 39 ++++++++++----------------------------- can/strings_to_candata.cc | 37 +++++++++++++++++++++++++++++++++++++ 3 files changed, 49 insertions(+), 30 deletions(-) create mode 100644 can/strings_to_candata.cc diff --git a/can/SConscript b/can/SConscript index 3923bf3035..1a1f79cd4c 100644 --- a/can/SConscript +++ b/can/SConscript @@ -16,8 +16,9 @@ envDBC.Library('libdbc_static', src, LIBS=libs) # Build packer and parser lenv = envCython.Clone() +lenv.Library('strings_to_candata', ['strings_to_candata.cc']) lenv["LINKFLAGS"] += [libdbc[0].get_labspath()] -parser = lenv.Program('parser_pyx.so', 'parser_pyx.pyx') +parser = lenv.Program('parser_pyx.so', 'parser_pyx.pyx', LIBS=['strings_to_candata', 'capnp', 'kj'] + lenv["LIBS"]) packer = lenv.Program('packer_pyx.so', 'packer_pyx.pyx') lenv.Depends(parser, libdbc) diff --git a/can/parser_pyx.pyx b/can/parser_pyx.pyx index e7a83122b3..cea37348d1 100644 --- a/can/parser_pyx.pyx +++ b/can/parser_pyx.pyx @@ -5,16 +5,18 @@ from cython.operator cimport dereference as deref, preincrement as preinc from libcpp.pair cimport pair from libcpp.string cimport string from libcpp.vector cimport vector +from libcpp cimport bool +from libcpp.unordered_set cimport unordered_set from libc.stdint cimport uint32_t from .common cimport CANParser as cpp_CANParser -from .common cimport dbc_lookup, SignalValue, DBC, CanData, CanFrame +from .common cimport dbc_lookup, SignalValue, DBC, CanData import numbers -import capnp -from cereal import log from collections import defaultdict +cdef extern from "strings_to_candata.cc": + void strings_to_candata(const vector[string] &strings, vector[CanData] &candata, bool sendcan) except + cdef class CANParser: cdef: @@ -71,34 +73,13 @@ cdef class CANParser: for address in self.addresses: self.vl_all[address].clear() - cdef CanFrame* frame - cdef CanData* can_data - cdef vector[CanData] can_data_array - - can_data_array.reserve(len(strings)) - try: - for s in strings: - with log.Event.from_bytes(s) as msg: - can_event = msg.sendCan if sendcan else msg.can - can_data = &(can_data_array.emplace_back()) - can_data.nanos = msg.logMonoTime - can_data.frames.reserve(len(can_event)) - for c in can_event: - frame = &(can_data.frames.emplace_back()) - frame.src = c.src - frame.address = c.address - frame.dat = c.dat - except capnp.lib.capnp.KjException as ex: - raise RuntimeError(str(ex)) - cdef vector[SignalValue] new_vals - cur_address = -1 - vl = {} - vl_all = {} - ts_nanos = {} - updated_addrs = set() + cdef unordered_set[uint32_t] updated_addrs + cdef vector[CanData] can_data + + strings_to_candata(strings, can_data, sendcan) + self.can.update(can_data, new_vals) - self.can.update(can_data_array, new_vals) cdef vector[SignalValue].iterator it = new_vals.begin() cdef SignalValue* cv while it != new_vals.end(): diff --git a/can/strings_to_candata.cc b/can/strings_to_candata.cc new file mode 100644 index 0000000000..46ce918602 --- /dev/null +++ b/can/strings_to_candata.cc @@ -0,0 +1,37 @@ +#include + +#include +#include + +#include "cereal/gen/cpp/log.capnp.h" +#include "opendbc/can/common.h" + +void strings_to_candata(const std::vector &strings, std::vector &can_data, bool sendcan) { + kj::Array aligned_buf; + can_data.reserve(strings.size()); + for (const auto &s : strings) { + const size_t buf_size = (s.length() / sizeof(capnp::word)) + 1; + if (aligned_buf.size() < buf_size) { + aligned_buf = kj::heapArray(buf_size); + } + memcpy(aligned_buf.begin(), s.data(), s.length()); + + // extract the messages + capnp::FlatArrayMessageReader cmsg(aligned_buf.slice(0, buf_size)); + cereal::Event::Reader event = cmsg.getRoot(); + + auto &can = can_data.emplace_back(); + can.nanos = event.getLogMonoTime(); + + auto cans = sendcan ? event.getSendcan() : event.getCan(); + can.frames.reserve(cans.size()); + for (const auto cmsg : cans) { + auto &frame = can.frames.emplace_back(); + frame.src = cmsg.getSrc(); + frame.address = cmsg.getAddress(); + auto dat = cmsg.getDat(); + frame.dat.resize(dat.size()); + memcpy(frame.dat.data(), dat.begin(), dat.size()); + } + } +} From 508fb6f70c211544103e64a397e9dd6f22712613 Mon Sep 17 00:00:00 2001 From: deanlee Date: Tue, 26 Mar 2024 12:44:17 +0800 Subject: [PATCH 05/15] remove all cereal --- can/SConscript | 3 +- can/common.h | 2 +- can/common.pxd | 2 +- can/parser_pyx.pyx | 39 +++++++++++++---- can/strings_to_candata.cc | 37 ---------------- can/tests/test_checksums.py | 4 +- can/tests/test_packer_parser.py | 64 ++++++---------------------- can/tests/test_parser_performance.py | 4 +- 8 files changed, 49 insertions(+), 106 deletions(-) delete mode 100644 can/strings_to_candata.cc diff --git a/can/SConscript b/can/SConscript index 1a1f79cd4c..3923bf3035 100644 --- a/can/SConscript +++ b/can/SConscript @@ -16,9 +16,8 @@ envDBC.Library('libdbc_static', src, LIBS=libs) # Build packer and parser lenv = envCython.Clone() -lenv.Library('strings_to_candata', ['strings_to_candata.cc']) lenv["LINKFLAGS"] += [libdbc[0].get_labspath()] -parser = lenv.Program('parser_pyx.so', 'parser_pyx.pyx', LIBS=['strings_to_candata', 'capnp', 'kj'] + lenv["LIBS"]) +parser = lenv.Program('parser_pyx.so', 'parser_pyx.pyx') packer = lenv.Program('packer_pyx.so', 'packer_pyx.pyx') lenv.Depends(parser, libdbc) diff --git a/can/common.h b/can/common.h index f06aa28e79..deffaf36fb 100644 --- a/can/common.h +++ b/can/common.h @@ -29,7 +29,7 @@ unsigned int pedal_checksum(uint32_t address, const Signal &sig, const std::vect struct CanFrame { long src; - long address; + uint32_t address; std::vector dat; }; diff --git a/can/common.pxd b/can/common.pxd index 70bf1571e7..a8f754b56e 100644 --- a/can/common.pxd +++ b/can/common.pxd @@ -69,7 +69,7 @@ cdef extern from "common.h": cdef struct CanFrame: long src - long address + uint32_t address vector[uint8_t] dat cdef struct CanData: diff --git a/can/parser_pyx.pyx b/can/parser_pyx.pyx index cea37348d1..65d451520f 100644 --- a/can/parser_pyx.pyx +++ b/can/parser_pyx.pyx @@ -5,19 +5,15 @@ from cython.operator cimport dereference as deref, preincrement as preinc from libcpp.pair cimport pair from libcpp.string cimport string from libcpp.vector cimport vector -from libcpp cimport bool from libcpp.unordered_set cimport unordered_set from libc.stdint cimport uint32_t from .common cimport CANParser as cpp_CANParser -from .common cimport dbc_lookup, SignalValue, DBC, CanData +from .common cimport dbc_lookup, SignalValue, DBC, CanData, CanFrame import numbers from collections import defaultdict -cdef extern from "strings_to_candata.cc": - void strings_to_candata(const vector[string] &strings, vector[CanData] &candata, bool sendcan) except + - cdef class CANParser: cdef: cpp_CANParser *can @@ -72,13 +68,38 @@ cdef class CANParser: def update_strings(self, strings, sendcan=False): for address in self.addresses: self.vl_all[address].clear() + # input format: + # [nanos, [[address, 0, data, src], ...]] + # [[nanos, [[address, 0, data, src], ...], ...]] + + for v in self.vl_all.values(): + for l in v.values(): # no-cython-lint + l.clear() cdef vector[SignalValue] new_vals cdef unordered_set[uint32_t] updated_addrs - cdef vector[CanData] can_data - - strings_to_candata(strings, can_data, sendcan) - self.can.update(can_data, new_vals) + cdef CanFrame* frame + cdef CanData* can_data + cdef vector[CanData] can_data_array + + try: + if len(strings) and not isinstance(strings[0], (list, tuple)): + strings = [strings] + + can_data_array.reserve(len(strings)) + for s in strings: + can_data = &(can_data_array.emplace_back()) + can_data.nanos = s[0] + can_data.frames.reserve(len(s[1])) + for f in s[1]: + frame = &(can_data.frames.emplace_back()) + frame.address = f[0] + frame.dat = f[2] + frame.src = f[3] + except TypeError: + raise RuntimeError("invalid parameter") + + self.can.update(can_data_array, new_vals) cdef vector[SignalValue].iterator it = new_vals.begin() cdef SignalValue* cv diff --git a/can/strings_to_candata.cc b/can/strings_to_candata.cc deleted file mode 100644 index 46ce918602..0000000000 --- a/can/strings_to_candata.cc +++ /dev/null @@ -1,37 +0,0 @@ -#include - -#include -#include - -#include "cereal/gen/cpp/log.capnp.h" -#include "opendbc/can/common.h" - -void strings_to_candata(const std::vector &strings, std::vector &can_data, bool sendcan) { - kj::Array aligned_buf; - can_data.reserve(strings.size()); - for (const auto &s : strings) { - const size_t buf_size = (s.length() / sizeof(capnp::word)) + 1; - if (aligned_buf.size() < buf_size) { - aligned_buf = kj::heapArray(buf_size); - } - memcpy(aligned_buf.begin(), s.data(), s.length()); - - // extract the messages - capnp::FlatArrayMessageReader cmsg(aligned_buf.slice(0, buf_size)); - cereal::Event::Reader event = cmsg.getRoot(); - - auto &can = can_data.emplace_back(); - can.nanos = event.getLogMonoTime(); - - auto cans = sendcan ? event.getSendcan() : event.getCan(); - can.frames.reserve(cans.size()); - for (const auto cmsg : cans) { - auto &frame = can.frames.emplace_back(); - frame.src = cmsg.getSrc(); - frame.address = cmsg.getAddress(); - auto dat = cmsg.getDat(); - frame.dat.resize(dat.size()); - memcpy(frame.dat.data(), dat.begin(), dat.size()); - } - } -} diff --git a/can/tests/test_checksums.py b/can/tests/test_checksums.py index 93ddbe0074..1e61262a03 100755 --- a/can/tests/test_checksums.py +++ b/can/tests/test_checksums.py @@ -3,7 +3,6 @@ from opendbc.can.parser import CANParser from opendbc.can.packer import CANPacker -from opendbc.can.tests.test_packer_parser import can_list_to_can_capnp class TestCanChecksums(unittest.TestCase): @@ -31,8 +30,7 @@ def test_honda_checksum(self): packer.make_can_msg("LKAS_HUD", 0, values), packer.make_can_msg("LKAS_HUD_A", 0, values), ] - can_strings = [can_list_to_can_capnp(msgs), ] - parser.update_strings(can_strings) + parser.update_strings([0, msgs]) self.assertEqual(parser.vl['LKAS_HUD']['CHECKSUM'], std) self.assertEqual(parser.vl['LKAS_HUD_A']['CHECKSUM'], ext) diff --git a/can/tests/test_packer_parser.py b/can/tests/test_packer_parser.py index c313805c47..6b8112b006 100755 --- a/can/tests/test_packer_parser.py +++ b/can/tests/test_packer_parser.py @@ -2,7 +2,6 @@ import unittest import random -import cereal.messaging as messaging from opendbc.can.parser import CANParser from opendbc.can.packer import CANPacker from opendbc.can.tests import TEST_DBC @@ -10,27 +9,6 @@ MAX_BAD_COUNTER = 5 -# Python implementation so we don't have to depend on boardd -def can_list_to_can_capnp(can_msgs, msgtype='can', logMonoTime=None): - dat = messaging.new_message(msgtype, len(can_msgs)) - - if logMonoTime is not None: - dat.logMonoTime = logMonoTime - - for i, can_msg in enumerate(can_msgs): - if msgtype == 'sendcan': - cc = dat.sendcan[i] - else: - cc = dat.can[i] - - cc.address = can_msg[0] - cc.busTime = can_msg[1] - cc.dat = bytes(can_msg[2]) - cc.src = can_msg[3] - - return dat.to_bytes() - - class TestCanParserPacker(unittest.TestCase): def test_packer(self): packer = CANPacker(TEST_DBC) @@ -51,8 +29,7 @@ def test_packer_counter(self): # packer should increment the counter for i in range(1000): msg = packer.make_can_msg("CAN_FD_MESSAGE", 0, {}) - dat = can_list_to_can_capnp([msg, ]) - parser.update_strings([dat]) + parser.update_strings([0, [msg]]) self.assertEqual(parser.vl["CAN_FD_MESSAGE"]["COUNTER"], i % 256) # setting COUNTER should override @@ -62,16 +39,14 @@ def test_packer_counter(self): "COUNTER": cnt, "SIGNED": 0 }) - dat = can_list_to_can_capnp([msg, ]) - parser.update_strings([dat]) + parser.update_strings([0, [msg]]) self.assertEqual(parser.vl["CAN_FD_MESSAGE"]["COUNTER"], cnt) # then, should resume counting from the override value cnt = parser.vl["CAN_FD_MESSAGE"]["COUNTER"] for i in range(100): msg = packer.make_can_msg("CAN_FD_MESSAGE", 0, {}) - dat = can_list_to_can_capnp([msg, ]) - parser.update_strings([dat]) + parser.update_strings([0, [msg]]) self.assertEqual(parser.vl["CAN_FD_MESSAGE"]["COUNTER"], (cnt + i) % 256) def test_parser_can_valid(self): @@ -84,16 +59,14 @@ def test_parser_can_valid(self): # not valid until the message is seen for _ in range(100): - dat = can_list_to_can_capnp([]) - parser.update_strings([dat]) + parser.update_strings([0, []]) self.assertFalse(parser.can_valid) # valid once seen for i in range(1, 100): t = int(0.01 * i * 1e9) msg = packer.make_can_msg("CAN_FD_MESSAGE", 0, {}) - dat = can_list_to_can_capnp([msg, ], logMonoTime=t) - parser.update_strings([dat]) + parser.update_strings([t, [msg]]) self.assertTrue(parser.can_valid) def test_parser_counter_can_valid(self): @@ -108,17 +81,15 @@ def test_parser_counter_can_valid(self): parser = CANParser("honda_civic_touring_2016_can_generated", msgs, 0) msg = packer.make_can_msg("STEERING_CONTROL", 0, {"COUNTER": 0}) - bts = can_list_to_can_capnp([msg]) # bad static counter, invalid once it's seen MAX_BAD_COUNTER messages for idx in range(0x1000): - parser.update_strings([bts]) + parser.update_strings([0, [msg]]) self.assertEqual((idx + 1) < MAX_BAD_COUNTER, parser.can_valid) # one to recover msg = packer.make_can_msg("STEERING_CONTROL", 0, {"COUNTER": 1}) - bts = can_list_to_can_capnp([msg]) - parser.update_strings([bts]) + parser.update_strings([0, [msg]]) self.assertTrue(parser.can_valid) def test_parser_no_partial_update(self): @@ -140,8 +111,7 @@ def rx_steering_msg(values, bad_checksum=False): msg[2] = bytearray(msg[2]) msg[2][4] = (msg[2][4] & 0xF0) | ((msg[2][4] & 0x0F) + 1) - bts = can_list_to_can_capnp([msg]) - parser.update_strings([bts]) + parser.update_strings([0, [msg]]) rx_steering_msg({"STEER_TORQUE": 100}, bad_checksum=False) self.assertEqual(parser.vl["STEERING_CONTROL"]["STEER_TORQUE"], 100) @@ -184,8 +154,7 @@ def test_packer_parser(self): } msgs = [packer.make_can_msg(k, 0, v) for k, v in values.items()] - bts = can_list_to_can_capnp(msgs) - parser.update_strings([bts]) + parser.update_strings([0, msgs]) for k, v in values.items(): for key, val in v.items(): @@ -205,9 +174,7 @@ def test_scale_offset(self): for brake in range(100): values = {"USER_BRAKE": brake} msgs = packer.make_can_msg("VSA_STATUS", 0, values) - bts = can_list_to_can_capnp([msgs]) - - parser.update_strings([bts]) + parser.update_strings([0, [msgs]]) self.assertAlmostEqual(parser.vl["VSA_STATUS"]["USER_BRAKE"], brake) @@ -231,8 +198,7 @@ def test_subaru(self): } msgs = packer.make_can_msg("ES_LKAS", 0, values) - bts = can_list_to_can_capnp([msgs]) - parser.update_strings([bts]) + parser.update_strings([0, [msgs]]) self.assertAlmostEqual(parser.vl["ES_LKAS"]["LKAS_Output"], steer) self.assertAlmostEqual(parser.vl["ES_LKAS"]["LKAS_Request"], active) @@ -261,8 +227,7 @@ def send_msg(blank=False): else: msgs = [packer.make_can_msg("VSA_STATUS", 0, {}), ] - can = can_list_to_can_capnp(msgs, logMonoTime=t) - parser.update_strings([can, ]) + parser.update_strings([t, msgs]) # all good, no timeout for _ in range(1000): @@ -300,8 +265,7 @@ def test_updated(self): can_msgs[frame].append(packer.make_can_msg("VSA_STATUS", 0, values)) idx += 1 - can_strings = [can_list_to_can_capnp(msgs) for msgs in can_msgs] - parser.update_strings(can_strings) + parser.update_strings([[0, can_msgs[0]], [0, can_msgs[1]]]) vl_all = parser.vl_all["VSA_STATUS"]["USER_BRAKE"] self.assertEqual(vl_all, user_brake_vals) @@ -335,7 +299,7 @@ def test_timestamp_nanos(self): for i in range(10): log_mono_time = int(0.01 * i * 1e+9) can_msg = packer.make_can_msg("VSA_STATUS", 0, {}) - can_strings.append(can_list_to_can_capnp([can_msg], logMonoTime=log_mono_time)) + can_strings.append((log_mono_time, [can_msg])) parser.update_strings(can_strings) ts_nanos = parser.ts_nanos["VSA_STATUS"].values() diff --git a/can/tests/test_parser_performance.py b/can/tests/test_parser_performance.py index 2010fa4bf7..ac1bbdf93e 100755 --- a/can/tests/test_parser_performance.py +++ b/can/tests/test_parser_performance.py @@ -4,7 +4,6 @@ from opendbc.can.parser import CANParser from opendbc.can.packer import CANPacker -from opendbc.can.tests.test_packer_parser import can_list_to_can_capnp @unittest.skip("TODO: varies too much between machines") @@ -17,8 +16,7 @@ def _benchmark(self, checks, thresholds, n): for i in range(50000): values = {"ACC_CONTROL": {"ACC_TYPE": 1, "ALLOW_LONG_PRESS": 3}} msgs = [packer.make_can_msg(k, 0, v) for k, v in values.items()] - bts = can_list_to_can_capnp(msgs, logMonoTime=int(0.01 * i * 1e9)) - can_msgs.append(bts) + can_msgs.append([int(0.01 * i * 1e9), msgs]) ets = [] for _ in range(25): From a5738a57a3125d68dcb4feef11531e6841a6cfaa Mon Sep 17 00:00:00 2001 From: deanlee Date: Fri, 29 Mar 2024 15:47:48 +0800 Subject: [PATCH 06/15] reserve --- can/common.h | 1 + can/parser.cc | 8 ++++++++ 2 files changed, 9 insertions(+) diff --git a/can/common.h b/can/common.h index deffaf36fb..0fb17a7bdd 100644 --- a/can/common.h +++ b/can/common.h @@ -66,6 +66,7 @@ class CANParser { const int bus; const DBC *dbc = NULL; std::unordered_map message_states; + int32_t signal_count = -1; public: bool can_valid = false; diff --git a/can/parser.cc b/can/parser.cc index 2dee09a9a2..b367afef45 100644 --- a/can/parser.cc +++ b/can/parser.cc @@ -2,6 +2,7 @@ #include #include #include +#include #include #include @@ -243,6 +244,13 @@ void CANParser::query_latest(std::vector &vals, uint64_t last_ts) { if (last_ts == 0) { last_ts = last_nanos; } + + if (signal_count == -1) { + signal_count = std::accumulate(message_states.cbegin(), message_states.cend(), 0, [](int n, auto &it) { + return n + it.second.parse_sigs.size(); + }); + } + vals.reserve(signal_count); for (auto& kv : message_states) { auto& state = kv.second; if (last_ts != 0 && state.last_seen_nanos < last_ts) { From e8cec4918e27d6aa2c122a1a8d5b39c170acef8f Mon Sep 17 00:00:00 2001 From: deanlee Date: Fri, 29 Mar 2024 21:13:45 +0800 Subject: [PATCH 07/15] use itervalues --- can/parser_pyx.pyx | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/can/parser_pyx.pyx b/can/parser_pyx.pyx index 65d451520f..e48d703835 100644 --- a/can/parser_pyx.pyx +++ b/can/parser_pyx.pyx @@ -72,8 +72,8 @@ cdef class CANParser: # [nanos, [[address, 0, data, src], ...]] # [[nanos, [[address, 0, data, src], ...], ...]] - for v in self.vl_all.values(): - for l in v.values(): # no-cython-lint + for v in self.vl_all.itervalues(): + for l in v.itervalues(): # no-cython-lint l.clear() cdef vector[SignalValue] new_vals From c3367d0d00a4f3c8461e3d37638a6f16b3f39aa6 Mon Sep 17 00:00:00 2001 From: deanlee Date: Sat, 8 Jun 2024 20:33:19 +0800 Subject: [PATCH 08/15] rebase master --- can/common.h | 1 - can/parser.cc | 7 ------- can/parser_pyx.pyx | 15 +++++++-------- 3 files changed, 7 insertions(+), 16 deletions(-) diff --git a/can/common.h b/can/common.h index 0fb17a7bdd..deffaf36fb 100644 --- a/can/common.h +++ b/can/common.h @@ -66,7 +66,6 @@ class CANParser { const int bus; const DBC *dbc = NULL; std::unordered_map message_states; - int32_t signal_count = -1; public: bool can_valid = false; diff --git a/can/parser.cc b/can/parser.cc index b367afef45..8f056c7a51 100644 --- a/can/parser.cc +++ b/can/parser.cc @@ -244,13 +244,6 @@ void CANParser::query_latest(std::vector &vals, uint64_t last_ts) { if (last_ts == 0) { last_ts = last_nanos; } - - if (signal_count == -1) { - signal_count = std::accumulate(message_states.cbegin(), message_states.cend(), 0, [](int n, auto &it) { - return n + it.second.parse_sigs.size(); - }); - } - vals.reserve(signal_count); for (auto& kv : message_states) { auto& state = kv.second; if (last_ts != 0 && state.last_seen_nanos < last_ts) { diff --git a/can/parser_pyx.pyx b/can/parser_pyx.pyx index e48d703835..aec42f1822 100644 --- a/can/parser_pyx.pyx +++ b/can/parser_pyx.pyx @@ -5,7 +5,6 @@ from cython.operator cimport dereference as deref, preincrement as preinc from libcpp.pair cimport pair from libcpp.string cimport string from libcpp.vector cimport vector -from libcpp.unordered_set cimport unordered_set from libc.stdint cimport uint32_t from .common cimport CANParser as cpp_CANParser @@ -18,7 +17,6 @@ cdef class CANParser: cdef: cpp_CANParser *can const DBC *dbc - vector[SignalValue] can_values vector[uint32_t] addresses cdef readonly: @@ -66,18 +64,19 @@ cdef class CANParser: del self.can def update_strings(self, strings, sendcan=False): - for address in self.addresses: - self.vl_all[address].clear() # input format: # [nanos, [[address, 0, data, src], ...]] # [[nanos, [[address, 0, data, src], ...], ...]] + for address in self.addresses: + self.vl_all[address].clear() - for v in self.vl_all.itervalues(): - for l in v.itervalues(): # no-cython-lint - l.clear() + cur_address = -1 + vl = {} + vl_all = {} + ts_nanos = {} + updated_addrs = set() cdef vector[SignalValue] new_vals - cdef unordered_set[uint32_t] updated_addrs cdef CanFrame* frame cdef CanData* can_data cdef vector[CanData] can_data_array From 986dd5da073962bb79cc35fe89586e3d67335c55 Mon Sep 17 00:00:00 2001 From: deanlee Date: Wed, 12 Jun 2024 18:56:43 +0800 Subject: [PATCH 09/15] cleanup --- can/common.h | 2 +- can/parser.cc | 5 ++--- 2 files changed, 3 insertions(+), 4 deletions(-) diff --git a/can/common.h b/can/common.h index deffaf36fb..7d6c2fe022 100644 --- a/can/common.h +++ b/can/common.h @@ -83,7 +83,7 @@ class CANParser { void query_latest(std::vector &vals, uint64_t last_ts = 0); protected: - void update_can(const CanData &can); + void updateCans(const CanData &can); void UpdateValid(uint64_t nanos); }; diff --git a/can/parser.cc b/can/parser.cc index 8f056c7a51..36ba0faf8e 100644 --- a/can/parser.cc +++ b/can/parser.cc @@ -2,7 +2,6 @@ #include #include #include -#include #include #include @@ -169,14 +168,14 @@ void CANParser::update(const std::vector &can_data, std::vector Date: Tue, 30 Jul 2024 15:32:09 -0700 Subject: [PATCH 10/15] keep the same style --- can/tests/test_packer_parser.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/can/tests/test_packer_parser.py b/can/tests/test_packer_parser.py index 6386befa95..3d14358d69 100644 --- a/can/tests/test_packer_parser.py +++ b/can/tests/test_packer_parser.py @@ -264,7 +264,7 @@ def test_updated(self): can_msgs[frame].append(packer.make_can_msg("VSA_STATUS", 0, values)) idx += 1 - parser.update_strings([[0, can_msgs[0]], [0, can_msgs[1]]]) + parser.update_strings([[0, m] for m in can_msgs]) vl_all = parser.vl_all["VSA_STATUS"]["USER_BRAKE"] assert vl_all == user_brake_vals From f7b9a6ccec97b3da3e3dd92064645b5ad0da6118 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 30 Jul 2024 22:11:30 -0700 Subject: [PATCH 11/15] revert unrelated changes --- can/parser.cc | 2 +- can/parser_pyx.pyx | 1 + 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/can/parser.cc b/can/parser.cc index 36ba0faf8e..30d0729b82 100644 --- a/can/parser.cc +++ b/can/parser.cc @@ -195,7 +195,7 @@ void CANParser::updateCans(const CanData &can) { } // TODO: this actually triggers for some cars. fix and enable this - // if (dat.size() != state_it->second.size) { + //if (dat.size() != state_it->second.size) { // DEBUG("got message with unexpected length: expected %d, got %zu for %d", state_it->second.size, dat.size(), cmsg.getAddress()); // continue; //} diff --git a/can/parser_pyx.pyx b/can/parser_pyx.pyx index 3a4d3398a7..9fb0c9f021 100644 --- a/can/parser_pyx.pyx +++ b/can/parser_pyx.pyx @@ -13,6 +13,7 @@ from .common cimport dbc_lookup, SignalValue, DBC, CanData, CanFrame import numbers from collections import defaultdict + cdef class CANParser: cdef: cpp_CANParser *can From 125141e01759c3c4f7a931076fe9e309d3c8f95b Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 30 Jul 2024 22:37:21 -0700 Subject: [PATCH 12/15] truly no cereal! --- Dockerfile | 5 ----- 1 file changed, 5 deletions(-) diff --git a/Dockerfile b/Dockerfile index df3cb56b8d..f11ed990b1 100644 --- a/Dockerfile +++ b/Dockerfile @@ -44,11 +44,6 @@ ENV PYTHONPATH=/project RUN git config --global --add safe.directory '*' WORKDIR /project -RUN git clone https://github.com/commaai/cereal.git /project/cereal && \ - cd /project/cereal && \ - git checkout 861144c136c91f70dcbc652c2ffe99f57440ad47 && \ - rm -rf .git && \ - scons -j$(nproc) --minimal COPY SConstruct . COPY ./site_scons /project/site_scons From 5ab2616e9a26bf013a694562661dcd19d8772b54 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 30 Jul 2024 23:08:15 -0700 Subject: [PATCH 13/15] same capitalization same capitalization --- can/common.h | 2 +- can/parser.cc | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/can/common.h b/can/common.h index 7d6c2fe022..8b5b8d320d 100644 --- a/can/common.h +++ b/can/common.h @@ -83,7 +83,7 @@ class CANParser { void query_latest(std::vector &vals, uint64_t last_ts = 0); protected: - void updateCans(const CanData &can); + void UpdateCans(const CanData &can); void UpdateValid(uint64_t nanos); }; diff --git a/can/parser.cc b/can/parser.cc index 30d0729b82..8b78e73e81 100644 --- a/can/parser.cc +++ b/can/parser.cc @@ -168,14 +168,14 @@ void CANParser::update(const std::vector &can_data, std::vector Date: Tue, 30 Jul 2024 23:13:17 -0700 Subject: [PATCH 14/15] parser: declutter nanos usage (#1067) thought there'd be more --- can/parser.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/can/parser.cc b/can/parser.cc index 8b78e73e81..5e5a132ac4 100644 --- a/can/parser.cc +++ b/can/parser.cc @@ -211,7 +211,7 @@ void CANParser::UpdateCans(const CanData &can) { } void CANParser::UpdateValid(uint64_t nanos) { - const bool show_missing = (last_nanos - first_nanos) > 8e9; + const bool show_missing = (nanos - first_nanos) > 8e9; bool _valid = true; bool _counters_valid = true; From 379d54be92748cd281df3d3b99bcb836236be9f8 Mon Sep 17 00:00:00 2001 From: Shane Smiskol Date: Tue, 30 Jul 2024 23:22:07 -0700 Subject: [PATCH 15/15] revert more --- can/parser.cc | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/can/parser.cc b/can/parser.cc index 5e5a132ac4..a65a8ec2d6 100644 --- a/can/parser.cc +++ b/can/parser.cc @@ -171,12 +171,14 @@ void CANParser::update(const std::vector &can_data, std::vector