diff --git a/README.md b/README.md index 1149cd20..cfbf7d35 100644 --- a/README.md +++ b/README.md @@ -67,7 +67,7 @@ At its most basic, a car port will control the steering on a car. A "complete" c ### Connect to the Car -The first step is to get connected to the car with a comma 3X and a car harness. +The first step is to get connected to the car with a comma four and a car harness. The car harness gets you connected to two different CAN buses and splits one of those buses to send our own actuation messages. If you're lucky, a harness compatible with your car will already be designed and sold on comma.ai/shop. @@ -151,7 +151,7 @@ In addition to the standard bounties, we also offer higher value bounties for mo ## FAQ -***How do I use this?*** A [comma 3X](https://comma.ai/shop/comma-3x) is custom-designed to be the best way to run and develop opendbc and openpilot. +***How do I use this?*** A [comma four](https://comma.ai/shop/comma-four) is custom-designed to be the best way to run and develop opendbc and openpilot. ***Which cars are supported?*** See the [supported cars list](docs/CARS.md). @@ -179,7 +179,7 @@ In addition to the standard bounties, we also offer higher value bounties for mo * **[DBC file](https://en.wikipedia.org/wiki/CAN_bus#DBC)**: contains definitions for messages on a CAN bus * **[openpilot](https://github.com/commaai/openpilot)**: an ADAS system for cars supported by opendbc * **[comma](https://github.com/commaai)**: the company behind opendbc -* **[comma 3X](https://comma.ai/shop/comma-3x)**: the hardware used to run openpilot +* **[comma four](https://comma.ai/shop/comma-four)**: the hardware used to run openpilot ### More resources diff --git a/SConscript b/SConscript index 86c47fb3..6e191d71 100644 --- a/SConscript +++ b/SConscript @@ -1,6 +1,4 @@ -Import("env") - -SConscript(['opendbc/dbc/SConscript'], exports={'env': env}) +SConscript(['opendbc/dbc/SConscript']) # test files if GetOption('extras'): diff --git a/SConstruct b/SConstruct index 14fff6bf..b18d9fdf 100644 --- a/SConstruct +++ b/SConstruct @@ -1,27 +1,9 @@ -import os -import subprocess -import platform - -arch = subprocess.check_output(["uname", "-m"], encoding='utf8').rstrip() -if platform.system() == "Darwin": - arch = "Darwin" - -cpppath = [ - '#', - '/usr/lib/include', -] - AddOption('--minimal', action='store_false', dest='extras', default=True, help='the minimum build. no tests, tools, etc.') -AddOption('--asan', - action='store_true', - help='turn on ASAN') - -# safety options AddOption('--ubsan', action='store_true', help='turn on UBSan') @@ -30,39 +12,4 @@ AddOption('--coverage', action='store_true', help='build with test coverage options') -AddOption('--mutation', - action='store_true', - help='generate mutation-ready code') - -ccflags_asan = ["-fsanitize=address", "-fno-omit-frame-pointer"] if GetOption('asan') else [] -ldflags_asan = ["-fsanitize=address"] if GetOption('asan') else [] - -env = Environment( - ENV=os.environ, - CC='gcc', - CXX='g++', - CCFLAGS=[ - "-g", - "-fPIC", - "-O2", - "-Wunused", - "-Werror", - "-Wshadow", - "-Wno-vla-cxx-extension", - "-Wno-unknown-warning-option", # for compatibility across compiler versions - ] + ccflags_asan, - LDFLAGS=ldflags_asan, - LINKFLAGS=ldflags_asan, - CFLAGS="-std=gnu11", - CXXFLAGS=["-std=c++1z"], - CPPPATH=cpppath, - tools=["default", "compilation_db"] -) -if arch != "Darwin": - env.Append(CCFLAGS=["-fmax-errors=1", ]) - -env.CompilationDatabase('compile_commands.json') - -Export('env', 'arch') - SConscript(['SConscript']) diff --git a/docs/CARS.md b/docs/CARS.md index 96c5000c..b01501f5 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -1,6 +1,6 @@ -# Support Information for 379 Known Cars +# Support Information for 384 Known Cars |Make|Model|Package|Support Level| |---|---|---|:---:| @@ -9,6 +9,7 @@ |Acura|Integra 2023-25|All|[Community](#community)| |Acura|MDX 2015-16|Advance Package|[Community](#community)| |Acura|MDX 2017-20|All|[Community](#community)| +|Acura|MDX 2022-24|All|[Community](#community)| |Acura|MDX 2025|All except Type S|[Upstream](#upstream)| |Acura|RDX 2016-18|AcuraWatch Plus or Advance Package|[Upstream](#upstream)| |Acura|RDX 2019-21|All|[Upstream](#upstream)| @@ -16,6 +17,8 @@ |Acura|RLX 2017|Advance Package or Technology Package|[Community](#community)| |Acura|TLX 2015-17|Advance Package|[Community](#community)| |Acura|TLX 2018-20|All|[Community](#community)| +|Acura|TLX 2021|All|[Upstream](#upstream)| +|Acura|TLX 2022-23|All|[Community](#community)| |Acura|ZDX 2024|All|[Not compatible](#can-bus-security)| |Audi|A3 2014-19|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| |Audi|A3 Sportback e-tron 2017-18|Adaptive Cruise Control (ACC) & Lane Assist|[Upstream](#upstream)| @@ -94,11 +97,11 @@ |Honda|Civic Hatchback 2022-24|All|[Upstream](#upstream)| |Honda|Civic Hatchback Hybrid 2025-26|All|[Upstream](#upstream)| |Honda|Civic Hatchback Hybrid (Europe only) 2023|All|[Upstream](#upstream)| -|Honda|Civic Hybrid 2025|All|[Upstream](#upstream)| +|Honda|Civic Hybrid 2025-26|All|[Upstream](#upstream)| |Honda|Clarity 2018-21|All|[Community](#community)| |Honda|CR-V 2015-16|Touring Trim|[Upstream](#upstream)| |Honda|CR-V 2017-22|Honda Sensing|[Upstream](#upstream)| -|Honda|CR-V 2023-25|All|[Upstream](#upstream)| +|Honda|CR-V 2023-26|All|[Upstream](#upstream)| |Honda|CR-V Hybrid 2017-22|Honda Sensing|[Upstream](#upstream)| |Honda|CR-V Hybrid 2023-25|All|[Upstream](#upstream)| |Honda|e 2020|All|[Upstream](#upstream)| @@ -108,10 +111,11 @@ |Honda|HR-V 2023-25|All|[Upstream](#upstream)| |Honda|Insight 2019-22|All|[Upstream](#upstream)| |Honda|Inspire 2018|All|[Upstream](#upstream)| +|Honda|N-Box 2018|All|[Upstream](#upstream)| |Honda|Odyssey 2018-20|Honda Sensing|[Upstream](#upstream)| -|Honda|Odyssey 2021-25|All|[Community](#community)| +|Honda|Odyssey 2021-26|All|[Upstream](#upstream)| |Honda|Passport 2019-25|All|[Upstream](#upstream)| -|Honda|Passport 2026|All|[Community](#community)| +|Honda|Passport 2026|All|[Upstream](#upstream)| |Honda|Pilot 2016-22|Honda Sensing|[Upstream](#upstream)| |Honda|Pilot 2023-25|All|[Upstream](#upstream)| |Honda|Prologue 2024-25|All|[Not compatible](#can-bus-security)| @@ -238,11 +242,12 @@ |Mazda|CX-5 2022-25|All|[Upstream](#upstream)| |Mazda|CX-9 2016-20|All|[Dashcam mode](#dashcam)| |Mazda|CX-9 2021-23|All|[Upstream](#upstream)| -|Nissan|Altima 2019-20|ProPILOT Assist|[Upstream](#upstream)| +|Nissan|Altima 2019-20, 2024|ProPILOT Assist|[Upstream](#upstream)| |Nissan|Leaf 2018-23|ProPILOT Assist|[Upstream](#upstream)| |Nissan|Rogue 2018-20|ProPILOT Assist|[Upstream](#upstream)| |Nissan|X-Trail 2017|ProPILOT Assist|[Upstream](#upstream)| |Peugeot|208 2019-25|Adaptive Cruise Control (ACC) & Lane Assist|[Dashcam mode](#dashcam)| +|Porsche|Macan 2017-24|Adaptive Cruise Control (ACC) & Lane Assist|[Dashcam mode](#dashcam)| |Ram|1500 2019-24|Adaptive Cruise Control (ACC)|[Upstream](#upstream)| |Ram|2500 2020-24|Adaptive Cruise Control (ACC)|[Dashcam mode](#dashcam)| |Ram|3500 2019-22|Adaptive Cruise Control (ACC)|[Dashcam mode](#dashcam)| @@ -423,7 +428,6 @@ Supported Models' section of each make [on our wiki](https://wiki.comma.ai/). Some notable works-in-progress: * Honda * 2022-24 Acura RDX, commaai/opendbc#1967 - * 2021-25 Honda Odyssey, commaai/opendbc#2488 * Camera ACC stability improvements, commaai/opendbc#2192 * Alpha longitudinal stability improvements, commaai/opendbc#2347 and commaai/opendbc#2165 diff --git a/opendbc/can/dbc.py b/opendbc/can/dbc.py index 658bbdab..1e79bb08 100644 --- a/opendbc/can/dbc.py +++ b/opendbc/can/dbc.py @@ -11,6 +11,7 @@ from opendbc.car.toyota.toyotacan import toyota_checksum from opendbc.car.subaru.subarucan import subaru_checksum from opendbc.car.chrysler.chryslercan import chrysler_checksum, fca_giorgio_checksum from opendbc.car.hyundai.hyundaicanfd import hkg_can_fd_checksum +from opendbc.car.volkswagen.mlbcan import volkswagen_mlb_checksum from opendbc.car.volkswagen.mqbcan import volkswagen_mqb_meb_checksum, xor_checksum from opendbc.car.tesla.teslacan import tesla_checksum from opendbc.car.body.bodycan import body_checksum @@ -31,6 +32,7 @@ class SignalType: FCA_GIORGIO_CHECKSUM = 10 TESLA_CHECKSUM = 11 PSA_CHECKSUM = 12 + VOLKSWAGEN_MLB_CHECKSUM = 13 @dataclass @@ -186,6 +188,8 @@ def get_checksum_state(dbc_name: str) -> ChecksumState | None: return ChecksumState(16, -1, 0, -1, True, SignalType.HKG_CAN_FD_CHECKSUM, hkg_can_fd_checksum) elif dbc_name.startswith(("vw_mqb", "vw_mqbevo", "vw_meb")): return ChecksumState(8, 4, 0, 0, True, SignalType.VOLKSWAGEN_MQB_MEB_CHECKSUM, volkswagen_mqb_meb_checksum) + elif dbc_name.startswith("vw_mlb"): + return ChecksumState(8, 4, 0, 0, True, SignalType.VOLKSWAGEN_MLB_CHECKSUM, volkswagen_mlb_checksum) elif dbc_name.startswith("vw_pq"): return ChecksumState(8, 4, 0, -1, True, SignalType.XOR_CHECKSUM, xor_checksum) elif dbc_name.startswith("subaru_global_"): diff --git a/opendbc/car/car.capnp b/opendbc/car/car.capnp index d237e353..10f49bc1 100644 --- a/opendbc/car/car.capnp +++ b/opendbc/car/car.capnp @@ -549,14 +549,15 @@ struct CarParams { } struct LateralTorqueTuning { - kp @1 :Float32; - ki @2 :Float32; friction @3 :Float32; - kf @4 :Float32; steeringAngleDeadzoneDeg @5 :Float32; latAccelFactor @6 :Float32; latAccelOffset @7 :Float32; useSteeringAngleDEPRECATED @0 :Bool; + kpDEPRECATED @1 :Float32; + kiDEPRECATED @2 :Float32; + kfDEPRECATED @4 :Float32; + kdDEPRECATED @8 : Float32; } struct LongitudinalPIDTuning { @@ -564,7 +565,7 @@ struct CarParams { kpV @1 :List(Float32); kiBP @2 :List(Float32); kiV @3 :List(Float32); - kf @6 :Float32; + kfDEPRECATED @6 :Float32; deadzoneBPDEPRECATED @4 :List(Float32); deadzoneVDEPRECATED @5 :List(Float32); } diff --git a/opendbc/car/chrysler/fingerprints.py b/opendbc/car/chrysler/fingerprints.py index 9d7caa96..cd7642aa 100644 --- a/opendbc/car/chrysler/fingerprints.py +++ b/opendbc/car/chrysler/fingerprints.py @@ -354,6 +354,7 @@ FW_VERSIONS = { b'68402707AB', b'68402708AB', b'68402714AB', + b'68402736AB', b'68402971AD', b'68454144AD', b'68454145AB', @@ -382,6 +383,7 @@ FW_VERSIONS = { b'68417279AA', b'68417280AA', b'68417281AA', + b'68417283AA', b'68453431AA', b'68453433AA', b'68453435AA', @@ -394,6 +396,7 @@ FW_VERSIONS = { b'05035674AB ', b'68412635AE ', b'68412635AG ', + b'68412635AH ', b'68412660AD ', b'68412660AF ', b'68422860AB', @@ -407,6 +410,7 @@ FW_VERSIONS = { (Ecu.transmission, 0x7e1, None): [ b'05035707AA', b'68419672AC', + b'68419675AC', b'68419678AB', b'68423905AB', b'68449258AC', diff --git a/opendbc/car/common/filter_simple.py b/opendbc/car/common/filter_simple.py index 0ec7a515..c08bde38 100644 --- a/opendbc/car/common/filter_simple.py +++ b/opendbc/car/common/filter_simple.py @@ -2,17 +2,43 @@ class FirstOrderFilter: # first order filter def __init__(self, x0, rc, dt, initialized=True): self.x = x0 - self.dt = dt + self._dt = dt self.update_alpha(rc) self.initialized = initialized + def update_dt(self, dt): + self._dt = dt + self.update_alpha(self._rc) + def update_alpha(self, rc): - self.alpha = self.dt / (rc + self.dt) + self._rc = rc + self._alpha = self._dt / (self._rc + self._dt) def update(self, x): if self.initialized: - self.x = (1. - self.alpha) * self.x + self.alpha * x + self.x = (1. - self._alpha) * self.x + self._alpha * x else: self.initialized = True self.x = x return self.x + + +class HighPassFilter: + # technically a band-pass filter + def __init__(self, x0, rc1, rc2, dt, initialized=True): + self.x = x0 + self._f1 = FirstOrderFilter(x0, rc1, dt, initialized) + self._f2 = FirstOrderFilter(x0, rc2, dt, initialized) + assert rc2 > rc1, "rc2 must be greater than rc1" + + def update_dt(self, dt): + self._f1.update_dt(dt) + self._f2.update_dt(dt) + + def update_alpha(self, rc1, rc2): + self._f1.update_alpha(rc1) + self._f2.update_alpha(rc2) + + def update(self, x): + self.x = self._f1.update(x) - self._f2.update(x) + return self.x diff --git a/opendbc/car/docs_definitions.py b/opendbc/car/docs_definitions.py index 5b06cfaf..df63a505 100644 --- a/opendbc/car/docs_definitions.py +++ b/opendbc/car/docs_definitions.py @@ -72,7 +72,6 @@ class EnumBase(Enum): class Mount(EnumBase): mount = BasePart("mount") - angled_mount_8_degrees = BasePart("angled mount (8 degrees)") class Cable(EnumBase): @@ -80,8 +79,7 @@ class Cable(EnumBase): usb_a_2_a_cable = BasePart("USB A-A cable") usbc_otg_cable = BasePart("USB C OTG cable") usbc_coupler = BasePart("USB-C coupler") - obd_c_cable_1_5ft = BasePart("OBD-C cable (1.5 ft)") - right_angle_obd_c_cable_1_5ft = BasePart("right angle OBD-C cable (1.5 ft)") + obd_c_cable_2ft = BasePart("OBD-C cable (2 ft)") class Accessory(EnumBase): @@ -143,8 +141,8 @@ class CarHarness(EnumBase): ford_q3 = BaseCarHarness("Ford Q3 connector") ford_q4 = BaseCarHarness("Ford Q4 connector", parts=[Accessory.harness_box, Accessory.comma_power, Cable.long_obdc_cable, Cable.usbc_coupler]) rivian = BaseCarHarness("Rivian A connector", parts=[Accessory.harness_box, Accessory.comma_power, Cable.long_obdc_cable, Cable.usbc_coupler]) - tesla_a = BaseCarHarness("Tesla A connector", parts=[Accessory.harness_box, Accessory.comma_power, Cable.long_obdc_cable, Cable.usbc_coupler]) - tesla_b = BaseCarHarness("Tesla B connector", parts=[Accessory.harness_box, Accessory.comma_power, Cable.long_obdc_cable, Cable.usbc_coupler]) + tesla_a = BaseCarHarness("Tesla A connector", parts=[Accessory.harness_box, Cable.long_obdc_cable, Cable.usbc_coupler]) + tesla_b = BaseCarHarness("Tesla B connector", parts=[Accessory.harness_box, Cable.long_obdc_cable, Cable.usbc_coupler]) psa_a = BaseCarHarness("PSA A connector", parts=[Accessory.harness_box, Cable.long_obdc_cable, Cable.usbc_coupler]) # custom harness @@ -152,15 +150,7 @@ class CarHarness(EnumBase): class Device(EnumBase): - threex = BasePart("comma 3X", parts=[Mount.mount, Cable.right_angle_obd_c_cable_1_5ft]) - # variant of comma 3X with angled mounts - threex_angled_mount = BasePart("comma 3X", parts=[Mount.angled_mount_8_degrees, Cable.right_angle_obd_c_cable_1_5ft]) - red_panda = BasePart("red panda") - - -class Kit(EnumBase): - red_panda_kit = BasePart("CAN FD panda kit", parts=[Device.red_panda, Accessory.harness_box, - Cable.usb_a_2_a_cable, Cable.usbc_otg_cable, Cable.obd_c_cable_1_5ft]) + four = BasePart("comma four", parts=[Mount.mount, Cable.obd_c_cable_2ft]) class PartType(Enum): @@ -168,12 +158,11 @@ class PartType(Enum): cable = Cable connector = CarHarness device = Device - kit = Kit mount = Mount tool = Tool -DEFAULT_CAR_PARTS: list[EnumBase] = [Device.threex] +DEFAULT_CAR_PARTS: list[EnumBase] = [Device.four] @dataclass @@ -273,6 +262,7 @@ class CarDocs: def init(self, CP: CarParams, all_footnotes=None): self.brand = CP.brand self.car_fingerprint = CP.carFingerprint + self.longitudinal_control = CP.openpilotLongitudinalControl and not CP.alphaLongitudinalAvailable if self.merged and CP.dashcamOnly: if self.support_type != SupportType.REVIEW: diff --git a/opendbc/car/extra_cars.py b/opendbc/car/extra_cars.py index c500c846..5ffa42bf 100644 --- a/opendbc/car/extra_cars.py +++ b/opendbc/car/extra_cars.py @@ -40,14 +40,15 @@ class CAR(Platforms): CommunityCarDocs("Acura Integra 2023-25", "All"), CommunityCarDocs("Acura MDX 2015-16", "Advance Package"), CommunityCarDocs("Acura MDX 2017-20", "All"), + CommunityCarDocs("Acura MDX 2022-24", "All"), CommunityCarDocs("Acura RDX 2022-25", "All"), CommunityCarDocs("Acura RLX 2017", "Advance Package or Technology Package"), CommunityCarDocs("Acura TLX 2015-17", "Advance Package"), CommunityCarDocs("Acura TLX 2018-20", "All"), + CommunityCarDocs("Acura TLX 2022-23", "All"), GMSecurityCarDocs("Acura ZDX 2024", "All"), CommunityCarDocs("Honda Accord 2016-17", "Honda Sensing"), CommunityCarDocs("Honda Clarity 2018-21", "All"), - CommunityCarDocs("Honda Passport 2026", "All"), GMSecurityCarDocs("Honda Prologue 2024-25", "All"), ], ) diff --git a/opendbc/car/ford/values.py b/opendbc/car/ford/values.py index 2bda03b8..6b8c1b3c 100644 --- a/opendbc/car/ford/values.py +++ b/opendbc/car/ford/values.py @@ -6,8 +6,7 @@ from enum import Enum, IntFlag from opendbc.car import Bus, CarSpecs, DbcDict, PlatformConfig, Platforms, uds from opendbc.car.lateral import AngleSteeringLimits from opendbc.car.structs import CarParams -from opendbc.car.docs_definitions import CarFootnote, CarHarness, CarDocs, CarParts, Column, \ - Device +from opendbc.car.docs_definitions import CarFootnote, CarHarness, CarDocs, CarParts, Column from opendbc.car.fw_query_definitions import FwQueryConfig, LiveFwVersions, OfflineFwVersions, Request, StdQueries, p16 Ecu = CarParams.Ecu @@ -75,10 +74,7 @@ class FordCarDocs(CarDocs): def init_make(self, CP: 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]) + self.car_parts = CarParts.common([harness]) if harness == CarHarness.ford_q4: self.setup_video = "https://www.youtube.com/watch?v=uUGkH6C_EQU" diff --git a/opendbc/car/honda/carcontroller.py b/opendbc/car/honda/carcontroller.py index 901ee4e8..39921898 100644 --- a/opendbc/car/honda/carcontroller.py +++ b/opendbc/car/honda/carcontroller.py @@ -4,7 +4,7 @@ from opendbc.can import CANPacker from opendbc.car import Bus, DT_CTRL, rate_limit, make_tester_present_msg, structs from opendbc.car.honda import hondacan from opendbc.car.honda.values import CAR, CruiseButtons, HONDA_BOSCH, HONDA_BOSCH_CANFD, HONDA_BOSCH_RADARLESS, \ - HONDA_NIDEC_ALT_PCM_ACCEL, CarControllerParams + HONDA_BOSCH_TJA_CONTROL, HONDA_NIDEC_ALT_PCM_ACCEL, CarControllerParams from opendbc.car.interfaces import CarControllerBase from opendbc.sunnypilot.car.honda.mads import MadsCarController @@ -101,6 +101,7 @@ class CarController(CarControllerBase, MadsCarController, GasInterceptorCarContr self.packer = CANPacker(dbc_names[Bus.pt]) self.params = CarControllerParams(CP) self.CAN = hondacan.CanBus(CP) + self.tja_control = CP.carFingerprint in HONDA_BOSCH_TJA_CONTROL self.braking = False self.brake_steady = 0. @@ -159,7 +160,7 @@ class CarController(CarControllerBase, MadsCarController, GasInterceptorCarContr can_sends.append(make_tester_present_msg(0x18DAB0F1, 1, suppress_response=True)) # Send steering command. - can_sends.append(hondacan.create_steering_control(self.packer, self.CAN, apply_torque, CC.latActive)) + can_sends.append(hondacan.create_steering_control(self.packer, self.CAN, apply_torque, CC.latActive, self.tja_control)) # wind brake from air resistance decel at high speed wind_brake = np.interp(CS.out.vEgo, [0.0, 2.3, 35.0], [0.001, 0.002, 0.15]) diff --git a/opendbc/car/honda/fingerprints.py b/opendbc/car/honda/fingerprints.py index eb976f29..b587c714 100644 --- a/opendbc/car/honda/fingerprints.py +++ b/opendbc/car/honda/fingerprints.py @@ -29,7 +29,7 @@ FW_VERSIONS = { ], (Ecu.fwdCamera, 0x18dab5f1, None): [ b'38897-TTA-J010\x00\x00', - ] + ], }, CAR.HONDA_ACCORD: { (Ecu.shiftByWire, 0x18da0bf1, None): [ @@ -334,6 +334,7 @@ FW_VERSIONS = { (Ecu.vsa, 0x18da28f1, None): [ b'57114-T1W-A230\x00\x00', b'57114-T1W-A240\x00\x00', + b'57114-TFF-A930\x00\x00', b'57114-TFF-A940\x00\x00', ], (Ecu.srs, 0x18da53f1, None): [ @@ -723,20 +724,16 @@ FW_VERSIONS = { (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', @@ -744,32 +741,27 @@ FW_VERSIONS = { 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', ], }, @@ -893,11 +885,13 @@ FW_VERSIONS = { b'38897-TX6-A010\x00\x00', ], (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36161-TV9-A040\x00\x00', b'36161-TV9-A140\x00\x00', b'36161-TV9-C140\x00\x00', b'36161-TX6-A030\x00\x00', ], (Ecu.srs, 0x18da53f1, None): [ + b'77959-TX6-A210\x00\x00', b'77959-TX6-A230\x00\x00', b'77959-TX6-C210\x00\x00', ], @@ -979,6 +973,7 @@ FW_VERSIONS = { b'8S102-T47-AA20\x00\x00', b'8S102-T50-EA10\x00\x00', b'8S102-T56-A060\x00\x00', + b'8S102-T56-A070\x00\x00', b'8S102-T60-AA10\x00\x00', b'8S102-T64-A040\x00\x00', ], @@ -1022,11 +1017,14 @@ FW_VERSIONS = { CAR.HONDA_CRV_6G: { (Ecu.fwdRadar, 0x18dab0f1, None): [ b'8S302-3A0-A060\x00\x00', + b'8S302-3A0-A220\x00\x00', b'8S302-3C0-Q050\x00\x00', b'8S302-3D4-A050\x00\x00', ], (Ecu.fwdCamera, 0x18dab5f1, None): [ + b'8S102-3A0-A090\x00\x00', b'8S102-3A0-A110\x00\x00', + b'8S102-3A0-A230\x00\x00', b'8S102-3C0-Q060\x00\x00', b'8S102-3D4-A060\x00\x00', b'8S102-3D4-A070\x00\x00', @@ -1054,6 +1052,22 @@ FW_VERSIONS = { b'28101-63B-M420\x00\x00', ], }, + CAR.HONDA_PASSPORT_4G: { + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'8S302-3BM-A020\x00\x00', + ], + (Ecu.fwdCamera, 0x18dab5f1, None): [ + b'8S102-3BM-A020\x00\x00', + ], + }, + CAR.ACURA_TLX_2G: { + (Ecu.fwdRadar, 0x18dab0f1, None): [ + b'36802-TGV-A060\x00\x00', + ], + (Ecu.fwdCamera, 0x18dab5f1, None): [ + b'36161-TGV-A030\x00\x00', + ], + }, } FW_VERSIONS = merge_fw_versions(FW_VERSIONS, FW_VERSIONS_EXT) diff --git a/opendbc/car/honda/hondacan.py b/opendbc/car/honda/hondacan.py index 45c3458e..0cf6151a 100644 --- a/opendbc/car/honda/hondacan.py +++ b/opendbc/car/honda/hondacan.py @@ -121,11 +121,15 @@ def create_acc_commands(packer, CAN, enabled, active, accel, gas, stopping_count return commands -def create_steering_control(packer, CAN, apply_torque, lkas_active): +def create_steering_control(packer, CAN, apply_torque, lkas_active, tja_control): values = { "STEER_TORQUE": apply_torque if lkas_active else 0, "STEER_TORQUE_REQUEST": lkas_active, } + + if tja_control: + values["STEER_DOWN_TO_ZERO"] = lkas_active + return packer.make_can_msg("STEERING_CONTROL", CAN.lkas, values) diff --git a/opendbc/car/honda/interface.py b/opendbc/car/honda/interface.py index c15a3f1a..e40eb9f4 100755 --- a/opendbc/car/honda/interface.py +++ b/opendbc/car/honda/interface.py @@ -52,7 +52,7 @@ class CarInterface(CarInterfaceBase): # If Bosch radarless, this blocks ACC messages from the camera # TODO: get radar disable working on Bosch CANFD ret.alphaLongitudinalAvailable = candidate not in HONDA_BOSCH_CANFD - ret.openpilotLongitudinalControl = alpha_long + ret.openpilotLongitudinalControl = alpha_long and (candidate not in HONDA_BOSCH_CANFD) ret.pcmCruise = not ret.openpilotLongitudinalControl else: ret.safetyConfigs = [get_safety_config(structs.CarParams.SafetyModel.hondaNidec)] diff --git a/opendbc/car/honda/tests/test_honda.py b/opendbc/car/honda/tests/test_honda.py index 7142393a..def5a821 100644 --- a/opendbc/car/honda/tests/test_honda.py +++ b/opendbc/car/honda/tests/test_honda.py @@ -1,6 +1,7 @@ import re from opendbc.car.honda.fingerprints import FW_VERSIONS +from opendbc.car.honda.values import HONDA_BOSCH, HONDA_BOSCH_TJA_CONTROL HONDA_FW_VERSION_RE = br"[A-Z0-9]{5}(-|,)[A-Z0-9]{3}(-|,)[A-Z0-9]{4}(\x00){2}$" @@ -12,3 +13,6 @@ class TestHondaFingerprint: for fws in fw_by_ecu.values(): for fw in fws: assert re.match(HONDA_FW_VERSION_RE, fw) is not None, fw + + def test_tja_bosch_only(self): + assert set(HONDA_BOSCH_TJA_CONTROL).issubset(set(HONDA_BOSCH)), "Nidec car found in TJA control list" diff --git a/opendbc/car/honda/values.py b/opendbc/car/honda/values.py index 207fc955..9da29c59 100644 --- a/opendbc/car/honda/values.py +++ b/opendbc/car/honda/values.py @@ -3,7 +3,7 @@ from enum import Enum, IntFlag from opendbc.car import Bus, CarSpecs, DbcDict, PlatformConfig, Platforms, structs, uds from opendbc.car.common.conversions import Conversions as CV -from opendbc.car.docs_definitions import CarFootnote, CarHarness, CarDocs, CarParts, Column, Device +from opendbc.car.docs_definitions import CarFootnote, CarHarness, CarDocs, CarParts, Column from opendbc.car.fw_query_definitions import FwQueryConfig, Request, StdQueries, p16 Ecu = structs.CarParams.Ecu @@ -78,6 +78,7 @@ class HondaFlags(IntFlag): BOSCH_ALT_RADAR = 512 ALLOW_MANUAL_TRANS = 1024 HYBRID = 2048 + BOSCH_TJA_CONTROL = 4096 # Car button codes @@ -108,10 +109,7 @@ class HondaCarDocs(CarDocs): else: harness = CarHarness.nidec - if CP.carFingerprint in (CAR.HONDA_PILOT_4G,): - self.car_parts = CarParts([Device.threex_angled_mount, harness]) - else: - self.car_parts = CarParts.common([harness]) + self.car_parts = CarParts.common([harness]) if CP.carFingerprint in (CAR.HONDA_CLARITY,): self.car_parts = CarParts.common([CarHarness.honda_clarity]) @@ -173,6 +171,7 @@ class CAR(Platforms): # 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), {Bus.pt: 'honda_civic_hatchback_ex_2017_can_generated'}, + flags=HondaFlags.ALLOW_MANUAL_TRANS, ) HONDA_ACCORD_11G = HondaBoschCANFDPlatformConfig( [ @@ -199,7 +198,7 @@ class CAR(Platforms): HONDA_CIVIC_2022 = HondaBoschPlatformConfig( [ HondaCarDocs("Honda Civic 2022-24", "All", video="https://youtu.be/ytiOT5lcp6Q"), - HondaCarDocs("Honda Civic Hybrid 2025", "All"), + HondaCarDocs("Honda Civic Hybrid 2025-26", "All"), HondaCarDocs("Honda Civic Hatchback 2022-24", "All", video="https://youtu.be/ytiOT5lcp6Q"), HondaCarDocs("Honda Civic Hatchback Hybrid (Europe only) 2023", "All"), # TODO: Confirm 2024 @@ -218,7 +217,7 @@ class CAR(Platforms): ) HONDA_CRV_6G = HondaBoschCANFDPlatformConfig( [ - HondaCarDocs("Honda CR-V 2023-25", "All"), + HondaCarDocs("Honda CR-V 2023-26", "All"), HondaCarDocs("Honda CR-V Hybrid 2023-25", "All"), ], CarSpecs(mass=1703, wheelbase=2.7, steerRatio=16.2, centerToFrontRatio=0.42), @@ -261,17 +260,27 @@ class CAR(Platforms): [HondaCarDocs("Honda Pilot 2023-25", "All")], CarSpecs(mass=4660 * CV.LB_TO_KG, wheelbase=2.89, centerToFrontRatio=0.442, steerRatio=17.5), ) + HONDA_PASSPORT_4G = HondaBoschCANFDPlatformConfig( + [HondaCarDocs("Honda Passport 2026", "All")], + CarSpecs(mass=4620 * CV.LB_TO_KG, wheelbase=2.89, centerToFrontRatio=0.442, steerRatio=18.5), + ) # mid-model refresh ACURA_MDX_4G_MMR = HondaBoschCANFDPlatformConfig( [HondaCarDocs("Acura MDX 2025", "All except Type S")], CarSpecs(mass=4544 * CV.LB_TO_KG, wheelbase=2.89, centerToFrontRatio=0.428, steerRatio=16.2), ) HONDA_ODYSSEY_5G_MMR = HondaBoschPlatformConfig( - [HondaCarDocs("Honda Odyssey 2021-25", "All", min_steer_speed=70. * CV.KPH_TO_MS)], + [HondaCarDocs("Honda Odyssey 2021-26", "All", min_steer_speed=70. * CV.KPH_TO_MS)], CarSpecs(mass=4590 * CV.LB_TO_KG, wheelbase=3.00, steerRatio=19.4, centerToFrontRatio=0.41), {Bus.pt: 'acura_rdx_2020_can_generated'}, flags=HondaFlags.BOSCH_ALT_BRAKE | HondaFlags.BOSCH_ALT_RADAR, ) + ACURA_TLX_2G = HondaBoschPlatformConfig( + [HondaCarDocs("Acura TLX 2021", "All")], + CarSpecs(mass=3982 * CV.LB_TO_KG, wheelbase=2.87, steerRatio=14.0, centerToFrontRatio=0.43), + {Bus.pt: 'honda_civic_hatchback_ex_2017_can_generated'}, + flags=HondaFlags.BOSCH_ALT_RADAR, + ) # Nidec Cars ACURA_ILX = HondaNidecPlatformConfig( @@ -362,6 +371,7 @@ HONDA_BOSCH = CAR.with_flags(HondaFlags.BOSCH) HONDA_BOSCH_RADARLESS = CAR.with_flags(HondaFlags.BOSCH_RADARLESS) HONDA_BOSCH_CANFD = CAR.with_flags(HondaFlags.BOSCH_CANFD) HONDA_BOSCH_ALT_RADAR = CAR.with_flags(HondaFlags.BOSCH_ALT_RADAR) +HONDA_BOSCH_TJA_CONTROL = CAR.with_flags(HondaFlags.BOSCH_TJA_CONTROL) DBC = CAR.create_dbc_map() @@ -373,6 +383,7 @@ STEER_THRESHOLD = { CAR.HONDA_CRV_EU: 400, CAR.HONDA_ACCORD_11G: 600, CAR.HONDA_PILOT_4G: 600, + CAR.HONDA_PASSPORT_4G: 600, CAR.ACURA_MDX_4G_MMR: 600, CAR.HONDA_CRV_6G: 600, CAR.HONDA_CITY_7G: 600, diff --git a/opendbc/car/hyundai/fingerprints.py b/opendbc/car/hyundai/fingerprints.py index f83e513b..e6010049 100644 --- a/opendbc/car/hyundai/fingerprints.py +++ b/opendbc/car/hyundai/fingerprints.py @@ -56,6 +56,7 @@ FW_VERSIONS = { (Ecu.eps, 0x7d4, None): [ b'\xf1\x00AE MDPS C 1.00 1.03 56310/G2300 4AEHC103', b'\xf1\x00AE MDPS C 1.00 1.03 56310G2300\x00 4AEHC103', + b'\xf1\x00AE MDPS C 1.00 1.04 56310G2550\x00 4AEHC104', b'\xf1\x00AE MDPS C 1.00 1.05 56310/G2500 4AEHC105', b'\xf1\x00AE MDPS C 1.00 1.05 56310/G2501 4AEHC105', b'\xf1\x00AE MDPS C 1.00 1.07 56310/G2301 4AEHC107', @@ -65,6 +66,7 @@ FW_VERSIONS = { (Ecu.fwdCamera, 0x7c4, None): [ b'\xf1\x00AEH MFC AT EUR LHD 1.00 1.00 95740-G2400 180222', b'\xf1\x00AEH MFC AT EUR LHD 1.00 1.00 95740-G7200 160418', + b'\xf1\x00AEH MFC AT EUR RHD 1.00 1.00 95740-G2200 161014', b'\xf1\x00AEH MFC AT EUR RHD 1.00 1.00 95740-G2400 180222', b'\xf1\x00AEH MFC AT USA LHD 1.00 1.00 95740-G2300 170703', b'\xf1\x00AEH MFC AT USA LHD 1.00 1.00 95740-G2400 180222', @@ -922,6 +924,7 @@ FW_VERSIONS = { 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', + b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.09 99210-AA000 221108', ], (Ecu.abs, 0x7d1, None): [ b'\xf1\x00CN ESC \t 101 \x10\x03 58910-AB800', @@ -1125,6 +1128,7 @@ FW_VERSIONS = { b'\xf1\x00JK1 MFC AT CAN LHD 1.00 1.04 99211-AR100 210204', 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.02 99211-IY000 230627', b'\xf1\x00JK1 MFC AT USA LHD 1.00 1.04 99211-AR000 210204', ], (Ecu.fwdRadar, 0x7d0, None): [ diff --git a/opendbc/car/hyundai/values.py b/opendbc/car/hyundai/values.py index a36116a5..feb73e72 100644 --- a/opendbc/car/hyundai/values.py +++ b/opendbc/car/hyundai/values.py @@ -1,11 +1,11 @@ import re from dataclasses import dataclass, field -from enum import Enum, IntFlag +from enum import IntFlag from opendbc.car import Bus, CarSpecs, DbcDict, PlatformConfig, Platforms, uds from opendbc.car.common.conversions import Conversions as CV from opendbc.car.structs import CarParams -from opendbc.car.docs_definitions import CarFootnote, CarHarness, CarDocs, CarParts, Column, Device +from opendbc.car.docs_definitions import CarHarness, CarDocs, CarParts from opendbc.car.fw_query_definitions import FwQueryConfig, Request, p16 from opendbc.sunnypilot.car.hyundai.values import HyundaiFlagsSP @@ -129,21 +129,10 @@ class HyundaiFlags(IntFlag): ALT_LIMITS_2 = 2 ** 26 -class Footnote(Enum): - CANFD = CarFootnote( - "Requires a CAN FD panda kit if not using " + - "comma 3X for this CAN FD car.", - Column.MODEL) - - @dataclass class HyundaiCarDocs(CarDocs): package: str = "Smart Cruise Control (SCC)" - def init_make(self, CP: CarParams): - if CP.flags & HyundaiFlags.CANFD: - self.footnotes.insert(0, Footnote.CANFD) - @dataclass class HyundaiPlatformConfig(PlatformConfig): @@ -331,7 +320,7 @@ class CAR(Platforms): HYUNDAI_PALISADE = HyundaiPlatformConfig( [ HyundaiCarDocs("Hyundai Palisade 2020-22", "All", video="https://youtu.be/TAnDqjF4fDY?t=456", car_parts=CarParts.common([CarHarness.hyundai_h])), - HyundaiCarDocs("Kia Telluride 2020-22", "All", car_parts=CarParts([Device.threex_angled_mount, 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, diff --git a/opendbc/car/interfaces.py b/opendbc/car/interfaces.py index da40647c..1f23f225 100644 --- a/opendbc/car/interfaces.py +++ b/opendbc/car/interfaces.py @@ -246,7 +246,6 @@ class CarInterfaceBase(ABC, CarInterfaceBaseSP): ret.stoppingDecelRate = 0.8 # brake_travel/s while trying to stop ret.vEgoStopping = 0.5 ret.vEgoStarting = 0.5 - ret.longitudinalTuning.kf = 1. ret.longitudinalTuning.kpBP = [0.] ret.longitudinalTuning.kpV = [0.] ret.longitudinalTuning.kiBP = [0.] @@ -261,9 +260,6 @@ class CarInterfaceBase(ABC, CarInterfaceBaseSP): params = get_torque_params()[candidate] tune.init('torque') - tune.torque.kf = 1.0 - tune.torque.kp = 1.0 - tune.torque.ki = 0.3 tune.torque.friction = params['FRICTION'] tune.torque.latAccelFactor = params['LAT_ACCEL_FACTOR'] tune.torque.latAccelOffset = 0.0 diff --git a/opendbc/car/nissan/fingerprints.py b/opendbc/car/nissan/fingerprints.py index 4db2fe7c..f60903de 100644 --- a/opendbc/car/nissan/fingerprints.py +++ b/opendbc/car/nissan/fingerprints.py @@ -11,12 +11,15 @@ FW_VERSIONS = { ], (Ecu.eps, 0x742, None): [ b'6CA2B\xa9A\x02\x02G8A89P90D6A\x00\x00\x01\x80', + b'6CA2C\xa9A\x02\x02G8A89P90D6A\x00\x00\x01\x80', ], (Ecu.engine, 0x7e0, None): [ + b'237106GU3B', b'237109HE2B', ], (Ecu.gateway, 0x18dad0f1, None): [ b'284U29HE0A', + b'284U29HF0A', ], }, CAR.NISSAN_LEAF: { @@ -56,6 +59,7 @@ FW_VERSIONS = { b'5SK0ADB\x04\x18\x00\x00\x00\x00\x00_(5\x07\x9aQ\x00\x00\x00\x80', ], (Ecu.abs, 0x740, None): [ + b'476605SD2D', b'476605SD2E', b'476605SH1D', b'476605SH7D', @@ -66,13 +70,17 @@ FW_VERSIONS = { b'5SH2A\x99A\x05\x02N123F\x15\x81\x00\x00\x00\x00\x00\x00\x00\x80', b'5SH2A\xb7A\x05\x02N123F\x15\xa3\x00\x00\x00\x00\x00\x00\x00\x80', b'5SH2C\xb7A\x05\x02N123F\x15\xa3\x00\x00\x00\x00\x00\x00\x00\x80', + b'5SH3A\x99A\x05\x02N123F\x15\x81\x00\x00\x00\x00\x00\x00\x00\x80', + b'5SH3C\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'284U25SH3B', b'284U25SK2D', b'284U25SR0B', + b'284U25SR0C', ], }, CAR.NISSAN_XTRAIL: { diff --git a/opendbc/car/nissan/values.py b/opendbc/car/nissan/values.py index ee00cf42..bcb74f8f 100644 --- a/opendbc/car/nissan/values.py +++ b/opendbc/car/nissan/values.py @@ -72,7 +72,7 @@ class CAR(Platforms): NissanCarSpecs(mass=1610, wheelbase=2.705) ) NISSAN_ALTIMA = NissanPlatformConfig( - [NissanCarDocs("Nissan Altima 2019-20", car_parts=CarParts.common([CarHarness.nissan_b]))], + [NissanCarDocs("Nissan Altima 2019-20, 2024", car_parts=CarParts.common([CarHarness.nissan_b]))], NissanCarSpecs(mass=1492, wheelbase=2.824) ) diff --git a/opendbc/car/rivian/values.py b/opendbc/car/rivian/values.py index ae2d6e61..7ddfb70a 100644 --- a/opendbc/car/rivian/values.py +++ b/opendbc/car/rivian/values.py @@ -2,7 +2,7 @@ from dataclasses import dataclass, field from enum import StrEnum, IntFlag from opendbc.car import Bus, CarSpecs, DbcDict, PlatformConfig, Platforms, structs, uds -from opendbc.car.docs_definitions import CarHarness, CarDocs, CarParts, Device +from opendbc.car.docs_definitions import CarHarness, CarDocs, CarParts from opendbc.car.fw_query_definitions import FwQueryConfig, Request, StdQueries, p16 from opendbc.car.vin import Vin @@ -27,7 +27,7 @@ class ModelYear(StrEnum): @dataclass class RivianCarDocs(CarDocs): package: str = "All" - car_parts: CarParts = field(default_factory=CarParts([Device.threex_angled_mount, CarHarness.rivian])) + car_parts: CarParts = field(default_factory=CarParts.common([CarHarness.rivian])) setup_video: str = "https://youtu.be/uaISd1j7Z4U" diff --git a/opendbc/car/subaru/fingerprints.py b/opendbc/car/subaru/fingerprints.py index 5c4eb656..64158446 100644 --- a/opendbc/car/subaru/fingerprints.py +++ b/opendbc/car/subaru/fingerprints.py @@ -473,6 +473,7 @@ FW_VERSIONS = { b'\xa1 \x06\x02', b'\xa1 \x06\x03', b'\xa1 \x07\x00', + b'\xa1 \x07\x01', b'\xa1 \x07\x02', b'\xa1 \x07\x03', b'\xa1 \x08\x00', @@ -504,6 +505,7 @@ FW_VERSIONS = { b'\xe2"`0\x07', b'\xe2"`p\x07', b'\xe2"`q\x07', + b'\xe2"`t\x07', b'\xe2,\xa0p\x07', b'\xe3,\xa0@\x07', ], diff --git a/opendbc/car/tesla/fingerprints.py b/opendbc/car/tesla/fingerprints.py index f4e1a933..54705385 100644 --- a/opendbc/car/tesla/fingerprints.py +++ b/opendbc/car/tesla/fingerprints.py @@ -41,6 +41,7 @@ FW_VERSIONS = { CAR.TESLA_MODEL_X: { (Ecu.eps, 0x730, None): [ b'TeM3_SP_XP002p2_0.0.0 (23),XPR003.6.0', + b'TeM3_SP_XP002p2_0.0.0 (36),XPR003.10.0', ], }, } diff --git a/opendbc/car/tests/routes.py b/opendbc/car/tests/routes.py index 9d84f2ae..66389910 100644 --- a/opendbc/car/tests/routes.py +++ b/opendbc/car/tests/routes.py @@ -26,7 +26,11 @@ non_tested_cars = [ HYUNDAI.GENESIS_G90, VOLKSWAGEN.VOLKSWAGEN_CRAFTER_MK2, # need a route from an ACC-equipped Crafter SUBARU.SUBARU_FORESTER_HYBRID, - HONDA.HONDA_CRV_6G, + # Honda/Acura test routes below expired, replace when CI bucket sync is fixed + HONDA.ACURA_TLX_2G, + HONDA.HONDA_NBOX_2G, + HONDA.ACURA_MDX_4G_MMR, + HONDA.HONDA_CITY_7G, # port extensions HYUNDAI.KIA_CEED_PHEV_2022_NON_SCC, @@ -112,7 +116,6 @@ routes = [ CarTestRoute("320098ff6c5e4730/2023-04-13--17-47-46", HONDA.HONDA_HRV_3G), CarTestRoute("147613502316e718/00000001--dd141a3140", HONDA.HONDA_HRV_3G), # Brazilian model CarTestRoute("1e4baee1aa2687a0/00000001--74c4cc0b23", HONDA.HONDA_HRV_3G), # Thailand model use ALT_GEAR - CarTestRoute("414af83891dbf72c/00000006--51fa6d99cd", HONDA.HONDA_NBOX_2G), CarTestRoute("917b074700869333/2021-05-24--20-40-20", HONDA.ACURA_ILX), CarTestRoute("08a3deb07573f157/2020-03-06--16-11-19", HONDA.HONDA_ACCORD), # 1.5T CarTestRoute("1da5847ac2488106/2021-05-24--19-31-50", HONDA.HONDA_ACCORD), # 2.0T @@ -135,8 +138,9 @@ routes = [ CarTestRoute("b1c832ad56b6bc9d/00000010--debfcf5867", HONDA.HONDA_CIVIC_2022), # 2025 Civic Hatch Hybrid with new eCVT transmission CarTestRoute("f9c43864cf057d05/2024-01-15--23-01-20", HONDA.HONDA_PILOT_4G), # TODO: Replace with a newer route CarTestRoute("f39cf149898833ff/0000002b--54f3fae045", HONDA.HONDA_ACCORD_11G), - CarTestRoute("ad9840558640c31d/0000001a--d6cd4871c2", HONDA.ACURA_MDX_4G_MMR), # 2025 MDX - CarTestRoute("56b2cf1dacdcd033/00000017--d24ffdb376", HONDA.HONDA_CITY_7G), # Brazilian model + # CarTestRoute("56b2cf1dacdcd033/00000017--d24ffdb376", HONDA.HONDA_CITY_7G), # Brazilian model + CarTestRoute("2dc4489d7e1410ca/00000001--bbec3f5117", HONDA.HONDA_CRV_6G), + CarTestRoute("a703d058f4e05aeb/00000008--f169423024", HONDA.HONDA_PASSPORT_4G), CarTestRoute("87d7f06ade479c2e/2023-09-11--23-30-11", HYUNDAI.HYUNDAI_AZERA_6TH_GEN), CarTestRoute("66189dd8ec7b50e6/2023-09-20--07-02-12", HYUNDAI.HYUNDAI_AZERA_HEV_6TH_GEN), @@ -243,6 +247,7 @@ routes = [ CarTestRoute("7e34a988419b5307/2019-12-18--19-13-30", TOYOTA.TOYOTA_RAV4_TSS2), # hybrid CarTestRoute("2475fb3eb2ffcc2e/2022-04-29--12-46-23", TOYOTA.TOYOTA_RAV4_TSS2_2022), # hybrid CarTestRoute("20ba9ade056a8c7b/2021-02-08--21-57-35", TOYOTA.TOYOTA_RAV4_PRIME), # SecOC + CarTestRoute("41ba5b181f29435d/00000001--e3ae76382f", TOYOTA.TOYOTA_RAV4_PRIME), # SecOC longitudinal CarTestRoute("8bfb000e03b2a257/00000004--f9eee5f52e", TOYOTA.TOYOTA_SIENNA_4TH_GEN), # SecOC CarTestRoute("0b54d0594d924cd9/00000057--b6206a3205", TOYOTA.TOYOTA_YARIS), # SecOC CarTestRoute("7a31f030957b9c85/2023-04-01--14-12-51", TOYOTA.LEXUS_ES), @@ -308,6 +313,7 @@ routes = [ CarTestRoute("66e5edc3a16459c5/2021-05-25--19-00-29", VOLKSWAGEN.SKODA_OCTAVIA_MK3), CarTestRoute("026b6d18fba6417f/2021-03-26--09-17-04", VOLKSWAGEN.SKODA_KAMIQ_MK1), # Scala CarTestRoute("b2e9858e29db492b/2021-03-26--16-58-42", VOLKSWAGEN.SKODA_SUPERB_MK3), + CarTestRoute("e8dac44d3a3458a5/0000008d--c3e9496f1c", VOLKSWAGEN.PORSCHE_MACAN_MK1), # placeholder, replace after merge CarTestRoute("3c8f0c502e119c1c/2020-06-30--12-58-02", SUBARU.SUBARU_ASCENT), CarTestRoute("c321c6b697c5a5ff/2020-06-23--11-04-33", SUBARU.SUBARU_FORESTER), diff --git a/opendbc/car/tests/test_car_interfaces.py b/opendbc/car/tests/test_car_interfaces.py index 47c7835a..7cfe812c 100644 --- a/opendbc/car/tests/test_car_interfaces.py +++ b/opendbc/car/tests/test_car_interfaces.py @@ -94,7 +94,7 @@ class TestCarInterfaces: assert len(tune.pid.kiV) > 0 and len(tune.pid.kiV) == len(tune.pid.kiBP) elif tune.which() == 'torque': - assert not math.isnan(tune.torque.kf) and tune.torque.kf > 0 + assert not math.isnan(tune.torque.latAccelFactor) and tune.torque.latAccelFactor > 0 assert not math.isnan(tune.torque.friction) and tune.torque.friction > 0 # Run car interface diff --git a/opendbc/car/tests/test_docs.py b/opendbc/car/tests/test_docs.py index 8a4ae09b..8f0d862c 100644 --- a/opendbc/car/tests/test_docs.py +++ b/opendbc/car/tests/test_docs.py @@ -76,4 +76,4 @@ class TestCarDocs: assert len(car_parts) > 0, f"Need to specify car parts: {car.name}" assert car_part_type.count(PartType.connector) == 1, f"Need to specify one harness connector: {car.name}" assert car_part_type.count(PartType.mount) == 1, f"Need to specify one mount: {car.name}" - assert Cable.right_angle_obd_c_cable_1_5ft in car_parts, f"Need to specify a right angle OBD-C cable (1.5ft): {car.name}" + assert Cable.obd_c_cable_2ft in car_parts, f"Need to specify an OBD-C cable (2ft): {car.name}" diff --git a/opendbc/car/torque_data/override.toml b/opendbc/car/torque_data/override.toml index cbb11e14..be30fb8e 100644 --- a/opendbc/car/torque_data/override.toml +++ b/opendbc/car/torque_data/override.toml @@ -84,11 +84,14 @@ legend = ["LAT_ACCEL_FACTOR", "MAX_LAT_ACCEL_MEASURED", "FRICTION"] "HYUNDAI_NEXO_1ST_GEN" = [2.5, 2.5, 0.1] "HONDA_ACCORD_11G" = [1.35, 1.35, 0.17] "HONDA_PILOT_4G" = [1.25, 1.25, 0.21] +"HONDA_PASSPORT_4G" = [1.2, 1.2, 0.16] "ACURA_MDX_4G_MMR" = [1.25, 1.25, 0.15] "HONDA_CRV_6G" = [1.3, 1.3, 0.2] "HONDA_CITY_7G" = [1.2, 1.2, 0.23] "HONDA_ODYSSEY_5G_MMR" = [0.9, 0.9, 0.2] "HONDA_NBOX_2G" = [1.2, 1.2, 0.2] +"ACURA_TLX_2G" = [1.2, 1.2, 0.15] +"PORSCHE_MACAN_MK1" = [2.0, 2.0, 0.2] # Dashcam or fallback configured as ideal car "MOCK" = [10.0, 10, 0.0] diff --git a/opendbc/car/toyota/carcontroller.py b/opendbc/car/toyota/carcontroller.py index 3e1a80d0..09c88d15 100644 --- a/opendbc/car/toyota/carcontroller.py +++ b/opendbc/car/toyota/carcontroller.py @@ -4,7 +4,7 @@ from opendbc.car import Bus, make_tester_present_msg, rate_limit, structs, ACCEL from opendbc.car.lateral import apply_meas_steer_torque_limits, apply_std_steer_angle_limits, common_fault_avoidance from opendbc.car.can_definitions import CanData from opendbc.car.carlog import carlog -from opendbc.car.common.filter_simple import FirstOrderFilter +from opendbc.car.common.filter_simple import FirstOrderFilter, HighPassFilter from opendbc.car.common.pid import PIDController from opendbc.car.secoc import add_mac, build_sync_mac from opendbc.car.interfaces import CarControllerBase @@ -70,8 +70,8 @@ class CarController(CarControllerBase, SecOCLongCarController, GasInterceptorCar # *** start long control state *** self.long_pid = get_long_tune(self.CP, self.params) self.aego = FirstOrderFilter(0.0, 0.25, DT_CTRL * 3) - self.pitch = FirstOrderFilter(0, 0.25, DT_CTRL) - self.pitch_slow = FirstOrderFilter(0, 1.5, DT_CTRL) + self.pitch = FirstOrderFilter(0, 0.5, DT_CTRL) + self.pitch_hp = HighPassFilter(0.0, 0.25, 1.5, DT_CTRL) self.accel = 0 self.prev_accel = 0 @@ -81,6 +81,7 @@ class CarController(CarControllerBase, SecOCLongCarController, GasInterceptorCar self.secoc_lka_message_counter = 0 self.secoc_lta_message_counter = 0 + self.secoc_acc_message_counter = 0 self.secoc_prev_reset_counter = 0 def update(self, CC, CC_SP, CS, now_nanos): @@ -92,7 +93,7 @@ class CarController(CarControllerBase, SecOCLongCarController, GasInterceptorCar if len(CC.orientationNED) == 3: self.pitch.update(CC.orientationNED[1]) - self.pitch_slow.update(CC.orientationNED[1]) + self.pitch_hp.update(CC.orientationNED[1]) # *** control msgs *** can_sends = [] @@ -104,6 +105,7 @@ class CarController(CarControllerBase, SecOCLongCarController, GasInterceptorCar if CS.secoc_synchronization['RESET_CNT'] != self.secoc_prev_reset_counter: self.secoc_lka_message_counter = 0 self.secoc_lta_message_counter = 0 + self.secoc_acc_message_counter = 0 self.secoc_prev_reset_counter = CS.secoc_synchronization['RESET_CNT'] expected_mac = build_sync_mac(self.secoc_key, int(CS.secoc_synchronization['TRIP_CNT']), int(CS.secoc_synchronization['RESET_CNT'])) @@ -235,8 +237,7 @@ class CarController(CarControllerBase, SecOCLongCarController, GasInterceptorCar if not stopping: # Toyota's PCM slowly responds to changes in pitch. On change, we amplify our # acceleration request to compensate for the undershoot and following overshoot - high_pass_pitch = self.pitch.x - self.pitch_slow.x - pitch_compensation = float(np.clip(math.sin(high_pass_pitch) * ACCELERATION_DUE_TO_GRAVITY, + pitch_compensation = float(np.clip(math.sin(self.pitch_hp.x) * ACCELERATION_DUE_TO_GRAVITY, -MAX_PITCH_COMPENSATION, MAX_PITCH_COMPENSATION)) pcm_accel_cmd += pitch_compensation @@ -258,8 +259,19 @@ class CarController(CarControllerBase, SecOCLongCarController, GasInterceptorCar pcm_accel_cmd = pcm_accel_cmd if self.CP.carFingerprint in TSS2_CAR else actuators.accel pcm_accel_cmd = float(np.clip(pcm_accel_cmd, self.params.ACCEL_MIN, self.params.ACCEL_MAX)) - can_sends.append(toyotacan.create_accel_command(self.packer, pcm_accel_cmd, pcm_cancel_cmd, self.permit_braking, self.standstill_req, lead, - CS.acc_type, fcw_alert, self.distance_button, self.SECOC_LONG)) + main_accel_cmd = 0. if self.CP.flags & ToyotaFlags.SECOC.value else pcm_accel_cmd + can_sends.append(toyotacan.create_accel_command(self.packer, main_accel_cmd, pcm_cancel_cmd, self.permit_braking, self.standstill_req, lead, + CS.acc_type, fcw_alert, self.distance_button)) + if self.CP.flags & ToyotaFlags.SECOC.value: + acc_cmd_2 = toyotacan.create_accel_command_2(self.packer, pcm_accel_cmd) + acc_cmd_2 = add_mac(self.secoc_key, + int(CS.secoc_synchronization['TRIP_CNT']), + int(CS.secoc_synchronization['RESET_CNT']), + self.secoc_acc_message_counter, + acc_cmd_2) + self.secoc_acc_message_counter += 1 + can_sends.append(acc_cmd_2) + self.accel = pcm_accel_cmd else: diff --git a/opendbc/car/toyota/carstate.py b/opendbc/car/toyota/carstate.py index 8e22ce2f..607906d6 100644 --- a/opendbc/car/toyota/carstate.py +++ b/opendbc/car/toyota/carstate.py @@ -6,7 +6,8 @@ from opendbc.car.common.conversions import Conversions as CV from opendbc.car.common.filter_simple import FirstOrderFilter from opendbc.car.interfaces import CarStateBase from opendbc.car.toyota.values import ToyotaFlags, CAR, DBC, STEER_THRESHOLD, NO_STOP_TIMER_CAR, \ - TSS2_CAR, RADAR_ACC_CAR, EPS_SCALE, UNSUPPORTED_DSU_CAR + TSS2_CAR, RADAR_ACC_CAR, EPS_SCALE, UNSUPPORTED_DSU_CAR, \ + SECOC_CAR from opendbc.sunnypilot.car.toyota.carstate_ext import CarStateExt from opendbc.sunnypilot.car.toyota.values import ToyotaFlagsSP @@ -195,7 +196,7 @@ class CarState(CarStateBase, CarStateExt): buttonEvents.extend(create_button_events(1, 0, {1: ButtonType.lkas}) + create_button_events(0, 1, {1: ButtonType.lkas})) - if self.CP.carFingerprint not in RADAR_ACC_CAR: + if self.CP.carFingerprint not in (RADAR_ACC_CAR | SECOC_CAR): # distance button is wired to the ACC module (camera or radar) self.distance_button = cp_acc.vl["ACC_CONTROL"]["DISTANCE"] diff --git a/opendbc/car/toyota/toyotacan.py b/opendbc/car/toyota/toyotacan.py index 88e3e7ca..00ece2b5 100644 --- a/opendbc/car/toyota/toyotacan.py +++ b/opendbc/car/toyota/toyotacan.py @@ -60,6 +60,13 @@ def create_accel_command(packer, accel, pcm_cancel, permit_braking, standstill_r return packer.make_can_msg("ACC_CONTROL", 0, values) +def create_accel_command_2(packer, accel): + values = { + "ACCEL_CMD": accel, + } + return packer.make_can_msg("ACC_CONTROL_2", 0, values) + + def create_pcs_commands(packer, accel, active, mass): values1 = { "COUNTER": 0, diff --git a/opendbc/car/volkswagen/carcontroller.py b/opendbc/car/volkswagen/carcontroller.py index 8ebffcbc..60358791 100644 --- a/opendbc/car/volkswagen/carcontroller.py +++ b/opendbc/car/volkswagen/carcontroller.py @@ -4,7 +4,7 @@ from opendbc.car import Bus, DT_CTRL, structs from opendbc.car.lateral import apply_driver_steer_torque_limits from opendbc.car.common.conversions import Conversions as CV from opendbc.car.interfaces import CarControllerBase -from opendbc.car.volkswagen import mqbcan, pqcan +from opendbc.car.volkswagen import mlbcan, mqbcan, pqcan from opendbc.car.volkswagen.values import CanBus, CarControllerParams, VolkswagenFlags VisualAlert = structs.CarControl.HUDControl.VisualAlert @@ -16,10 +16,16 @@ class CarController(CarControllerBase): super().__init__(dbc_names, CP, CP_SP) self.CCP = CarControllerParams(CP) self.CAN = CanBus(CP) - self.CCS = pqcan if CP.flags & VolkswagenFlags.PQ else mqbcan self.packer_pt = CANPacker(dbc_names[Bus.pt]) self.aeb_available = not CP.flags & VolkswagenFlags.PQ + if CP.flags & VolkswagenFlags.PQ: + self.CCS = pqcan + elif CP.flags & VolkswagenFlags.MLB: + self.CCS = mlbcan + else: + self.CCS = mqbcan + self.apply_torque_last = 0 self.gra_acc_counter_last = None self.eps_timer_soft_disable_alert = False diff --git a/opendbc/car/volkswagen/carstate.py b/opendbc/car/volkswagen/carstate.py index 9ca183dc..97caefa9 100644 --- a/opendbc/car/volkswagen/carstate.py +++ b/opendbc/car/volkswagen/carstate.py @@ -18,6 +18,7 @@ class CarState(CarStateBase): self.esp_hold_confirmation = False self.upscale_lead_car_signal = False self.eps_stock_values = False + self.acc_type = 0 def update_button_enable(self, buttonEvents: list[structs.CarState.ButtonEvent]): if not self.CP.pcmCruise: @@ -48,6 +49,8 @@ class CarState(CarStateBase): if self.CP.flags & VolkswagenFlags.PQ: return self.update_pq(pt_cp, cam_cp, ext_cp) + elif self.CP.flags & VolkswagenFlags.MLB: + return self.update_mlb(pt_cp, cam_cp, ext_cp) ret = structs.CarState() ret_sp = structs.CarStateSP() @@ -74,11 +77,9 @@ class CarState(CarStateBase): pt_cp.vl["ESP_19"]["ESP_HR_Radgeschw_02"], ) - hca_status = self.CCP.hca_status_values.get(pt_cp.vl["LH_EPS_03"]["EPS_HCA_Status"]) 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 # EA - drive_mode = True 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"]) @@ -115,11 +116,7 @@ class CarState(CarStateBase): # Shared logic ret.vEgoCluster = pt_cp.vl["Kombi_01"]["KBI_angez_Geschw"] * CV.KPH_TO_MS - 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.steerFaultTemporary, ret.steerFaultPermanent = self.update_hca_state(hca_status, drive_mode) + self.parse_mlb_mqb_steering_state(ret, pt_cp) ret.gasPressed = pt_cp.vl["Motor_20"]["MO_Fahrpedalrohwert_01"] > 0 ret.espActive = bool(pt_cp.vl["ESP_21"]["ESP_Eingriff"]) @@ -161,14 +158,14 @@ class CarState(CarStateBase): ret.steerFaultTemporary, ret.steerFaultPermanent = self.update_hca_state(hca_status) # Update gas, brakes, and gearshift. - ret.gasPressed = pt_cp.vl["Motor_3"]["Fahrpedal_Rohsignal"] > 0 + ret.gasPressed = pt_cp.vl["Motor_3"]["MO3_Pedalwert"] > 0 ret.brake = pt_cp.vl["Bremse_5"]["BR5_Bremsdruck"] / 250.0 # FIXME: this is pressure in Bar, not sure what OP expects ret.brakePressed = bool(pt_cp.vl["Motor_2"]["MO2_BLS"]) ret.parkingBrake = bool(pt_cp.vl["Kombi_1"]["Bremsinfo"]) # Update gear and/or clutch position data. if self.CP.transmissionType == TransmissionType.automatic: - ret.gearShifter = self.parse_gear_shifter(self.CCP.shifter_values.get(pt_cp.vl["Getriebe_1"]["Waehlhebelposition__Getriebe_1_"], None)) + ret.gearShifter = self.parse_gear_shifter(self.CCP.shifter_values.get(pt_cp.vl["Getriebe_1"]["GE1_Wahl_Pos"], None)) elif self.CP.transmissionType == TransmissionType.manual: reverse_light = bool(pt_cp.vl["Gate_Komf_1"]["GK1_Rueckfahr"]) if reverse_light: @@ -208,7 +205,7 @@ class CarState(CarStateBase): # 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.available = bool(pt_cp.vl["Motor_5"]["MO5_GRA_Hauptsch"]) ret.cruiseState.enabled = pt_cp.vl["Motor_2"]["MO2_Sta_GRA"] in (1, 2) if self.CP.pcmCruise: ret.accFaulted = ext_cp.vl["ACC_GRA_Anzeige"]["ACA_StaACC"] in (6, 7) @@ -235,6 +232,62 @@ class CarState(CarStateBase): self.frame += 1 return ret, ret_sp + def update_mlb(self, pt_cp, cam_cp, ext_cp) -> structs.CarState: + ret = structs.CarState() + ret_sp = structs.CarStateSP() + + self.parse_wheel_speeds(ret, + pt_cp.vl["ESP_03"]["ESP_VL_Radgeschw"], + pt_cp.vl["ESP_03"]["ESP_VR_Radgeschw"], + pt_cp.vl["ESP_03"]["ESP_HL_Radgeschw"], + pt_cp.vl["ESP_03"]["ESP_HR_Radgeschw"], + ) + + ret.gasPressed = pt_cp.vl["Motor_03"]["MO_Fahrpedalrohwert_01"] > 0 + ret.gearShifter = self.parse_gear_shifter(self.CCP.shifter_values.get(pt_cp.vl["Getriebe_03"]["GE_Waehlhebel"], None)) + + # 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) + # TODO: get this from the drivetrain side instead, for openpilot long support later + ret.cruiseState.available = ext_cp.vl["ACC_05"]["ACC_Status_ACC"] in (2, 3, 4, 5) + ret.cruiseState.enabled = ext_cp.vl["ACC_05"]["ACC_Status_ACC"] in (3, 4, 5) + ret.accFaulted = ext_cp.vl["ACC_05"]["ACC_Status_ACC"] in (6, 7) + + self.parse_mlb_mqb_steering_state(ret, pt_cp) + + ret.brake = pt_cp.vl["ESP_05"]["ESP_Bremsdruck"] / 250.0 + brake_pedal_pressed = bool(pt_cp.vl["Motor_03"]["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"]) + ret.espDisabled = pt_cp.vl["ESP_01"]["ESP_Tastung_passiv"] != 0 + + ret.leftBlinker, ret.rightBlinker = self.update_blinker_from_stalk(300, pt_cp.vl["Gateway_11"]["BH_Blinker_li"], + pt_cp.vl["Gateway_11"]["BH_Blinker_re"]) + + ret.seatbeltUnlatched = pt_cp.vl["Gateway_06"]["AB_Gurtschloss_FA"] != 3 + ret.doorOpen = any([pt_cp.vl["Gateway_05"]["FT_Tuer_geoeffnet"], + pt_cp.vl["Gateway_05"]["BT_Tuer_geoeffnet"], + pt_cp.vl["Gateway_05"]["HL_Tuer_geoeffnet"], + pt_cp.vl["Gateway_05"]["HR_Tuer_geoeffnet"]]) + + # 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"]) + + self.ldw_stock_values = cam_cp.vl["LDW_02"] if self.CP.networkLocation == NetworkLocation.fwdCamera else {} + self.gra_stock_values = pt_cp.vl["LS_01"] + + ret.buttonEvents = self.create_button_events(pt_cp, self.CCP.BUTTONS) + + ret.cruiseState.standstill = self.CP.pcmCruise and self.esp_hold_confirmation + ret.standstill = ret.vEgoRaw == 0 + + self.frame += 1 + return ret, ret_sp + def update_low_speed_alert(self, v_ego: float) -> bool: # Low speed steer alert hysteresis logic if (self.CP.minSteerSpeed - 1e-3) > CarControllerParams.DEFAULT_MIN_STEER_SPEED and v_ego < (self.CP.minSteerSpeed + 1.): @@ -243,6 +296,16 @@ class CarState(CarStateBase): self.low_speed_alert = False return self.low_speed_alert + def parse_mlb_mqb_steering_state(self, ret, pt_cp, drive_mode=True): + 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 + + 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, drive_mode) + return + def update_hca_state(self, hca_status, drive_mode=True): # Treat 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 @@ -256,18 +319,20 @@ class CarState(CarStateBase): if CP.flags & VolkswagenFlags.PQ: return CarState.get_can_parsers_pq(CP) - # another case of the 1-50Hz - cam_messages = [] + # manually configure some optional and variable-rate/edge-triggered messages + pt_messages, cam_messages = [], [] + + if not CP.flags & VolkswagenFlags.MLB: + pt_messages += [ + ("Blinkmodi_02", 1) # From J519 BCM (sent at 1Hz when no lights active, 50Hz when active) + ] if CP.flags & VolkswagenFlags.STOCK_HCA_PRESENT: cam_messages += [ ("HCA_01", 1), # From R242 Driver assistance camera, 50Hz if steering/1Hz if not ] return { - Bus.pt: CANParser(DBC[CP.carFingerprint][Bus.pt], [ - # the 50->1Hz is currently too much for the CANParser to figure out - ("Blinkmodi_02", 1), # From J519 BCM (sent at 1Hz when no lights active, 50Hz when active) - ], CanBus(CP).pt), + Bus.pt: CANParser(DBC[CP.carFingerprint][Bus.pt], pt_messages, CanBus(CP).pt), Bus.cam: CANParser(DBC[CP.carFingerprint][Bus.pt], cam_messages, CanBus(CP).cam), } diff --git a/opendbc/car/volkswagen/fingerprints.py b/opendbc/car/volkswagen/fingerprints.py index f29b6ff5..f0e13e56 100644 --- a/opendbc/car/volkswagen/fingerprints.py +++ b/opendbc/car/volkswagen/fingerprints.py @@ -837,6 +837,7 @@ FW_VERSIONS = { b'\xf1\x878V0906259H \xf1\x890002', b'\xf1\x878V0906259J \xf1\x890002', b'\xf1\x878V0906259K \xf1\x890001', + b'\xf1\x878V0906259K \xf1\x890002', b'\xf1\x878V0906264B \xf1\x890003', b'\xf1\x878V0907115B \xf1\x890007', b'\xf1\x878V0907404A \xf1\x890005', @@ -852,6 +853,7 @@ FW_VERSIONS = { b'\xf1\x870D9300012L \xf1\x894521', b'\xf1\x870D9300013B \xf1\x894902', b'\xf1\x870D9300013B \xf1\x894931', + b'\xf1\x870D9300014Q \xf1\x895006', b'\xf1\x870D9300041N \xf1\x894512', b'\xf1\x870D9300043T \xf1\x899699', b'\xf1\x870DD300046 \xf1\x891604', @@ -966,6 +968,35 @@ FW_VERSIONS = { b'\xf1\x872Q0907572T \xf1\x890383', ], }, + CAR.PORSCHE_MACAN_MK1: { + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8795B906259BJ\xf1\x890001', + b'\xf1\x8795B90652013\xf1\x893485', + b'\xf1\x8795B90654002\xf1\x893495', + b'\xf1\x8795B907551D \xf1\x890006', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x8795B927156CE\xf1\x890022', + b'\xf1\x8795B927156JH\xf1\x890001', + b'\xf1\x8795B927156KK\xf1\x890001', + b'\xf1\x8795B927156R \xf1\x890021', + ], + (Ecu.srs, 0x715, None): [ + b'\xf1\x8795B959655F \xf1\x890130\xf1\x82\x05065Q033513', + b'\xf1\x8795B959655F \xf1\x890130\xf1\x82\x050682033514', + b'\xf1\x8795B959655G \xf1\x890150\xf1\x82\x0506B1033514', + b'\xf1\x8795B959655G \xf1\x890150\xf1\x82\x0506CJ02D417', + ], + (Ecu.eps, 0x712, None): [ + b'\xf1\x8795B909144K \xf1\x891902\xf1\x82\x02\x04#\x04#', + b'\xf1\x8795B909144K \xf1\x891902\xf1\x82\x02\x04/\x04/', + ], + (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x8795B907567B\x00\xf1\x890800\xf1\x82108', + b'\xf1\x8795B907567G\x00\xf1\x890410\xf1\x82104', + b'\xf1\x8795B907567J \xf1\x890440\xf1\x82104', + ], + }, CAR.SEAT_ATECA_MK1: { (Ecu.engine, 0x7e0, None): [ b'\xf1\x8704E906027KA\xf1\x893749', diff --git a/opendbc/car/volkswagen/interface.py b/opendbc/car/volkswagen/interface.py index 4c40f874..eaa60f4e 100644 --- a/opendbc/car/volkswagen/interface.py +++ b/opendbc/car/volkswagen/interface.py @@ -37,6 +37,13 @@ class CarInterface(CarInterfaceBase): # Panda ALLOW_DEBUG firmware required. ret.dashcamOnly = True + elif ret.flags & VolkswagenFlags.MLB: + # Set global MLB parameters + safety_configs = [get_safety_config(structs.CarParams.SafetyModel.volkswagenMlb)] + ret.enableBsm = 0x30F in fingerprint[0] # SWA_01 + ret.networkLocation = NetworkLocation.gateway + ret.dashcamOnly = True # Pending HCA timeout fix, safety validation, harness termination, install procedure + else: # Set global MQB parameters safety_configs = [get_safety_config(structs.CarParams.SafetyModel.volkswagen)] @@ -62,7 +69,7 @@ class CarInterface(CarInterfaceBase): # Global lateral tuning defaults, can be overridden per-vehicle ret.steerLimitTimer = 0.4 - if ret.flags & VolkswagenFlags.PQ: + if ret.flags & VolkswagenFlags.PQ or ret.flags & VolkswagenFlags.MLB: ret.steerActuatorDelay = 0.2 CarInterfaceBase.configure_torque_tune(candidate, ret.lateralTuning) else: @@ -83,6 +90,11 @@ class CarInterface(CarInterfaceBase): if ret.transmissionType == TransmissionType.manual: ret.minEnableSpeed = 4.5 + # Per-vehicle overrides + + if candidate == CAR.PORSCHE_MACAN_MK1: + ret.steerActuatorDelay = 0.07 + ret.pcmCruise = not ret.openpilotLongitudinalControl ret.stopAccel = -0.55 ret.vEgoStarting = 0.1 diff --git a/opendbc/car/volkswagen/mlbcan.py b/opendbc/car/volkswagen/mlbcan.py new file mode 100644 index 00000000..dc3b717e --- /dev/null +++ b/opendbc/car/volkswagen/mlbcan.py @@ -0,0 +1,71 @@ +from opendbc.car.volkswagen.mqbcan import (volkswagen_mqb_meb_checksum, xor_checksum, + create_lka_hud_control as mqb_create_lka_hud_control) + +# TODO: Parameterize the hca control type (5 vs 7) and consolidate with MQB (and PQ?) +def create_steering_control(packer, bus, apply_steer, lkas_enabled): + values = { + "HCA_01_Status_HCA": 7 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_lka_hud_control(packer, bus, ldw_stock_values, enabled, steering_pressed, hud_alert, hud_control): + return mqb_create_lka_hud_control(packer, bus, ldw_stock_values, enabled, steering_pressed, hud_alert, hud_control) + + +def create_acc_buttons_control(packer, bus, gra_stock_values, cancel=False, resume=False): + values = {s: gra_stock_values[s] for s in [ + "LS_Hauptschalter", + "LS_Typ_Hauptschalter", + "LS_Codierung", + "LS_Tip_Stufe_2", + ]} + + values.update({ + "COUNTER": (gra_stock_values["COUNTER"] + 1) % 16, + "LS_Abbrechen": cancel, + "LS_Tip_Wiederaufnahme": resume, + }) + + return packer.make_can_msg("LS_01", bus, values) + + +def acc_control_value(main_switch_on, acc_faulted, long_active): + return 0 + + +def acc_hud_status_value(main_switch_on, acc_faulted, long_active): + return 0 + + +def create_acc_accel_control(packer, bus, acc_type, acc_enabled, accel, acc_control, stopping, starting, esp_hold): + values = {} + return packer.make_can_msg("ACC_05", bus, values) + + +def create_acc_hud_control(packer, bus, acc_hud_status, set_speed, lead_distance, distance): + values = {} + return packer.make_can_msg("ACC_02", bus, values) + +def volkswagen_mlb_checksum(address: int, sig, d: bytearray) -> int: + xor_starting_value = { + 0x109: 0x08, # ACC_01 + 0x111: 0x10, # TSK_05 + 0x30C: 0x0F, # ACC_02 + 0x324: 0x27, # ACC_04 + 0x10B: 0xA, # LS_01 + 0x10D: 0x0C, # ACC_05 + 0x10F: 0x0E, # ACC_0x10F + 0x311: 0x12, # ACC_0x311 + 0x397: 0x94, # LDW_02 + 0x10C: 0x0D, # TSK_02 + } + if address in xor_starting_value: + return xor_checksum(address, sig, d, xor_starting_value[address]) + else: + return volkswagen_mqb_meb_checksum(address, sig, d) diff --git a/opendbc/car/volkswagen/mqbcan.py b/opendbc/car/volkswagen/mqbcan.py index 02580e99..78a2eeff 100644 --- a/opendbc/car/volkswagen/mqbcan.py +++ b/opendbc/car/volkswagen/mqbcan.py @@ -185,8 +185,8 @@ def volkswagen_mqb_meb_checksum(address: int, sig, d: bytearray) -> int: return crc ^ 0xFF -def xor_checksum(address: int, sig, d: bytearray) -> int: - checksum = 0 +def xor_checksum(address: int, sig, d: bytearray, initial_value: int = 0) -> int: + checksum = initial_value checksum_byte = sig.start_bit // 8 for i in range(len(d)): if i != checksum_byte: diff --git a/opendbc/car/volkswagen/values.py b/opendbc/car/volkswagen/values.py index 573596fb..513affdc 100644 --- a/opendbc/car/volkswagen/values.py +++ b/opendbc/car/volkswagen/values.py @@ -5,8 +5,7 @@ from enum import Enum, IntFlag, StrEnum from opendbc.car import Bus, CanBusBase, CarSpecs, DbcDict, PlatformConfig, Platforms, structs, uds from opendbc.can import CANDefine from opendbc.car.common.conversions import Conversions as CV -from opendbc.car.docs_definitions import CarFootnote, CarHarness, CarDocs, CarParts, Column, \ - Device +from opendbc.car.docs_definitions import CarFootnote, CarHarness, CarDocs, CarParts, Column from opendbc.car.fw_query_definitions import EcuAddrSubAddr, FwQueryConfig, Request, p16 from opendbc.car.vin import Vin @@ -81,7 +80,7 @@ class CarControllerParams: 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.shifter_values = can_define.dv["Getriebe_1"]["GE1_Wahl_Pos"] self.hca_status_values = can_define.dv["Lenkhilfe_2"]["LH2_Sta_HCA"] self.BUTTONS = [ @@ -90,7 +89,7 @@ class CarControllerParams: Button(structs.CarState.ButtonEvent.Type.accelCruise, "GRA_Neu", "GRA_Up_kurz", [1]), Button(structs.CarState.ButtonEvent.Type.decelCruise, "GRA_Neu", "GRA_Down_kurz", [1]), Button(structs.CarState.ButtonEvent.Type.cancel, "GRA_Neu", "GRA_Abbrechen", [1]), - Button(structs.CarState.ButtonEvent.Type.gapAdjustCruise, "GRA_Neu", "GRA_Zeitluecke", [1]), + Button(structs.CarState.ButtonEvent.Type.gapAdjustCruise, "GRA_Neu", "GRA_Zeitluecke", [3]), ] self.LDW_MESSAGES = { @@ -105,24 +104,43 @@ class CarControllerParams: 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["Gateway_73"]["GE_Fahrstufe"] - elif CP.transmissionType == TransmissionType.direct: - self.shifter_values = can_define.dv["Motor_EV_01"]["MO_Waehlpos"] self.hca_status_values = can_define.dv["LH_EPS_03"]["EPS_HCA_Status"] - self.BUTTONS = [ - Button(structs.CarState.ButtonEvent.Type.setCruise, "GRA_ACC_01", "GRA_Tip_Setzen", [1]), - Button(structs.CarState.ButtonEvent.Type.resumeCruise, "GRA_ACC_01", "GRA_Tip_Wiederaufnahme", [1]), - Button(structs.CarState.ButtonEvent.Type.accelCruise, "GRA_ACC_01", "GRA_Tip_Hoch", [1]), - Button(structs.CarState.ButtonEvent.Type.decelCruise, "GRA_ACC_01", "GRA_Tip_Runter", [1]), - Button(structs.CarState.ButtonEvent.Type.cancel, "GRA_ACC_01", "GRA_Abbrechen", [1]), - Button(structs.CarState.ButtonEvent.Type.gapAdjustCruise, "GRA_ACC_01", "GRA_Verstellung_Zeitluecke", [1]), - ] + if CP.flags & VolkswagenFlags.MLB: + self.STEER_DRIVER_ALLOWANCE = 60 # Driver intervention threshold 0.6 Nm + self.STEER_DELTA_UP = 9 # Max HCA reached in 0.66s (STEER_MAX / (50Hz * 0.66)) + self.STEER_DELTA_DOWN = 10 # Min HCA reached in 0.60s (STEER_MAX / (50Hz * 0.60)) + + self.shifter_values = can_define.dv["Getriebe_03"]["GE_Waehlhebel"] + + self.BUTTONS = [ + Button(structs.CarState.ButtonEvent.Type.setCruise, "LS_01", "LS_Tip_Setzen", [1]), + Button(structs.CarState.ButtonEvent.Type.resumeCruise, "LS_01", "LS_Tip_Wiederaufnahme", [1]), + Button(structs.CarState.ButtonEvent.Type.accelCruise, "LS_01", "LS_Tip_Hoch", [1]), + Button(structs.CarState.ButtonEvent.Type.decelCruise, "LS_01", "LS_Tip_Runter", [1]), + Button(structs.CarState.ButtonEvent.Type.cancel, "LS_01", "LS_Abbrechen", [1]), + Button(structs.CarState.ButtonEvent.Type.gapAdjustCruise, "LS_01", "LS_Verstellung_Zeitluecke", [1]), + ] + + else: + 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["Gateway_73"]["GE_Fahrstufe"] + elif CP.transmissionType == TransmissionType.direct: + self.shifter_values = can_define.dv["Motor_EV_01"]["MO_Waehlpos"] + + self.BUTTONS = [ + Button(structs.CarState.ButtonEvent.Type.setCruise, "GRA_ACC_01", "GRA_Tip_Setzen", [1]), + Button(structs.CarState.ButtonEvent.Type.resumeCruise, "GRA_ACC_01", "GRA_Tip_Wiederaufnahme", [1]), + Button(structs.CarState.ButtonEvent.Type.accelCruise, "GRA_ACC_01", "GRA_Tip_Hoch", [1]), + Button(structs.CarState.ButtonEvent.Type.decelCruise, "GRA_ACC_01", "GRA_Tip_Runter", [1]), + Button(structs.CarState.ButtonEvent.Type.cancel, "GRA_ACC_01", "GRA_Abbrechen", [1]), + Button(structs.CarState.ButtonEvent.Type.gapAdjustCruise, "GRA_ACC_01", "GRA_Verstellung_Zeitluecke", [1]), + ] self.LDW_MESSAGES = { "none": 0, # Nothing to display @@ -150,6 +168,7 @@ class WMI(StrEnum): AUDI_EUROPE_MPV = "WA1" AUDI_GERMANY_CAR = "WAU" MAN = "WMA" + PORSCHE_SUV = "WP1" AUDI_SPORT = "WUA" VOLKSWAGEN_COMMERCIAL = "WV1" VOLKSWAGEN_COMMERCIAL_BUS_VAN = "WV2" @@ -169,6 +188,17 @@ class VolkswagenFlags(IntFlag): # Static flags PQ = 2 + MLB = 8 + + +@dataclass +class VolkswagenMLBPlatformConfig(PlatformConfig): + dbc_dict: DbcDict = field(default_factory=lambda: {Bus.pt: 'vw_mlb'}) + chassis_codes: set[str] = field(default_factory=set) + wmis: set[WMI] = field(default_factory=set) + + def init(self): + self.flags |= VolkswagenFlags.MLB @dataclass @@ -204,7 +234,7 @@ class Footnote(Enum): 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.", + "to block GPS signal needed for some comma four functionality.", Column.MODEL) VW_EXP_LONG = CarFootnote( "Only available for vehicles using a gateway (J533) harness. At this time, vehicles using a camera harness " + @@ -226,9 +256,6 @@ class VWCarDocs(CarDocs): 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.vw_j533]) - if abs(CP.minSteerSpeed - CarControllerParams.DEFAULT_MIN_STEER_SPEED) < 1e-3: self.min_steer_speed = 0 @@ -414,6 +441,12 @@ class CAR(Platforms): chassis_codes={"8U", "F3", "FS"}, wmis={WMI.AUDI_EUROPE_MPV, WMI.AUDI_GERMANY_CAR}, ) + PORSCHE_MACAN_MK1 = VolkswagenMLBPlatformConfig( + [VWCarDocs("Porsche Macan 2017-24")], + VolkswagenCarSpecs(mass=1895, wheelbase=2.81, steerRatio=16.2), + chassis_codes={"95", "A5"}, + wmis={WMI.PORSCHE_SUV}, + ) SEAT_ATECA_MK1 = VolkswagenMQBPlatformConfig( [ VWCarDocs("CUPRA Ateca 2018-23"), diff --git a/opendbc/dbc/SConscript b/opendbc/dbc/SConscript index 9a929120..481e024b 100644 --- a/opendbc/dbc/SConscript +++ b/opendbc/dbc/SConscript @@ -1,7 +1,8 @@ -Import("env") - +import os from pathlib import Path +env = Environment(ENV=os.environ) + generator = File("generator/generator.py") source_files = [ diff --git a/opendbc/dbc/generator/honda/_bosch_2018.dbc b/opendbc/dbc/generator/honda/_bosch_2018.dbc index dace015b..d5171fde 100644 --- a/opendbc/dbc/generator/honda/_bosch_2018.dbc +++ b/opendbc/dbc/generator/honda/_bosch_2018.dbc @@ -1,9 +1,3 @@ -BO_ 148 KINEMATICS: 8 XXX - SG_ LAT_ACCEL : 7|10@0+ (-0.035,17.92) [-20|20] "m/s2" EON - SG_ LONG_ACCEL : 25|10@0+ (-0.035,17.92) [-20|20] "m/s2" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - BO_ 228 STEERING_CONTROL: 5 EON SG_ STEER_TORQUE : 7|16@0- (1,0) [-4096|4096] "" EPS SG_ DRIVER_OVERRIDE : 17|1@0+ (1,0) [0|1] "" XXX diff --git a/opendbc/dbc/generator/honda/_honda_common.dbc b/opendbc/dbc/generator/honda/_honda_common.dbc index 001b24d7..24d3ed56 100644 --- a/opendbc/dbc/generator/honda/_honda_common.dbc +++ b/opendbc/dbc/generator/honda/_honda_common.dbc @@ -1,3 +1,14 @@ +BO_ 145 KINEMATICS_ALT: 8 XXX + SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 148 KINEMATICS: 8 XXX + SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON + SG_ LONG_ACCEL : 24|9@0- (-0.02,0) [-20|20] "m/s2" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + BO_ 304 GAS_PEDAL_2: 8 PCM SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON diff --git a/opendbc/dbc/generator/honda/_nidec_common.dbc b/opendbc/dbc/generator/honda/_nidec_common.dbc index 0af1cd35..d22c28a5 100644 --- a/opendbc/dbc/generator/honda/_nidec_common.dbc +++ b/opendbc/dbc/generator/honda/_nidec_common.dbc @@ -1,14 +1,3 @@ -BO_ 145 KINEMATICS: 8 XXX - SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - -BO_ 148 KINEMATICS_ALT: 8 XXX - SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON - SG_ LONG_ACCEL : 24|9@0- (-0.02,0) [-20|20] "m/s2" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - BO_ 432 STANDSTILL: 7 VSA SG_ CONTROLLED_STANDSTILL : 0|1@0+ (1,0) [0|1] "" EON SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON @@ -71,8 +60,8 @@ BO_ 927 RADAR_HUD: 8 ADAS SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" BDY CM_ SG_ 506 AEB_REQ_1 "set for duration of suspected AEB event"; -CM_ SG_ 506 COMPUTER_BRAKE_ALT "Used by dual-can Nidec"; -CM_ SG_ 506 BRAKE_PUMP_REQUEST_ALT "Used by dual-can Nidec"; +CM_ SG_ 506 COMPUTER_BRAKE_HYBRID "Used by Hybrid Nidec"; +CM_ SG_ 506 BRAKE_PUMP_REQUEST_HYBRID "Used by Hybrid Nidec"; VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw"; VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime"; diff --git a/opendbc/dbc/vw_mlb.dbc b/opendbc/dbc/vw_mlb.dbc new file mode 100644 index 00000000..aea4cb40 --- /dev/null +++ b/opendbc/dbc/vw_mlb.dbc @@ -0,0 +1,2749 @@ +VERSION "HNNBNNNYNNNNNNNNNNNNNNNNNNNNNNNNNNNNNNNNNN/4/%%%/4/'%**4NNN///" + + +NS_ : + NS_DESC_ + CM_ + BA_DEF_ + BA_ + VAL_ + CAT_DEF_ + CAT_ + FILTER + BA_DEF_DEF_ + EV_DATA_ + ENVVAR_DATA_ + SGTYPE_ + SGTYPE_VAL_ + BA_DEF_SGTYPE_ + BA_SGTYPE_ + SIG_TYPE_REF_ + VAL_TABLE_ + SIG_GROUP_ + SIG_VALTYPE_ + SIGTYPE_VALTYPE_ + BO_TX_BU_ + BA_DEF_REL_ + BA_REL_ + BA_DEF_DEF_REL_ + BU_SG_REL_ + BU_EV_REL_ + BU_BO_REL_ + +BS_: + +BU_: Airbag_D4 EPB_D4 ESP_D4 Gateway_D4C7 Getriebe_AL551_951_D4_C7 Getriebe_DL501_C7 Getriebe_VL381_C7 LWS_D4 Motor_EDC17_D4 Motor_ME17_BY Motor_MED17_SIMOS8_D4 Motor_Slave_D4 QSP_D4 SAK_C7 SCR_C7 SCU_D4 + + +BO_ 780 ACC_02: 8 Gateway_D4C7 + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" HUD_C7,Kombi_D4 + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" HUD_C7,Kombi_D4 + SG_ ACC_Wunschgeschw_02 : 12|10@1+ (0.32,0) [0.00|326.72] "Unit_KiloMeterPerHour" HUD_C7,Kombi_D4 + SG_ ACC_Status_Prim_Anz : 22|2@1+ (1.0,0.0) [0.0|3] "" HUD_C7,Kombi_D4 + SG_ ACC_Abstandsindex : 24|10@1+ (1,0) [1|1021] "" HUD_C7,Kombi_D4 + SG_ ACC_Akustik : 34|3@1+ (1.0,0.0) [0.0|7] "" Kombi_D4 + SG_ ACC_Gesetzte_Zeitluecke : 37|3@1+ (1.0,0.0) [0.0|7] "" Kombi_D4 + SG_ ACC_Optischer_Fahrerhinweis : 40|1@1+ (1.0,0.0) [0.0|1] "" Kombi_D4 + SG_ ACC_Typ_Tachokranz : 41|1@1+ (1.0,0.0) [0.0|1] "" Kombi_D4 + SG_ ACC_Anzeige_Zeitluecke : 42|1@1+ (1.0,0.0) [0.0|1] "" Kombi_D4 + SG_ ACC_Tachokranz : 43|1@1+ (1.0,0.0) [0.0|1] "" Kombi_D4 + SG_ ACC_Display_Prio : 44|2@1+ (1.0,0.0) [0.0|3] "" Vector__XXX + SG_ ACC_Relevantes_Objekt : 46|2@1+ (1.0,0.0) [0.0|3] "" HUD_C7,Kombi_D4 + SG_ ACC_Texte_Primaeranz : 48|7@1+ (1.0,0.0) [0.0|127] "" HUD_C7,Kombi_D4 + SG_ ACC_Wunschgeschw_erreicht : 55|1@1+ (1.0,0.0) [0.0|1] "" Kombi_D4 + SG_ ACC_Status_Anzeige : 61|3@1+ (1.0,0.0) [0.0|7] "" APS_D4,Kombi_D4 + +BO_ 804 ACC_04: 8 Gateway_D4C7 + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" HUD_C7,Kombi_D4 + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" HUD_C7,Kombi_D4 + SG_ ACC_Texte_Zusatzanz : 16|6@1+ (1.0,0.0) [0.0|63] "" Kombi_D4 + SG_ ACC_Status_Zusatzanz : 22|5@1+ (1.0,0.0) [0.0|31] "" HUD_C7,Kombi_D4 + SG_ ACC_Texte : 27|5@1+ (1.0,0.0) [0.0|31] "" Kombi_D4 + SG_ ACC_Texte_braking_guard : 32|3@1+ (1.0,0.0) [0.0|7] "" HUD_C7,Kombi_D4 + SG_ ACC_Warnhinweis : 35|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ ACC_Geschw_Zielfahrzeug : 40|10@1+ (0.32,0) [0.00|326.72] "Unit_KiloMeterPerHour" Vector__XXX + SG_ ACC_Charisma_FahrPr : 56|3@1+ (1.0,0.0) [0.0|7] "" Vector__XXX + SG_ ACC_Charisma_Status : 59|2@1+ (1.0,0.0) [0.0|3] "" Vector__XXX + SG_ ACC_Charisma_Umschaltung : 61|2@1+ (1.0,0.0) [0.0|3] "" Vector__XXX + +BO_ 269 ACC_05: 8 Gateway_D4C7 + SG_ ACC_05_CHK : 0|8@1+ (1,0) [0|255] "" EPB_D4,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" EPB_D4,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ ACC_Freigabe_Momentenanf : 12|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ ACC_Freigabe_Verzanf : 13|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ ACC_Getriebestellung_P : 14|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ ACC_limitierte_Anfahrdyn : 15|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ ACC_Momentenanforderung : 16|10@1+ (1,0) [0|1021] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ ACC_zul_Regelabw : 26|6@1+ (0.024,0) [0.000|1.512] "Unit_MeterPerSeconSquar" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ ACC_Verz_anf : 32|11@1+ (0.005,-7.22) [-7.220|3.015] "Unit_MeterPerSeconSquar" Vector__XXX + SG_ ACC_Loeseanforderung : 43|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ ACC_StartStopp_Info : 44|2@1+ (1.0,0.0) [0.0|3] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ ACC_Vorbefuellung_Bremsanlage : 47|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ ACC_ax_Getriebe : 48|9@1+ (0.024,-2.016) [-2.016|10.248] "Unit_MeterPerSeconSquar" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ ACC_Status_ACC : 57|3@1+ (1.0,0.0) [0.0|7] "" EPB_D4,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ ACC_Betaetigung_EPB : 60|1@1+ (1.0,0.0) [0.0|1] "" EPB_D4,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ ACC_Beeinflussung_ESP : 61|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ ACC_Anhalten : 62|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ ACC_KD_Fehler : 63|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + +BO_ 279 ACC_10: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX + SG_ AWV1_Anf_Prefill : 16|1@1+ (1,0) [0|1] "" XXX + SG_ ANB_CM_Info : 17|1@1+ (1,0) [0|1] "" XXX + SG_ AWV2_Freigabe : 18|1@1+ (1,0) [0|1] "" XXX + SG_ AWV1_HBA_Param : 19|2@1+ (1,0) [0|3] "" XXX + SG_ AWV2_Ruckprofil : 21|3@1+ (1,0) [0|7] "" XXX + SG_ AWV2_Priowarnung : 24|1@1+ (1,0) [0|1] "" XXX + SG_ ANB_CM_Anforderung : 25|1@1+ (1,0) [0|1] "" XXX + SG_ ANB_Info_Teilbremsung : 26|1@1+ (1,0) [0|1] "" XXX + SG_ ANB_Notfallblinken : 27|1@1+ (1,0) [0|1] "" XXX + SG_ ANB_Teilbremsung_Freigabe : 28|1@1+ (1,0) [0|1] "" XXX + SG_ ANB_Zielbrems_Teilbrems_Verz_Anf : 29|10@1+ (0.024,-20.016) [-20.016|4.536] "Unit_MeterPerSeconSquar" XXX + SG_ ANB_Zielbremsung_Freigabe : 39|1@1+ (1,0) [0|1] "" XXX + SG_ AWV_Vorstufe : 40|1@1+ (1,0) [0|1] "" XXX + SG_ AWV_Halten : 41|1@1+ (1,0) [0|1] "" XXX + SG_ AWV_CityANB_Auspraegung : 42|1@1+ (1,0) [0|1] "" XXX + SG_ PCF_Freigabe : 43|1@1+ (1,0) [0|1] "" XXX + SG_ AWV1_ECD_Anlauf : 44|1@1+ (1,0) [0|1] "" XXX + SG_ AWV_AWA_VZ_Anf_Lenkmomoffset : 46|1@1+ (1.0,0.0) [0.0|1] "" XXX + SG_ AWV_AWA_Anf_Lenkmomoffset : 47|9@1+ (0.01,0) [0.00|5.11] "Unit_NewtoMeter" XXX + SG_ PCF_Time_to_collision : 56|8@1+ (0.01,0) [0|2.5] "Unit_Secon" XXX + +BO_ 64 Airbag_01: 8 Airbag_D4 + SG_ Airbag_01_CHK : 0|8@1+ (1,0) [0|255] "" Gateway_D4C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ Airbag_01_BZ : 8|4@1+ (1,0) [0|15] "" Gateway_D4C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ AB_RGS_Anst : 12|4@1+ (1.0,0.0) [0.0|15] "" Gateway_D4C7 + SG_ AB_Front_Crash : 16|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ AB_Heck_Crash : 17|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ AB_SF_Crash : 18|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ AB_SB_Crash : 19|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ AB_Rollover_Crash : 20|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ AB_Crash_Int : 21|3@1+ (1.0,0.0) [0.0|7] "" Gateway_D4C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ AB_Lampe : 24|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ AB_Deaktiviert : 25|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ AB_VB_deaktiviert : 26|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ AB_Systemfehler : 27|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ AB_Diagnose : 28|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ AB_Stellgliedtest : 29|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ AB_Erh_Auf_VB : 30|2@1+ (1.0,0.0) [0.0|3] "" Gateway_D4C7 + SG_ AB_Gurtwarn_VF : 32|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ AB_Gurtwarn_VB : 33|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ AB_Anzeige_Fussg : 34|2@1+ (1.0,0.0) [0.0|3] "" Gateway_D4C7 + SG_ AB_Texte_AKS : 36|2@1+ (1.0,0.0) [0.0|3] "" Gateway_D4C7 + SG_ AB_PAO_Leuchte_Anf : 38|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ AB_MKB_gueltig : 39|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ AB_MKB_Anforderung : 40|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ AB_Versorgungsspannung : 41|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ AB_KD_Fehler : 63|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + +BO_ 1312 Airbag_02: 8 Airbag_D4 + SG_ AB_Belegung_VB : 26|2@1+ (1.0,0.0) [0.0|3] "" Gateway_D4C7 + SG_ AB_Gurtschloss_FA : 40|2@1+ (1.0,0.0) [0.0|3] "" EPB_D4,Gateway_D4C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ AB_Gurtschloss_BF : 42|2@1+ (1.0,0.0) [0.0|3] "" Gateway_D4C7 + SG_ AB_Gurtschloss_Reihe2_FA : 44|2@1+ (1.0,0.0) [0.0|3] "" Gateway_D4C7 + SG_ AB_Gurtschloss_Reihe2_MI : 46|2@1+ (1.0,0.0) [0.0|3] "" Gateway_D4C7 + SG_ AB_Gurtschloss_Reihe2_BF : 48|2@1+ (1.0,0.0) [0.0|3] "" Gateway_D4C7 + SG_ AB_Gurtschloss_Reihe3_FA : 50|2@1+ (1.0,0.0) [0.0|3] "" Gateway_D4C7 + SG_ AB_Gurtschloss_Reihe3_MI : 52|2@1+ (1.0,0.0) [0.0|3] "" Gateway_D4C7 + SG_ AB_Gurtschloss_Reihe3_BF : 54|2@1+ (1.0,0.0) [0.0|3] "" Gateway_D4C7 + SG_ AB_Sitzpos_Sens_FA : 56|2@1+ (1.0,0.0) [0.0|3] "" Gateway_D4C7 + SG_ AB_Sitzpos_Sens_BF : 58|2@1+ (1.0,0.0) [0.0|3] "" Gateway_D4C7 + +BO_ 1633 Anhaenger_01: 3 Gateway_D4C7 + SG_ AAG_BZ : 0|4@1+ (1,0) [0|15] "" Getriebe_AL551_951_D4_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ AAG_Bremsl_durch_ECD : 5|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ AAG_Anhaenger_abgesteckt : 6|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ AAG_NSL_aktiv : 7|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ AAG_Anhaenger_erkannt : 8|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ AAG_Blinker_H_aktiv : 9|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ AAG_Blinker_HL_def : 10|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ AAG_Blinker_HR_def : 11|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ AAG_Bremslicht_H_def : 12|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ AAG_Schlusslicht_HL_def : 13|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ AAG_Schlusslicht_HR_def : 14|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ AAG_KD_Fehler : 15|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ AAG_AVS_Fehler : 18|2@1+ (1.0,0.0) [0.0|3] "" Vector__XXX + SG_ AAG_AVS_Stati : 20|4@1+ (1.0,0.0) [0.0|15] "" Vector__XXX + +BO_ 777 BEM_01: 4 Gateway_D4C7 + SG_ BEM_01_CHK : 0|8@1+ (1,0) [0|255] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ BEM_01_BZ : 8|4@1+ (1,0) [0|15] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ BEM_Segel_Info : 12|2@1+ (1.0,0.0) [0.0|3] "" Vector__XXX + SG_ BEM_P_Generator : 16|8@1+ (50,0) [0|12700] "Unit_Watt" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ BEM_n_LLA : 24|2@1+ (1.0,0.0) [0.0|3] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ BEM_01_Abschaltstufen : 26|3@1+ (1.0,0.0) [0.0|7] "" Vector__XXX + SG_ BEM_Anf_KL : 29|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ BEM_StartStopp_Info : 30|2@1+ (1.0,0.0) [0.0|3] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + +BO_ 867 Blinkmodi_01: 4 Gateway_D4C7 + SG_ BM_ZV_auf : 0|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ BM_ZV_zu : 1|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ BM_DWA_ein : 2|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ BM_DWA_Alarm : 3|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ BM_Crash : 4|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ BM_Panik : 5|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ BM_Not_Bremsung : 6|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ BM_GDO : 7|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ BM_links : 8|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ BM_rechts : 9|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ BM_Warnblinken : 10|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ BM_Autobahn : 11|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ BM_Taxi_Notalarm : 12|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ BM_Telematik : 13|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ BM_HD_Oeffnung_angelernt : 14|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ BM_WBT_Beleuchtung : 15|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ Blinken_li_Fzg_Takt : 16|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ Blinken_re_Fzg_Takt : 17|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ Blinken_li_Kombi_Takt : 18|1@1+ (1.0,0.0) [0.0|1] "" Kombi_D4 + SG_ Blinken_re_Kombi_Takt : 19|1@1+ (1.0,0.0) [0.0|1] "" Kombi_D4 + SG_ BM_NBA_n_codiert_n_aktiv : 20|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ BM_NBA_Status : 21|2@1+ (1.0,0.0) [0.0|3] "" Vector__XXX + SG_ Blinken_FWB_aktiv : 23|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + +BO_ 482 CCP_GE_CR0_01: 8 Gateway_D4C7 + SG_ CCP_GE_CRO_01_Data : 0|64@1+ (1,0) [0|1] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + +BO_ 490 CCP_GE_DTO_01: 8 Getriebe_AL551_951_D4_C7 + SG_ CCP_GE_DTO_01_Data : 0|64@1+ (1,0) [0|1] "" Gateway_D4C7 + +BO_ 480 CCP_MO_CRO_01: 8 Gateway_D4C7 + SG_ CCP_MO_CRO_01_Data : 0|64@1+ (1,0) [0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + +BO_ 2616986624 CCP_MO_CRO_02: 8 Vector__XXX + SG_ CCP_MO_CRO_02_Data : 0|64@1+ (1,0) [0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + +BO_ 488 CCP_MO_DTO_01: 8 Motor_EDC17_D4 + SG_ CCP_MO_DTO_01_Data : 0|64@1+ (1,0) [0|1] "" Gateway_D4C7 + +BO_ 2616986625 CCP_MO_DTO_02: 8 Motor_EDC17_D4 + SG_ CCP_MO_DTO_02_Data : 0|64@1+ (1,0) [0|1] "" Vector__XXX + +BO_ 481 CCP_MOS_CRO_01: 8 Gateway_D4C7 + SG_ CCP_MOS_CRO_01_Data : 0|64@1+ (1,0) [0|1] "" Motor_Slave_D4 + +BO_ 2616986629 CCP_MOS_CRO_02: 8 Vector__XXX + SG_ CCP_MOS_CRO_02_Data : 0|64@1+ (1,0) [0|1] "" Motor_Slave_D4 + +BO_ 489 CCP_MOS_DTO_01: 8 Motor_Slave_D4 + SG_ CCP_MOS_DTO_01_Data : 0|64@1+ (1,0) [0|1] "" Gateway_D4C7 + +BO_ 2616986630 CCP_MOS_DTO_02: 8 Motor_Slave_D4 + SG_ CCP_MOS_DTO_02_Data : 0|64@1+ (1,0) [0|1] "" Vector__XXX + +BO_ 2617042432 CCP_Soundaktor_CRO_01: 8 Vector__XXX + SG_ CCP_Soundaktor_CRO_01_Data : 0|64@1+ (1.0,0.0) [0.0|18446744073709551615] "" SAK_C7 + +BO_ 2617042433 CCP_Soundaktor_DTO_01: 8 SAK_C7 + SG_ CCP_Soundaktor_DTO_01_Data : 0|64@1+ (1.0,0.0) [0.0|18446744073709551615] "" Vector__XXX + +BO_ 901 Charisma_01: 8 Gateway_D4C7 + SG_ CHA_01_CHK : 0|8@1+ (1,0) [0|255] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4,SCU_D4 + SG_ CHA_01_BZ : 8|4@1+ (1,0) [0|15] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ CHA_Systemstatus : 12|2@1+ (1.0,0.0) [0.0|3] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4,SCU_D4 + SG_ CHA_Fahrer_Umschaltung : 14|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ CHA_Ziel_FahrPr_MO : 16|3@1+ (1.0,0.0) [0.0|7] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ CHA_Ziel_FahrPr_GE : 20|3@1+ (1.0,0.0) [0.0|7] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ CHA_Ziel_FahrPr_ST : 24|3@1+ (1.0,0.0) [0.0|7] "" Vector__XXX + SG_ CHA_Ziel_FahrPr_SCU : 28|3@1+ (1.0,0.0) [0.0|7] "" SCU_D4 + SG_ CHA_Ziel_FahrPr_DR : 32|3@1+ (1.0,0.0) [0.0|7] "" Vector__XXX + SG_ CHA_Ziel_FahrPr_QS : 36|3@1+ (1.0,0.0) [0.0|7] "" Vector__XXX + SG_ CHA_Ziel_FahrPr_AFS : 40|3@1+ (1.0,0.0) [0.0|7] "" Vector__XXX + SG_ CHA_Ziel_FahrPr_RGS : 44|3@1+ (1.0,0.0) [0.0|7] "" Vector__XXX + SG_ CHA_Ziel_FahrPr_EPS : 48|3@1+ (1.0,0.0) [0.0|7] "" Vector__XXX + SG_ CHA_Ziel_FahrPr_ACC : 52|3@1+ (1.0,0.0) [0.0|7] "" Vector__XXX + SG_ CHA_Ziel_FahrPr_SAK : 56|3@1+ (1.0,0.0) [0.0|7] "" Vector__XXX + +BO_ 2617027072 DEV_Airbag_01: 4 Airbag_D4 + SG_ DEV_Airbag_01 : 0|32@1+ (1.0,0.0) [0.0|4294967295] "" Vector__XXX + +BO_ 1714 Diagnose_01: 8 Gateway_D4C7 + SG_ DGN_Verlernzaehler : 0|8@1+ (1,0) [0|254] "" Airbag_D4,EPB_D4,Getriebe_AL551_951_D4_C7,SAK_C7,SCR_C7,SCU_D4 + SG_ KBI_Kilometerstand : 8|20@1+ (1,0) [0|1048573] "Unit_KiloMeter" Airbag_D4,EPB_D4,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4,SAK_C7,SCR_C7,SCU_D4 + SG_ UH_Jahr : 28|7@1+ (1,2000) [2000|2127] "Unit_Year" Airbag_D4,EPB_D4,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4,SAK_C7,SCR_C7,SCU_D4 + SG_ UH_Monat : 35|4@1+ (1,0) [1|12] "Unit_Month" Airbag_D4,EPB_D4,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4,SAK_C7,SCR_C7,SCU_D4 + SG_ UH_Tag : 39|5@1+ (1,0) [1|31] "Unit_Day" Airbag_D4,EPB_D4,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4,SAK_C7,SCR_C7,SCU_D4 + SG_ UH_Stunde : 44|5@1+ (1,0) [0|23] "Unit_Hours" Airbag_D4,EPB_D4,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4,SAK_C7,SCR_C7,SCU_D4 + SG_ UH_Minute : 49|6@1+ (1,0) [0|59] "Unit_Minut" Airbag_D4,EPB_D4,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4,SAK_C7,SCR_C7,SCU_D4 + SG_ UH_Sekunde : 55|6@1+ (1,0) [0|59] "Unit_Secon" Airbag_D4,EPB_D4,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4,SAK_C7,SCR_C7,SCU_D4 + SG_ Kombi_02_alt : 62|1@1+ (1.0,0.0) [0.0|1] "" Airbag_D4,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,SCR_C7,SCU_D4 + SG_ Uhrzeit_01_alt : 63|1@1+ (1.0,0.0) [0.0|1] "" Airbag_D4,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,SCR_C7,SCU_D4 + +BO_ 1520 Dimmung_01: 5 Gateway_D4C7 + SG_ DI_KL_58d : 0|8@1+ (1,0) [0|253] "" Airbag_D4,Getriebe_AL551_951_D4_C7 + SG_ DI_KL_58s : 8|7@1+ (1,0) [0|100] "Unit_PerCent" Getriebe_AL551_951_D4_C7 + SG_ DI_KL_58st : 16|7@1+ (1,0) [0|100] "Unit_PerCent" Getriebe_AL551_951_D4_C7 + SG_ DI_Lichtsensorwert : 24|16@1+ (1,0) [0|65535] "" Airbag_D4,Getriebe_AL551_951_D4_C7 + +BO_ 1603 Einheiten_01: 3 Gateway_D4C7 + SG_ KBI_Einheit_Datum : 0|2@1+ (1.0,0.0) [0.0|3] "" Vector__XXX + SG_ KBI_Einheit_Druck : 2|2@1+ (1.0,0.0) [0.0|3] "" Vector__XXX + SG_ KBI_Einheit_Streckenanz : 4|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4 + SG_ KBI_MFA_v_Einheit_02 : 5|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ KBI_Einheit_Temp : 6|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ KBI_Einheit_Uhrzeit : 7|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ KBI_Einheit_Verbrauch : 8|2@1+ (1.0,0.0) [0.0|3] "" Vector__XXX + SG_ KBI_Einheit_Volumen : 10|2@1+ (1.0,0.0) [0.0|3] "" Vector__XXX + SG_ KBI_Einheit_Sprache : 16|8@1+ (1,0) [0|255] "" Vector__XXX + +BO_ 260 EPB_01: 8 EPB_D4 + SG_ EPB_01_CHK : 0|8@1+ (1,0) [0|255] "" Gateway_D4C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ EPB_01_BZ : 8|4@1+ (1,0) [0|15] "" Gateway_D4C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ EPB_QBit_Laengsbeschleunigung : 12|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ EPB_QBit_Pedalweg_Kuppl : 13|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ EPB_BCM2_Motor_Wakeup : 14|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ EPB_Freig_Verzoeg_Anf : 15|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7,Getriebe_AL551_951_D4_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ EPB_Verzoeg_Anf : 16|8@1+ (0.048,-7.968) [-7.968|4.224] "Unit_MeterPerSeconSquar" Gateway_D4C7 + SG_ EPB_Laengsbeschleunigung : 24|8@1+ (1,-128) [-128|126] "Unit_PerCentOfForceOfGravi" Gateway_D4C7 + SG_ EPB_Pedalweg_Kuppl : 32|8@1+ (0.4,0) [8.0|92.0] "Unit_PerCent" Gateway_D4C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ EPB_Anfahrwunsch_erkannt : 48|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ EPB_DAA_Randbed_erf : 49|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ EPB_Fehlerstatus : 50|2@1+ (1.0,0.0) [0.0|3] "" Gateway_D4C7 + SG_ EPB_Schalterposition : 52|2@1+ (1.0,0.0) [0.0|3] "" Gateway_D4C7,Getriebe_AL551_951_D4_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ EPB_QBit_Schalterpos : 54|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7,Getriebe_AL551_951_D4_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ EPB_Konsistenz_ACC : 55|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ EPB_Spannkraft : 56|5@1+ (1,0) [0|29] "Unit_KiloNewto" Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ EPB_Status : 61|2@1+ (1.0,0.0) [0.0|3] "" Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ EPB_KD_Fehler : 63|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + +BO_ 781 EPB_02: 4 EPB_D4 + SG_ EPB_Fehlerlampe_Gelb : 0|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ EPB_Fehlerlampe_BKL : 1|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ EPB_Funktionslampe : 2|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ EPB_Texte : 3|4@1+ (1.0,0.0) [0.0|15] "" Gateway_D4C7 + SG_ EPB_Akustik : 7|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ EPB_Autoholdlampe : 8|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ EPB_Bremsbelag_Warn : 9|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + +BO_ 256 ESP_01: 8 Gateway_D4C7 + SG_ ESP_01_CHK : 0|8@1+ (1,0) [0|255] "" Airbag_D4,EPB_D4,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" Airbag_D4,EPB_D4,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ ASR_Moment_langsam : 12|10@1+ (1,0) [0|1021] "" Airbag_D4,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ ASR_MSR_Moment_schnell : 22|10@1+ (1,0) [0|1021] "" Airbag_D4,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ ESP_v_Signal : 32|16@1+ (0.01,0) [0.00|655.32] "Unit_KiloMeterPerHour" Airbag_D4,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4,SAK_C7,SCR_C7 + SG_ ASR_Tastung_passiv : 48|1@1+ (1.0,0.0) [0.0|1] "" Airbag_D4,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ ESP_Tastung_passiv : 49|1@1+ (1.0,0.0) [0.0|1] "" Airbag_D4,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ ESP_Systemstatus : 50|1@1+ (1.0,0.0) [0.0|1] "" Airbag_D4,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ ASR_Schalteingriff : 51|2@1+ (1.0,0.0) [0.0|3] "" Airbag_D4,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ OBD_Schlechtweg : 53|1@1+ (1.0,0.0) [0.0|1] "" Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ OBD_QBit_Schlechtweg : 54|1@1+ (1.0,0.0) [0.0|1] "" Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ ESP_QBit_v_Signal : 55|1@1+ (1.0,0.0) [0.0|1] "" Airbag_D4,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4,SCR_C7 + SG_ ABS_Bremsung : 56|1@1+ (1.0,0.0) [0.0|1] "" Airbag_D4,EPB_D4,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ ASR_Anf : 57|1@1+ (1.0,0.0) [0.0|1] "" Airbag_D4,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ MSR_Anf : 58|1@1+ (1.0,0.0) [0.0|1] "" Airbag_D4,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ EBV_Eingriff : 59|1@1+ (1.0,0.0) [0.0|1] "" Airbag_D4,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ EDS_Eingriff : 60|1@1+ (1.0,0.0) [0.0|1] "" Airbag_D4,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ ESP_Eingriff : 61|1@1+ (1.0,0.0) [0.0|1] "" Airbag_D4,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ ESP_ASP : 62|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ ESP_KD_Fehler : 63|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + +BO_ 257 ESP_02: 8 Gateway_D4C7 + SG_ ESP_02_CHK : 0|8@1+ (1,0) [0|255] "" Airbag_D4,EPB_D4,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" Airbag_D4,EPB_D4,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ ESP_QBit_Gierrate : 12|1@1+ (1.0,0.0) [0.0|1] "" Airbag_D4 + SG_ ESP_QBit_Laengsbeschl : 13|1@1+ (1.0,0.0) [0.0|1] "" Airbag_D4,EPB_D4,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ ESP_QBit_Querb : 14|1@1+ (1.0,0.0) [0.0|1] "" Airbag_D4,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ ESP_Stillstandsflag : 15|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ ESP_Querbeschleunigung : 16|8@1+ (0.01,-1.27) [-1.27|1.27] "Unit_ForceOfGravi" Airbag_D4,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ ESP_Laengsbeschl : 24|10@1+ (0.03125,-16) [-16.00000|15.90625] "Unit_MeterPerSeconSquar" Airbag_D4,EPB_D4,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ ESP_Verteil_Wankmom : 34|5@1+ (0.1,-1) [-1.0|1.0] "" Vector__XXX + SG_ ESP_QBit_Anf_Vert_Wank : 39|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ ESP_Gierrate : 40|14@1+ (0.01,0) [0.00|163.82] "Unit_DegreOfArcPerSecon" Airbag_D4 + SG_ ESP_VZ_Gierrate : 54|1@1+ (1.0,0.0) [0.0|1] "" Airbag_D4 + SG_ ESP_Notbremsanzeige : 55|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ ESP_SpannungsAnf : 56|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ ESP_PLA_Abbruch : 57|3@1+ (1.0,0.0) [0.0|7] "" Vector__XXX + SG_ ESP_Status_ESP_PLA : 60|4@1+ (1.0,0.0) [0.0|15] "" Vector__XXX + +BO_ 259 ESP_03: 8 Gateway_D4C7 + SG_ ESP_03_CHK : 0|8@1+ (1,0) [0|255] "" Airbag_D4,EPB_D4,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,LWS_D4,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4,SCU_D4 + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" Airbag_D4,EPB_D4,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,LWS_D4,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4,SCU_D4 + SG_ ESP_VL_FR : 12|1@1+ (1.0,0.0) [0.0|1] "" Airbag_D4,EPB_D4,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4,SCU_D4 + SG_ ESP_VR_FR : 13|1@1+ (1.0,0.0) [0.0|1] "" Airbag_D4,EPB_D4,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4,SCU_D4 + SG_ ESP_HL_FR : 14|1@1+ (1.0,0.0) [0.0|1] "" Airbag_D4,EPB_D4,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4,SCU_D4 + SG_ ESP_HR_FR : 15|1@1+ (1.0,0.0) [0.0|1] "" Airbag_D4,EPB_D4,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4,SCU_D4 + SG_ ESP_VL_Radgeschw : 16|12@1+ (0.1,0) [0.0|409.2] "Unit_KiloMeterPerHour" Airbag_D4,EPB_D4,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,LWS_D4,SCU_D4 + SG_ ESP_VR_Radgeschw : 28|12@1+ (0.1,0) [0.0|409.2] "Unit_KiloMeterPerHour" Airbag_D4,EPB_D4,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,LWS_D4,SCU_D4 + SG_ ESP_HL_Radgeschw : 40|12@1+ (0.1,0) [0.0|409.2] "Unit_KiloMeterPerHour" Airbag_D4,EPB_D4,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,LWS_D4,SCU_D4 + SG_ ESP_HR_Radgeschw : 52|12@1+ (0.1,0) [0.0|409.2] "Unit_KiloMeterPerHour" Airbag_D4,EPB_D4,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,LWS_D4,SCU_D4 + +BO_ 776 ESP_04: 8 Gateway_D4C7 + SG_ ESP_Meldungen : 0|3@1+ (1.0,0.0) [0.0|7] "" Vector__XXX + SG_ ESP_HDC_FktLampe : 3|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ ESP_Lampe : 4|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ ABS_Lampe : 5|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ BK_Lampe : 6|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ ESP_Akustik : 7|2@1+ (1.0,0.0) [0.0|3] "" Vector__XXX + SG_ ESP_Diagnose : 9|1@1+ (1.0,0.0) [0.0|1] "" SCU_D4 + SG_ ESP_Textanzeigen_02 : 10|5@1+ (1.0,0.0) [0.0|31] "" Vector__XXX + SG_ ESP_Off_Lampe : 15|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ ESP_m_Raddrehz : 16|15@1+ (0.002,0) [0.000|65.278] "Unit_Hertz" Vector__XXX + SG_ ESP_ASR_Lampe : 31|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ ESP_Wegimp_VA : 32|11@1+ (1,0) [0|2047] "" Vector__XXX + SG_ ESP_Fehlerstatus_Wegimp : 43|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ ESP_Wegimp_Ueberlauf : 44|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ ESP_QBit_Wegimp_VA : 45|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ ESP_Displaywarnungen : 46|2@1+ (1.0,0.0) [0.0|3] "" Vector__XXX + SG_ ESP_HDC_Regelgeschw : 48|7@1+ (0.32,0) [0.32|39.68] "Unit_KiloMeterPerHour" Vector__XXX + SG_ ESP_BKV_Warnung : 55|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ ESP_Zaehnezahl : 56|8@1+ (1,0) [0|255] "" Vector__XXX + +BO_ 262 ESP_05: 8 Gateway_D4C7 + SG_ ESP_05_CHK : 0|8@1+ (1,0) [0|255] "" EPB_D4,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4,SCU_D4 + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" EPB_D4,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4,SCU_D4 + SG_ ESP_QBit_Bremsdruck : 12|1@1+ (1.0,0.0) [0.0|1] "" EPB_D4,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ ESP_QBit_Fahrer_bremst : 13|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ ESP_Schwelle_Unterdruck : 14|2@1+ (1.0,0.0) [0.0|3] "" Vector__XXX + SG_ ESP_Bremsdruck : 16|10@1+ (0.3,-30) [-30.0|276.6] "Unit_Bar" EPB_D4,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ ESP_Fahrer_bremst : 26|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ ESP_Verz_TSK_aktiv : 27|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ ESP_Lenkeingriff_ADS : 28|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4,SCU_D4 + SG_ ESP_Konsistenz_TSK : 29|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ ESP_Bremsruck_AWV2 : 30|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ ESP_Konsistenz_AWV2 : 31|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ ECD_Fehler : 32|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ ECD_nicht_verfuegbar : 33|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ ESP_Status_Bremsentemp : 34|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ ESP_Autohold_Standby : 35|1@1+ (1.0,0.0) [0.0|1] "" EPB_D4,Getriebe_AL551_951_D4_C7 + SG_ ESP_HDC_Standby : 36|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ ESP_HBA_aktiv : 37|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ ESP_Prefill_ausgeloest : 38|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ ESP_Rueckwaertsfahrt_erkannt : 39|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ ESP_Status_Anfahrhilfe : 40|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_MED17_SIMOS8_D4 + SG_ ESP_HDC_aktiv : 41|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ ESP_StartStopp_Info : 42|2@1+ (1.0,0.0) [0.0|3] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ ESP_Eingr_HL : 44|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ ESP_Eingr_HR : 45|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ ESP_Eingr_VL : 46|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ ESP_Eingr_VR : 47|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ ESP_BKV_Unterdruck : 48|8@1+ (4,0) [0|1012] "Unit_MilliBar" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ ESP_Autohold_aktiv : 56|1@1+ (1.0,0.0) [0.0|1] "" EPB_D4,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ ESP_FStatus_Anfahrhilfe : 57|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ ESP_Verz_EPB_aktiv : 58|1@1+ (1.0,0.0) [0.0|1] "" EPB_D4,Getriebe_AL551_951_D4_C7 + SG_ ECD_Bremslicht : 59|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ ESP_Verzoeg_EPB_verf : 60|1@1+ (1.0,0.0) [0.0|1] "" EPB_D4 + SG_ ESP_Status_Bremsdruck : 61|1@1+ (1.0,0.0) [0.0|1] "" EPB_D4,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ ESP_Anforderung_EPB : 62|2@1+ (1.0,0.0) [0.0|3] "" EPB_D4 + +BO_ 132 ESP_06: 8 ESP_D4 + SG_ ESP_06_CHK : 0|8@1+ (1,0) [0|255] "" SCU_D4 + SG_ ESP_06_BZ : 8|4@1+ (1,0) [0|15] "" Airbag_D4,SCU_D4 + SG_ ESP_06_KD_Fehler : 12|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ ESP_Teilsollwinkel : 16|11@1+ (0.1,0) [0.0|204.7] "Unit_DegreOfArc" SCU_D4 + SG_ ESP_VZ_Teilsollwinkel : 27|1@1+ (1.0,0.0) [0.0|1] "" SCU_D4 + SG_ ESP_Winkeleingriff : 28|2@1+ (1.0,0.0) [0.0|3] "" SCU_D4 + SG_ ESP_Status_ADS : 30|2@1+ (1.0,0.0) [0.0|3] "" SCU_D4 + SG_ ESP_v_ref : 32|12@1+ (0.125,0) [0.000|511.500] "Unit_KiloMeterPerHour" Airbag_D4 + SG_ void_Byte_10 : 48|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ ESP_06_CRC : 56|8@1+ (1,0) [0|255] "" Airbag_D4,SCU_D4 + +BO_ 914 ESP_07_FR: 8 Gateway_D4C7 + SG_ ESP_07_CHK : 0|8@1+ (1,0) [0|255] "" LWS_D4,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ ESP_07_BZ : 8|4@1+ (1,0) [0|15] "" LWS_D4,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ ESP_ACC_LDE : 12|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ ESP_Quattro_Antrieb : 13|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ ESP_Codierung_ADS : 14|2@1+ (1.0,0.0) [0.0|3] "" LWS_D4 + SG_ ESP_RTA_HL : 16|8@1+ (0.048828125,-6.20117) [-6.201170000|6.152345625] "Unit_PerCent" Vector__XXX + SG_ ESP_RTA_HR : 24|8@1+ (0.048828125,-6.20117) [-6.201170000|6.152345625] "Unit_PerCent" Vector__XXX + SG_ ESP_RTA_VR : 32|8@1+ (0.048828125,-6.20117) [-6.201170000|6.152345625] "Unit_PerCent" Vector__XXX + SG_ OBD_Fehler_Radsensor_HL : 40|4@1+ (1.0,0.0) [0.0|15] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ OBD_Fehler_Radsensor_HR : 44|4@1+ (1.0,0.0) [0.0|15] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ OBD_Fehler_Radsensor_VL : 48|4@1+ (1.0,0.0) [0.0|15] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ OBD_Fehler_Radsensor_VR : 52|4@1+ (1.0,0.0) [0.0|15] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ ESP_Qualifizierung_Antriebsart : 56|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ ESP_Offroad_Modus : 57|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ ESP_MKB_ausloesbar : 58|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ ESP_MKB_Status : 59|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ ESP_CM_Variante : 60|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ ESP_OBD_Status : 61|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + +BO_ 286 ESP_08: 8 Vector__XXX + SG_ ESP_08_CRC : 0|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ ESP_08_BZ : 8|4@1+ (1,0) [0|15] "" Vector__XXX + SG_ ESP_ANB_CM_Rueckk_Umsetz : 12|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ESP_Konsistenz_ACC_Botschaft : 13|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ESP_Stillstandsphase_erschoepft : 14|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ESP_ZT_Rueckk_Umsetz : 15|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ESP_Tuerkontakt_Fahrertuer : 16|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ESP_Abrutschen_Stillstand : 18|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ESP_Fahrer_tritt_ZBR_Schw : 19|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ESP_QBit_v_ref : 41|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ESP_v_ref_Fahrtrichtung : 42|2@1+ (1,0) [0|3] "" Vector__XXX + SG_ ESC_Bremsdruckgradient : 44|8@1+ (10,0) [0|2500] "Unit_BarPerSecon" Vector__XXX + SG_ ESP_v_ref : 52|12@1+ (0.125,0) [0|511.5] "Unit_KiloMeterPerHour" Vector__XXX + +BO_ 1623 ESP_17: 8 ESP_D4 + SG_ ESP_17_CRC : 0|8@1+ (1,0) [0|255] "" EPB_D4 + SG_ ESP_17_BZ : 8|4@1+ (1,0) [0|15] "" EPB_D4 + SG_ ESP_BremsenTemp_hinten : 12|3@1+ (1.0,0.0) [0.0|7] "" EPB_D4 + +BO_ 924 Gateway_05: 8 Gateway_D4C7 + SG_ BCM1_02_alt : 0|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ Wischer_01_alt : 1|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ Klima_02_alt : 2|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ BCM1_01_alt : 3|1@1+ (1.0,0.0) [0.0|1] "" EPB_D4,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ ESP_07_alt : 4|1@1+ (1.0,0.0) [0.0|1] "" Airbag_D4,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ TSG_BT_1_alt : 5|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ TSG_HL_1_alt : 6|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ TSG_HR_1_alt : 7|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ Motor_02_alt : 8|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ Klima_Sensor_02_alt : 9|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4,SCR_C7 + SG_ TSG_FT_1_alt : 10|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ Motor_05_alt : 11|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ QSP_01_alt : 12|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ Parkhilfe_01_alt : 13|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ Fahrwerk_02_alt : 14|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ GW_05_va_27 : 15|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BCM1_MH_WIV_Schalter : 16|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ Wischer_vorne_aktiv : 17|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ BCM1_Rueckfahrlicht_Schalter : 18|1@1+ (1.0,0.0) [0.0|1] "" EPB_D4,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ MO_Status_Normalbetrieb_01 : 19|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ KL_Zuheizer_Freigabe : 20|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ BCM1_Vorwaertsgang_eingelegt : 21|1@1+ (1.0,0.0) [0.0|1] "" EPB_D4 + SG_ ESP_Codierung_ADS : 22|2@1+ (1.0,0.0) [0.0|3] "" Airbag_D4,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ QSP_StartStopp_Info : 24|2@1+ (1.0,0.0) [0.0|3] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ FA_StartStopp_Info : 26|2@1+ (1.0,0.0) [0.0|3] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ PH_StartStopp_Info : 28|2@1+ (1.0,0.0) [0.0|3] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ KL_Beschlagsgefahr : 30|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ BCM1_GLW_Fernlicht_Anf : 31|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ BCM1_RFahrlicht_Fzg_Anf : 32|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ FT_Tuer_geoeffnet : 33|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ MO_Handshake_STH : 34|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ FT_Sperrklinke : 35|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ BCM1_OBD_FStatus_ATemp : 36|4@1+ (1.0,0.0) [0.0|15] "" Airbag_D4,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4,SCR_C7 + SG_ BCM1_Aussen_Temp_ungef : 40|8@1+ (0.5,-50) [-50.0|76.0] "Unit_DegreCelsi" Airbag_D4,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4,SCR_C7 + SG_ BCM1_Oeldruck_Schalter : 48|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ BCM1_Oeldruck_Schalter_2 : 49|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ BT_Tuer_geoeffnet : 50|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ HL_Tuer_geoeffnet : 51|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ HR_Tuer_geoeffnet : 52|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ BCM1_Adaptive_Lichtvert_Anf : 53|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ BCM1_Gleitende_Leuchtw_Anf : 54|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ BCM1_Schalter_StartStopp : 55|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ ESP_Offroad_Modus : 56|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ MO_Freig_Reku : 57|2@1+ (1.0,0.0) [0.0|3] "" Vector__XXX + +BO_ 927 Gateway_06: 8 XXX + SG_ AB_Gurtschloss_FA : 30|2@1+ (1,0) [0|3] "" XXX + +BO_ 1604 Gateway_11: 8 Gateway_D4C7 + SG_ SMLS_01_alt : 0|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ HUD_01_alt : 1|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BCM1_01_alt : 2|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ BCM1_02_alt : 3|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ BCM2_02_alt : 4|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_VL381_C7 + SG_ HYB_Anf_E_Mode_alt : 5|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ BCM1_04_alt : 6|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ ESP_04_alt : 7|1@1+ (1.0,0.0) [0.0|1] "" SCU_D4 + SG_ GW_11_va_20 : 8|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ GW_11_va_21 : 9|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ GW_11_va_22 : 10|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ GW_11_va_23 : 11|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ GW_11_va_24 : 12|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ GW_11_va_25 : 13|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ GW_11_va_26 : 14|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ GW_11_va_27 : 15|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ BH_Blinker_li : 16|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ BH_Blinker_re : 17|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ BM_Autobahn : 18|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ BH_Fernlicht : 19|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ BH_Lichthupe : 20|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ BCM1_MH_Schalter : 21|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ HYB_Anf_E_Mode : 22|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ HUD_NV_in_Anzeige : 23|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ BCM1_Touristen_Licht_Anf : 24|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ LV_Abblendlicht_li_def : 25|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ LV_Abblendlicht_re_def : 26|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ LV_Abblendlicht_Anzeige : 27|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ LV_AFL_aktiv_Anzeige : 28|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ BCM1_Licht_Dunkelheit_aktiv : 29|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ LV_Nebelschlusslicht_Anzeige : 30|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ BCM1_Linksverkehr : 31|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ BCM2_P_verriegelt : 32|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_VL381_C7 + SG_ BCM1_LDS_Stellung : 33|3@1+ (1.0,0.0) [0.0|7] "" Vector__XXX + SG_ BCM1_Allwetterlicht_Anf : 36|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ HUD_Anzeigefehler_NV : 37|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ ESP_Diagnose : 38|1@1+ (1.0,0.0) [0.0|1] "" SCU_D4 + +BO_ 130 Getriebe_01: 8 Getriebe_AL551_951_D4_C7 + SG_ Getriebe_01_CHK : 0|8@1+ (1,0) [0|255] "" Gateway_D4C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ Getriebe_01_BZ : 8|4@1+ (1,0) [0|15] "" Gateway_D4C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ GE_Schaltvorgang : 12|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ GE_Status_Kupplung : 13|2@1+ (1.0,0.0) [0.0|3] "" Gateway_D4C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ GE_Verbot_Ausblendung : 15|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ GE_MMom_Soll : 16|10@1+ (1,0) [0|1021] "" Gateway_D4C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ GE_MMom_Status : 26|2@1+ (1.0,0.0) [0.0|3] "" Gateway_D4C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ GE_Freig_Mmom_Soll : 28|1@1+ (1,0) [0|1] "" Gateway_D4C7 + SG_ GE_Status_Schaltablauf : 29|3@1+ (1,0) [0|7] "" Gateway_D4C7 + SG_ GE_MMom_Vorhalt : 32|10@1+ (1,0) [0|1021] "" Gateway_D4C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ GE_Freig_MMom_Vorhalt : 42|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ GE_KD_Fehler : 63|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + +BO_ 131 Getriebe_02: 8 Getriebe_AL551_951_D4_C7 + SG_ Getriebe_02_CHK : 0|8@1+ (1,0) [0|255] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ Getriebe_02_BZ : 8|4@1+ (1,0) [0|15] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ GE_Anf_Zylabsch : 13|2@1+ (1.0,0.0) [0.0|3] "" Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ GE_Synchro_Wunschdrehz : 15|9@1+ (25,0) [0|12750] "Unit_MinutInver" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ GE_Synchro_Zeit : 24|8@1+ (20,0) [0|5080] "Unit_MilliSecon" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ GE_Mom_Begr_Gradient : 32|8@1+ (10,0) [0|2540] "Unit_NewtoMeterPerSecon" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ GE_Anheb_Solldrehz_Leerlauf : 40|8@1+ (10,0) [0|2540] "Unit_MinutInver" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ GE_Vorsteuermoment : 48|9@1+ (1,0) [0|509] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ GE_Drehzahlmesser_Daempfung : 58|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ GE_Schubabschalt_Unt : 59|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ GE_Freigabe_Synchro : 60|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ GE_HYB_DZ_Eingriff : 61|2@1+ (1.0,0.0) [0.0|3] "" Vector__XXX + +BO_ 258 Getriebe_03: 8 Getriebe_AL551_951_D4_C7 + SG_ Getriebe_03_CHK : 0|8@1+ (1,0) [0|255] "" EPB_D4,Gateway_D4C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ Getriebe_03_BZ : 8|4@1+ (1,0) [0|15] "" EPB_D4,Gateway_D4C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ GE_Freig_Langfr_Schutzmom : 12|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ GE_Uefkt : 14|10@1+ (0.1,0) [0.0|102.2] "" EPB_D4,Gateway_D4C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ GE_Zielgang : 24|4@1+ (1.0,0.0) [0.0|15] "" Gateway_D4C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ GE_StartStopp_Info : 28|2@1+ (1.0,0.0) [0.0|3] "" Gateway_D4C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ GE_Langfr_Schutzmom : 32|10@1+ (1,0) [0|1021] "" Gateway_D4C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ GE_reserv_Waehlhebel : 43|1@1+ (1,0) [0|1] "" Gateway_D4C7 + SG_ GE_Waehlhebel : 44|4@1+ (1.0,0.0) [0.0|15] "" EPB_D4,Gateway_D4C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ GE_Eingangsdrehz : 48|14@1+ (1,0) [0|16381] "Unit_MinutInver" Gateway_D4C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ GE_Notlauf : 62|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ GE_Codierung_MSG : 63|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + +BO_ 1089 Getriebe_04: 8 Getriebe_AL551_951_D4_C7 + SG_ GE_Index_Fahrwid : 0|8@1+ (0.249,-31.623) [-31.623|31.623] "" Gateway_D4C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ GE_Heizwunsch : 8|2@1+ (1.0,0.0) [0.0|3] "" Gateway_D4C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ GE_OBD_Status : 10|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ GE_LFR_Adaption : 11|1@1+ (1,0) [0|1] "" Gateway_D4C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ GE_OBD_AbsperrVent : 12|4@1+ (1.0,0.0) [0.0|15] "" Gateway_D4C7 + SG_ GE_Grenzkriechmoment : 16|6@1+ (2,0) [0|122] "" Gateway_D4C7 + SG_ GE_Charisma_FahrPr : 24|3@1+ (1.0,0.0) [0.0|7] "" Gateway_D4C7 + SG_ GE_Charisma_Status : 27|2@1+ (1.0,0.0) [0.0|3] "" Gateway_D4C7 + SG_ GE_Charisma_Umschaltung : 29|2@1+ (1.0,0.0) [0.0|3] "" Gateway_D4C7 + SG_ GE_Freigabe_Verfallsinfo_WFS : 31|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ GE_Verlustmoment : 32|8@1+ (1,0) [0|254] "" EPB_D4,Gateway_D4C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ GE_amax_moeglich : 42|9@1+ (0.024,-2.016) [-2.016|10.224] "Unit_MeterPerSeconSquar" Gateway_D4C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ GE_Sumpftemperatur : 56|8@1+ (1,-58) [-58|196] "Unit_DegreCelsi" Gateway_D4C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + +BO_ 294 HCA_01: 8 Frontsensorik + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" Vector__XXX + SG_ HCA_01_Vib_Freq : 12|4@1+ (1,15) [15|30] "Unit_Hertz" Vector__XXX + SG_ HCA_01_LM_Offset : 16|9@1+ (1,0) [0|511] "Unit_centiNewtoMeter" Vector__XXX + SG_ EA_ACC_Sollstatus : 25|2@1+ (1,0) [0|3] "" Frontradar + SG_ EA_Ruckprofil : 27|3@1+ (1,0) [0|7] "" Vector__XXX + SG_ HCA_01_Sendestatus : 30|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ HCA_01_LM_OffSign : 31|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ HCA_01_Status_HCA : 32|4@1+ (1,0) [0|15] "" Vector__XXX + SG_ HCA_01_Vib_Amp : 36|4@1+ (0.2,0) [0|3] "Unit_NewtoMeter" Vector__XXX + SG_ EA_Ruckfreigabe : 40|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ EA_ACC_Wunschgeschwindigkeit : 41|10@1+ (0.32,0) [0|327.04] "Unit_KiloMeterPerHour" Frontradar + +BO_ 1811 ISO_ABS_Req: 8 Gateway_D4C7 + SG_ ISO_ABS_Req_Data : 0|64@1+ (1.0,0.0) [0.0|18446744073709551615] "" ESP_D4 + +BO_ 1917 ISO_ABS_Resp: 8 ESP_D4 + SG_ ISO_ABS_Resp_Data : 0|64@1+ (1.0,0.0) [0.0|18446744073709551615] "" Gateway_D4C7 + +BO_ 1813 ISO_Airbag_01_Req: 8 Gateway_D4C7 + SG_ ISO_Airbag_01_Req_Data : 0|64@1+ (1.0,0.0) [0.0|18446744073709551615] "" Airbag_D4 + +BO_ 1919 ISO_Airbag_01_Resp: 8 Airbag_D4 + SG_ ISO_Airbag_01_Resp_Data : 0|64@1+ (1.0,0.0) [0.0|18446744073709551615] "" Gateway_D4C7 + +BO_ 1874 ISO_EPB_Req: 8 Gateway_D4C7 + SG_ ISO_EPB_Req_Data : 0|64@1+ (1.0,0.0) [0.0|18446744073709551615] "" EPB_D4 + +BO_ 1980 ISO_EPB_Resp: 8 EPB_D4 + SG_ ISO_EPB_Resp_Data : 0|64@1+ (1.0,0.0) [0.0|18446744073709551615] "" Gateway_D4C7 + +BO_ 1795 ISO_Funktionaler_Req_Aggregate: 8 Gateway_D4C7 + SG_ ISO_Functionaler_Req_Aggregate : 0|64@1+ (1.0,0.0) [0.0|18446744073709551615] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4,Motor_Slave_D4,SCR_C7 + +BO_ 1792 ISO_Funktionaler_Req_All: 8 Gateway_D4C7 + SG_ ISO_ALL_01_Req_Data : 0|64@1+ (1.0,0.0) [0.0|18446744073709551615] "" Airbag_D4,EPB_D4,ESP_D4,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4,Motor_Slave_D4,SAK_C7,SCR_C7 + +BO_ 2015 ISO_Funktionaler_Req_OBD: 8 Gateway_D4C7 + SG_ ISO_OBD_Funktionaler_Req_Data : 0|64@1+ (1.0,0.0) [0.0|18446744073709551615] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4,Motor_Slave_D4,SCR_C7 + +BO_ 2017 ISO_Getriebe_01_Req: 8 Gateway_D4C7 + SG_ ISO_Getriebe_01_Req_Data : 0|64@1+ (1.0,0.0) [0.0|18446744073709551615] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + +BO_ 2025 ISO_Getriebe_01_Resp: 8 Getriebe_AL551_951_D4_C7 + SG_ ISO_Getriebe_01_Resp_Data : 0|64@1+ (1.0,0.0) [0.0|18446744073709551615] "" Gateway_D4C7 + +BO_ 2016 ISO_MO_01_Req: 8 Gateway_D4C7 + SG_ ISO_MO_01_Req_Data : 0|64@1+ (1.0,0.0) [0.0|18446744073709551615] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + +BO_ 2024 ISO_MO_01_Resp: 8 Motor_EDC17_D4 + SG_ ISO_MO_01_Resp_Data : 0|64@1+ (1.0,0.0) [0.0|18446744073709551615] "" Gateway_D4C7 + +BO_ 2018 ISO_MOS_01_Req: 8 Gateway_D4C7 + SG_ ISO_MOS_01_Req_Data : 0|64@1+ (1.0,0.0) [0.0|18446744073709551615] "" Motor_Slave_D4 + +BO_ 2026 ISO_MOS_01_Resp: 8 Motor_Slave_D4 + SG_ ISO_MOS_01_Resp_Data : 0|64@1+ (1.0,0.0) [0.0|18446744073709551615] "" Gateway_D4C7 + +BO_ 2019 ISO_OBD_reserv5_Req: 8 Gateway_D4C7 + SG_ ISO_OBD_reserv5_Req_Data : 0|64@1+ (1.0,0.0) [0.0|18446744073709551615] "" Vector__XXX + +BO_ 2027 ISO_OBD_reserv5_Resp: 8 Vector__XXX + SG_ ISO_OBD_reserv5_Resp_Data : 0|64@1+ (1.0,0.0) [0.0|18446744073709551615] "" Gateway_D4C7 + +BO_ 1834 ISO_SCR_Req: 8 Gateway_D4C7 + SG_ ISO_SCR_Req_Data : 0|64@1+ (1.0,0.0) [0.0|18446744073709551615] "" SCR_C7 + +BO_ 1940 ISO_SCR_Resp: 8 SCR_C7 + SG_ ISO_SCR_Resp_Data : 0|64@1+ (1.0,0.0) [0.0|18446744073709551615] "" Gateway_D4C7 + +BO_ 1814 ISO_SCU_Req: 8 Gateway_D4C7 + SG_ ISO_SCU_Req_Data : 0|64@1+ (1.0,0.0) [0.0|18446744073709551615] "" Vector__XXX + +BO_ 1920 ISO_SCU_Resp: 8 Vector__XXX + SG_ ISO_SCU_Resp_Data : 0|64@1+ (1.0,0.0) [0.0|18446744073709551615] "" Gateway_D4C7 + +BO_ 1820 ISO_Soundaktor_Req: 8 Gateway_D4C7 + SG_ ISO_Soundaktor_Req_Data : 0|64@1+ (1.0,0.0) [0.0|18446744073709551615] "" SAK_C7 + +BO_ 1926 ISO_Soundaktor_Resp: 8 SAK_C7 + SG_ ISO_Soundaktor_Resp_Data : 0|64@1+ (1.0,0.0) [0.0|18446744073709551615] "" Gateway_D4C7 + +BO_ 1875 ISO_Waehlhebel_Req: 8 Gateway_D4C7 + SG_ ISO_Waehlhebel_Req_Data : 0|64@1+ (1.0,0.0) [0.0|18446744073709551615] "" Getriebe_AL551_951_D4_C7 + +BO_ 1981 ISO_Waehlhebel_Resp: 8 Getriebe_AL551_951_D4_C7 + SG_ ISO_Waehlhebel_Resp_Data : 0|64@1+ (1.0,0.0) [0.0|18446744073709551615] "" Gateway_D4C7 + +BO_ 1424 Kessy_02: 8 Gateway_D4C7 + SG_ KY_Funkschl_Nr : 0|4@1+ (1.0,0.0) [0.0|15] "" Vector__XXX + SG_ KY_ID_Geb_autorisiert : 4|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ KY_ID_Geb_steckt : 5|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ KY_FFB_Frequenz : 6|2@1+ (1.0,0.0) [0.0|3] "" Vector__XXX + SG_ KY_HF_Aktiv : 8|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ KY_LF_Aktiv : 9|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ KY_ELV_verr : 10|1@1+ (1.0,0.0) [0.0|1] "" EPB_D4 + SG_ KY_ELV_entr : 11|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ KY_ELV_enable_Anforderung : 12|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ KY_Valet_Parking : 14|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ KY_Keyless_Verbau : 15|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ KY_FBS_Fahrer_Hinweise : 16|3@1+ (1.0,0.0) [0.0|7] "" Vector__XXX + SG_ FBS_Warn_Lenkung_def : 19|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ FBS_Warn_LenkVerriegelung_def : 20|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ FBS_Warn_Schluessel_Batt : 21|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ FBS_Prio_Warn_04 : 22|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ FBS_Prio_Warn_05 : 23|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ KY_KYL_Fahrer_Hinweise : 24|3@1+ (1.0,0.0) [0.0|7] "" Vector__XXX + SG_ KYL_Warn_kein_Schluessel : 27|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ KYL_Warn_Kessy_defekt : 28|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ KY_KYL_Prio_Warn_03 : 29|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ KY_KYL_Prio_Warn_04 : 30|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ KY_KYL_Prio_Warn_05 : 31|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ KY_Schluessel_Soll : 32|4@1+ (1.0,0.0) [0.0|15] "" Vector__XXX + SG_ KY_Schluessel_Ist : 36|4@1+ (1.0,0.0) [0.0|15] "" Vector__XXX + SG_ KY_WFS_Safe : 40|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ KY_WFS_LZ : 41|2@1+ (1.0,0.0) [0.0|3] "" Vector__XXX + SG_ KY_StartStopp_Info : 43|2@1+ (1.0,0.0) [0.0|3] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ KYL_Notzuendschloss : 45|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ KYL_Warn_Notzuendschloss : 46|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ FBS_KD_Fehler : 47|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + +BO_ 960 Klemmen_Status_01: 4 Gateway_D4C7 + SG_ Klemmen_Status_01_CHK : 0|8@1+ (1,0) [0|255] "" EPB_D4,Getriebe_AL551_951_D4_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ Klemmen_Status_01_BZ : 8|4@1+ (1,0) [0|15] "" EPB_D4,Getriebe_AL551_951_D4_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ ZV_verriegelt_extern_soll_02 : 12|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7 + SG_ ZAS_Kl_S : 16|1@1+ (1.0,0.0) [0.0|1] "" EPB_D4,Getriebe_AL551_951_D4_C7 + SG_ ZAS_Kl_15 : 17|1@1+ (1.0,0.0) [0.0|1] "" EPB_D4,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4,SCU_D4 + SG_ ZAS_Kl_X : 18|1@1+ (1.0,0.0) [0.0|1] "" EPB_D4,SCU_D4 + SG_ ZAS_Kl_50 : 19|1@1+ (1.0,0.0) [0.0|1] "" EPB_D4,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + +BO_ 959 Klima_01: 8 Gateway_D4C7 + SG_ KL_Drehz_Anh : 0|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ KL_Vorwarn_Komp_ein : 1|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ KL_Handshake_BEM : 2|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ KL_Komp_Moment_alt : 3|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ KL_Vorwarn_HHS_ein : 4|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ KL_Vorwarn_HFS_ein : 5|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ KL_Vorwarn_Zuheizer_ein : 6|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ KL_KD_Fehler : 7|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ KL_Comp_rev_rq : 8|8@1+ (50,0) [0|8600] "Unit_MinutInver" Vector__XXX + SG_ KL_Charisma_FahrPr : 16|3@1+ (1.0,0.0) [0.0|7] "" Vector__XXX + SG_ KL_Charisma_Status : 19|2@1+ (1.0,0.0) [0.0|3] "" Vector__XXX + SG_ KL_Charisma_Umschaltung : 21|2@1+ (1.0,0.0) [0.0|3] "" Vector__XXX + SG_ KL_Last_Kompr : 24|8@1+ (0.25,0) [0.00|63.50] "Unit_NewtoMeter" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ KL_Leistung_Hzg_Soll : 32|8@1+ (11,0) [0|2805] "Unit_Watt" Vector__XXX + SG_ KL_Anf_KL : 40|8@1+ (0.4,0) [0.0|101.6] "Unit_PerCent" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ KL_4_Zonen : 48|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ KL_AC_Schalter : 49|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7 + SG_ KL_Zustand : 50|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ KL_Thermomanagement : 51|2@1+ (1.0,0.0) [0.0|3] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ KL_Comp_enable : 53|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ KL_StartStopp_Info : 54|2@1+ (1.0,0.0) [0.0|3] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ KL_el_Zuheizer_Stufe : 56|3@1+ (1.0,0.0) [0.0|7] "" Motor_EDC17_D4 + SG_ KL_Diag_Absperrvent : 59|4@1+ (1.0,0.0) [0.0|15] "" Vector__XXX + +BO_ 779 Kombi_01: 8 Gateway_D4C7 + SG_ KBI_ABS_Lampe : 0|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7 + SG_ KBI_ESP_Lampe : 1|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7 + SG_ KBI_BKL_Lampe : 2|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7 + SG_ KBI_Airbag_Lampe : 3|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7 + SG_ KBI_SILA_gueltig : 4|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7 + SG_ KBI_Lenkung_Lampe : 5|1@1+ (1,0) [0|1] "" Getriebe_AL551_951_D4_C7 + SG_ KBI_Vorglueh_System_Lampe : 6|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7,Motor_EDC17_D4 + SG_ KBI_NV_in_Anzeige : 7|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7 + SG_ XCOUNTER : 8|4@1+ (1,0) [0|15] "" Getriebe_AL551_951_D4_C7 + SG_ KBI_Anzeigestatus_ACC : 12|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7 + SG_ KBI_Oeldruck_Schalter : 15|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7 + SG_ KBI_Tankwarnung : 16|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ KBI_MFA_v_Einheit_01 : 17|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ KBI_im_Stellgliedtest : 18|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7 + SG_ KBI_Anzeigefehler_LDW : 19|2@1+ (1.0,0.0) [0.0|3] "" Getriebe_AL551_951_D4_C7 + SG_ KBI_Variante_USA : 21|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7 + SG_ KBI_Oeldruckwarnung : 22|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7 + SG_ KBI_Handbremse : 23|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7 + SG_ KBI_V_Digital : 24|9@1+ (1,0) [0|511] "" Getriebe_AL551_951_D4_C7 + SG_ KBI_PLA_in_Anzeige : 33|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7 + SG_ KBI_Anzeigefehler_NV : 34|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7 + SG_ KBI_angez_Geschw : 48|10@1+ (0.32,0) [0.00|325.12] "Unit_KiloMeterPerHour" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ KBI_Einheit_Tacho : 58|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ KBI_Konsistenz_ACC : 59|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7 + SG_ KBI_Fehler_Anzeige_ACC : 60|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7 + SG_ KBI_Anzeigefehler_SWA : 61|2@1+ (1.0,0.0) [0.0|3] "" Getriebe_AL551_951_D4_C7 + SG_ KBI_KD_Fehler : 63|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7 + +BO_ 1719 Kombi_02: 8 Gateway_D4C7 + SG_ KBI_Kilometerstand : 0|20@1+ (1,0) [0|1048573] "Unit_KiloMeter" Vector__XXX + SG_ KBI_Standzeit : 20|15@1+ (4,0) [0|131068] "Unit_Secon" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ KBI_Reset_Standzeit : 35|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ KBI_Inhalt_Tank : 40|7@1+ (1,0) [0|126] "Unit_Liter" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ KBI_FStatus_Tank : 47|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ KBI_QBit_Aussen_Temp_gef : 55|1@1+ (1.0,0.0) [0.0|1] "" EPB_D4,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4,SCR_C7 + SG_ KBI_Aussen_Temp_gef : 56|8@1+ (0.5,-50) [-50.0|75.0] "Unit_DegreCelsi" EPB_D4,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4,SCR_C7 + +BO_ 1720 Kombi_03: 8 Gateway_D4C7 + SG_ KBI_Reifenumfang : 0|12@1+ (1,0) [0|4095] "Unit_MilliMeter" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ WFS_Schluessel_Fahrberecht : 12|4@1+ (1.0,0.0) [0.0|15] "" Vector__XXX + SG_ KBI_BCmE_aktiv : 16|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ KBI_Sparhinweis_quittiert : 17|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + +BO_ 517 KS_Airbag: 8 Airbag_D4 + SG_ KS_Airbag_Data : 0|64@1+ (1.0,0.0) [0.0|18446744073709551615] "" Gateway_D4C7 + +BO_ 640 KS_Master: 8 Gateway_D4C7 + SG_ KS_Master_Data : 0|64@1+ (1.0,0.0) [0.0|18446744073709551615] "" Airbag_D4 + +BO_ 919 LDW_02: 8 Gateway_D4C7 + SG_ LDW_Gong : 12|2@1+ (1.0,0.0) [0.0|3] "" Kombi_D4 + SG_ LDW_SW_Warnung_links : 14|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ LDW_SW_Warnung_rechts : 15|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ LDW_Texte : 16|4@1+ (1.0,0.0) [0.0|15] "" Kombi_D4 + SG_ LDW_Seite_DLCTLC : 20|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ LDW_Lernmodus : 21|3@1+ (1.0,0.0) [0.0|7] "" HUD_C7 + SG_ LDW_Anlaufsp_VLR : 24|4@1+ (1,0) [0|15] "" SMLS_D4 + SG_ LDW_Vib_Amp_VLR : 28|4@1+ (1,0) [0|15] "" SMLS_D4 + SG_ LDW_Anlaufzeit_VLR : 32|4@1+ (1,0) [0|15] "" SMLS_D4 + SG_ LDW_Lernmodus_rechts : 36|2@1+ (1,0) [0|3] "" XXX + SG_ LDW_Lernmodus_links : 38|2@1+ (1,0) [0|3] "" XXX + SG_ LDW_DLC : 40|8@1+ (0.01,-1.25) [-1.25|1.25] "Unit_Meter" Vector__XXX + SG_ LDW_TLC : 48|5@1+ (0.1,0) [0.0|3.0] "Unit_Secon" Vector__XXX + SG_ LDW_Warnung_links : 56|1@1+ (1.0,0.0) [0.0|1] "" SMLS_D4 + SG_ LDW_Warnung_rechts : 57|1@1+ (1.0,0.0) [0.0|1] "" SMLS_D4 + SG_ LDW_Codierinfo_fuer_VLR : 58|2@1+ (1.0,0.0) [0.0|3] "" SMLS_D4 + SG_ LDW_Frontscheibenheizung_aktiv : 60|1@1+ (1.0,0.0) [0.0|1] "" Klima_D4_C7,SMLS_D4 + SG_ LDW_Status_LED_gelb : 61|1@1+ (1.0,0.0) [0.0|1] "" APS_D4,Kombi_D4 + SG_ LDW_Status_LED_gruen : 62|1@1+ (1.0,0.0) [0.0|1] "" APS_D4,Kombi_D4 + SG_ LDW_KD_Fehler : 63|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + +BO_ 810 LH_EPS_01: 8 Gateway_D4C7 + SG_ EPS_01_CRC : 0|8@1+ (1,0) [0|255] "" APS_D4 + SG_ EPS_01_BZ : 8|4@1+ (1,0) [0|15] "" APS_D4 + SG_ EPS_Akustiksignal : 16|1@1+ (1.0,0.0) [0.0|1] "" Kombi_D4 + SG_ EPS_Fehlerlampe : 17|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ EPS_KD_Fehler : 18|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ EPS_Warnungen : 19|3@1+ (1.0,0.0) [0.0|7] "" Kombi_D4 + SG_ EPS_PLA_Abbruch : 22|4@1+ (1,0) [0|15] "" APS_D4 + SG_ EPS_PLA_Fehler : 26|4@1+ (1,0) [0|15] "" APS_D4 + SG_ EPS_PLA_Status : 30|4@1+ (1,0) [0|15] "" APS_D4 + SG_ EPS_Charisma_FahrPr : 34|3@1+ (1.0,0.0) [0.0|7] "" Vector__XXX + SG_ EPS_Charisma_Status : 37|2@1+ (1.0,0.0) [0.0|3] "" Vector__XXX + SG_ EPS_Charisma_Umschaltung : 39|2@1+ (1.0,0.0) [0.0|3] "" Vector__XXX + SG_ EPS_Lenkerposition : 41|2@1+ (1.0,0.0) [0.0|3] "" Vector__XXX + SG_ EPS_Anf_KL : 43|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + +BO_ 285 LH_EPS_02: 8 Gateway_D4C7 + SG_ EPS_02_CRC : 0|8@1+ (1,0) [0|255] "" SCU_D4 + SG_ EPS_02_BZ : 8|4@1+ (1,0) [0|15] "" SCU_D4 + SG_ EPS_Notlauf : 12|4@1+ (1.0,0.0) [0.0|15] "" Vector__XXX + SG_ EPS_Lastinfo : 16|8@1+ (1,0) [0|253] "Unit_Amper" Vector__XXX + SG_ EPS_Unterstuetzungsleistung : 24|8@1+ (0.5,0) [0.0|100.0] "Unit_PerCent" SCU_D4 + SG_ EPS_Drehzahlreserve : 32|7@1+ (10,0) [0|1000] "Unit_DegreOfArcPerSecon" SCU_D4 + SG_ EPS_VZ_Drehzahlreserve : 39|1@1+ (1.0,0.0) [0.0|1] "" SCU_D4 + SG_ EPS_Leistungsanforderung : 40|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + +BO_ 159 LH_EPS_03: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX + SG_ EPS_DSR_Status : 12|4@1+ (1,0) [0|15] "" XXX + SG_ EPS_Berechneter_LW : 16|12@1+ (0.15,0) [0|613.95] "Unit_DegreOfArc" XXX + SG_ EPS_BLW_QBit : 30|1@1+ (1,0) [0|1] "" XXX + SG_ EPS_VZ_BLW : 31|1@1+ (1,0) [0|1] "" XXX + SG_ EPS_HCA_Status : 32|4@1+ (1,0) [0|15] "" XXX + SG_ EPS_Lenkmoment : 40|10@1+ (1,0) [0|8] "Unit_centiNewtoMeter" XXX + SG_ EPS_Lenkmoment_QBit : 54|1@1+ (1,0) [0|1] "" XXX + SG_ EPS_VZ_Lenkmoment : 55|1@1+ (1,0) [0|1] "" XXX + SG_ EPS_Lenkungstyp : 60|4@1+ (1,0) [0|15] "" XXX + +BO_ 1137 Licht_hinten_01: 8 Gateway_D4C7 + SG_ Licht_hinten_01_BZ : 0|4@1+ (1,0) [0|15] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ BCM2_Bremsl_durch_ECD : 5|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ LH_Aussenlicht_def : 7|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ LH_Standlicht_H_aktiv : 8|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ LH_Parklicht_HL_aktiv : 9|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ LH_Parklicht_HR_aktiv : 10|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ LH_Bremslicht_H_aktiv : 11|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ LH_Nebelschluss_aktiv : 12|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ LH_Rueckfahrlicht_aktiv : 13|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ LH_Blinker_HL_akt : 14|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ LH_Blinker_HR_akt : 15|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ LH_Blinker_li_def : 16|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ LH_Bremsl_li_def : 17|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ LH_Schlusslicht_li_def : 18|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ LH_Rueckf_li_def : 19|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ LH_Nebel_li_def : 20|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ LH_Schluss_Brems_Nebel_li_def : 21|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ LH_Schluss_Brems_Nebel_re_def : 22|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ LH_Schluss_Brems_li_def : 24|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ LH_Schluss_Nebel_li_def : 25|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ LH_SL_BRL_BLK_li_def : 26|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ LH_Brems_Blk_li_def : 27|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ LH_Blinker_re_def : 32|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ LH_Bremsl_re_def : 33|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ LH_Schlusslicht_re_def : 34|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ LH_Rueckf_re_def : 35|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ LH_Nebel_re_def : 36|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ LH_Schluss_Brems_re_def : 40|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ LH_Schluss_Nebel_re_def : 41|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ LH_SL_BRL_BLK_re_def : 42|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ LH_Brems_Blk_re_def : 43|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ LH_Kennzl_def : 48|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ LH_3_Bremsl_def : 49|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ LH_Nebel_mi_def : 50|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ LH_Rueckf_mi_def : 51|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ LH_Bremsl_li_ges_def : 54|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ LH_Bremsl_re_ges_def : 55|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + +BO_ 267 LS_01: 4 Gateway_D4C7 + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ LS_Hauptschalter : 12|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ LS_Abbrechen : 13|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ LS_Typ_Hauptschalter : 14|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ LS_Limiter : 15|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ LS_Tip_Setzen : 16|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_DL501_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ LS_Tip_Hoch : 17|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_DL501_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ LS_Tip_Runter : 18|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_DL501_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ LS_Tip_Wiederaufnahme : 19|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_DL501_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ LS_Verstellung_Zeitluecke : 20|2@1+ (1.0,0.0) [0.0|3] "" Vector__XXX + SG_ MFL_Tip_Down : 22|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ MFL_Tip_Up : 23|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ LS_Tiptronic_Fehler : 24|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7 + SG_ LS_Fehler : 25|1@1+ (1,0) [0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ LS_Codierung : 26|3@1+ (1.0,0.0) [0.0|7] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ LS_Tip_Stufe_2 : 29|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ LS_GRA_ACC_2stufig : 30|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ MFL_M_Taste : 31|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7 + +BO_ 134 LWI_01: 8 LWS_D4 + SG_ LWI_01_CHK : 0|8@1+ (1,0) [0|255] "" ESP_D4,Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4,QSP_D4,SCU_D4 + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" Airbag_D4,ESP_D4,Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4,QSP_D4,SCU_D4 + SG_ LWI_Sensorstatus : 12|1@1+ (1.0,0.0) [0.0|1] "" ESP_D4,Gateway_D4C7,Getriebe_AL551_951_D4_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4,QSP_D4,SCU_D4 + SG_ LWI_QBit_Sub_Daten : 13|1@1+ (1.0,0.0) [0.0|1] "" ESP_D4,Gateway_D4C7,QSP_D4,SCU_D4 + SG_ LWI_QBit_Lenkradwinkel : 15|1@1+ (1.0,0.0) [0.0|1] "" Airbag_D4,ESP_D4,Gateway_D4C7,Getriebe_AL551_951_D4_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4,QSP_D4,SCU_D4 + SG_ LWI_Lenkradwinkel : 16|13@1+ (0.1,0) [0.0|800.0] "Unit_DegreOfArc" Airbag_D4,ESP_D4,Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4,QSP_D4,SCU_D4 + SG_ LWI_VZ_Lenkradwinkel : 29|1@1+ (1.0,0.0) [0.0|1] "" Airbag_D4,ESP_D4,Gateway_D4C7,Getriebe_AL551_951_D4_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4,QSP_D4,SCU_D4 + SG_ LWI_VZ_Lenkradw_Geschw : 30|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7,QSP_D4 + SG_ LWI_Lenkradw_Geschw : 31|9@1+ (5,0) [0|2500] "Unit_DegreOfArcPerSecon" Gateway_D4C7,QSP_D4 + SG_ LWI_Sub_Daten : 40|16@1+ (1,0) [0|65535] "" ESP_D4,Gateway_D4C7,QSP_D4,SCU_D4 + SG_ LWI_01_CRC : 56|8@1+ (1,0) [0|255] "" Airbag_D4,ESP_D4,Gateway_D4C7,QSP_D4,SCU_D4 + +BO_ 128 Motor_01: 8 Motor_EDC17_D4 + SG_ Motor_01_CHK : 0|8@1+ (1,0) [0|255] "" EPB_D4,Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ Motor_01_BZ : 8|4@1+ (1,0) [0|15] "" EPB_D4,Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ MO_Mom_o_ex : 12|10@1+ (1,0) [0|1021] "" Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ MO_Mom_m_ex : 22|10@1+ (1,0) [0|1021] "" EPB_D4,Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,SAK_C7 + SG_ MO_Mom_Verlust : 32|10@1+ (1,0) [0|1021] "" EPB_D4,Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,SAK_C7 + SG_ MO_Mom_Begrenzung : 42|10@1+ (1,0) [0|1021] "" Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ MO_Mom_Fahrerwunsch : 52|10@1+ (1,0) [0|1021] "" Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ MO_Kickdown : 62|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ MO_KD_Fehler : 63|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + +BO_ 129 Motor_02: 8 Motor_EDC17_D4 + SG_ Motor_02_CHK : 0|8@1+ (1,0) [0|255] "" EPB_D4,Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,SCU_D4 + SG_ Motor_02_BZ : 8|4@1+ (1,0) [0|15] "" EPB_D4,Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,SCU_D4 + SG_ MO_Mom_ZWR : 12|10@1+ (1,0) [0|1021] "" Gateway_D4C7 + SG_ MO_Mom_Soll : 22|10@1+ (1,0) [0|1021] "" Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ MO_Mom_Ist : 32|10@1+ (1,0) [0|1021] "" Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ MO_Status_Zylabschalt_01 : 42|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7,Getriebe_AL551_951_D4_C7 + SG_ MO_Status_Normalbetrieb_01 : 43|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ MO_StartStopp_Status : 44|2@1+ (1.0,0.0) [0.0|3] "" Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,SCR_C7,SCU_D4 + SG_ MO_StartStopp_Motorstopp : 46|1@1+ (1.0,0.0) [0.0|1] "" EPB_D4,Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,SCR_C7,SCU_D4 + SG_ MO_StartStopp_Wiederstart : 47|1@1+ (1.0,0.0) [0.0|1] "" EPB_D4,Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,SCR_C7,SCU_D4 + SG_ MO_Ext_E_Fahrt_aktiv : 48|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ MO_Gangposition : 49|4@1+ (1.0,0.0) [0.0|15] "" Gateway_D4C7 + SG_ MO_StartStopp_Fahrerwunsch : 53|2@1+ (1.0,0.0) [0.0|3] "" Gateway_D4C7 + SG_ MO_Momentenintegral : 56|8@1+ (0.3921,0) [0.0000|99.9855] "" Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + +BO_ 261 Motor_03: 8 Motor_EDC17_D4 + SG_ MOTOR_03_CHK : 0|8@1+ (1,0) [0|255] "" EPB_D4,Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,SCU_D4 + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" EPB_D4,Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,SCU_D4 + SG_ MO_QBit_Fahrpedalwerte_01 : 12|1@1+ (1.0,0.0) [0.0|1] "" EPB_D4,Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ MO_QBit_Motormomente : 13|1@1+ (1.0,0.0) [0.0|1] "" EPB_D4,Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ MO_QBit_Fahrer_bremst : 14|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ MO_QBit_Drehzahl_01 : 15|1@1+ (1.0,0.0) [0.0|1] "" EPB_D4,Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,SCR_C7 + SG_ MO_Drehzahl_01 : 16|16@1+ (0.25,0) [0.00|16383.00] "Unit_MinutInver" EPB_D4,Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,SAK_C7,SCR_C7,SCU_D4 + SG_ MO_Moment_im_Leerlauf : 32|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ MO_Interlock : 33|1@1+ (1.0,0.0) [0.0|1] "" EPB_D4,Gateway_D4C7 + SG_ MO_BLS : 34|1@1+ (1.0,0.0) [0.0|1] "" EPB_D4,Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ MO_Fahrer_bremst : 35|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ MO_Konsistenz_Bremsped : 36|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ MO_Kuppl_schalter : 37|1@1+ (1.0,0.0) [0.0|1] "" EPB_D4,Gateway_D4C7 + SG_ MO_Timeout_ESP : 38|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ MO_Motor_laeuft : 39|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ MO_Solldrehz_Leerlauf : 40|8@1+ (10,0) [0|2540] "Unit_MinutInver" Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ MO_Fahrpedalrohwert_01 : 48|8@1+ (0.4,0) [0.0|101.6] "Unit_PerCent" EPB_D4,Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ MO_erste_Ungenauschwelle : 56|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ MO_QBit_Stressfaktor : 57|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ MO_Stressfaktor : 58|6@1+ (1.6,0) [0.0|100.8] "Unit_PerCent" Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + +BO_ 263 Motor_04: 8 Motor_EDC17_D4 + SG_ MO_Istgang : 8|4@1+ (1.0,0.0) [0.0|15] "" Gateway_D4C7 + SG_ MO_Sollgang : 12|4@1+ (1.0,0.0) [0.0|15] "" Gateway_D4C7 + SG_ MO_Oeldruck : 16|8@1+ (0.04,0) [0.00|10.00] "Unit_Bar" Gateway_D4C7 + SG_ MO_Anzeigedrehz : 24|12@1+ (3,0) [0|12282] "Unit_MinutInver" Gateway_D4C7 + SG_ MO_Schaltempf_verfbar : 38|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ MO_Ladedruck : 39|9@1+ (0.01,0) [0.00|5.10] "Unit_Bar" Gateway_D4C7 + SG_ MO_KVS : 48|15@1+ (1,0) [0|32767] "Unit_MicroLiter" Gateway_D4C7 + SG_ MO_KVS_Ueberlauf : 63|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + +BO_ 782 Motor_05: 8 Motor_EDC17_D4 + SG_ Motor_05_CHK : 0|8@1+ (1,0) [0|255] "" Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ Motor_05_BZ : 8|4@1+ (1,0) [0|15] "" Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ MO_EKlKomLeiRed : 12|2@1+ (1.0,0.0) [0.0|3] "" Gateway_D4C7 + SG_ MO_Freig_Reku : 14|2@1+ (1.0,0.0) [0.0|3] "" Gateway_D4C7 + SG_ MO_Klima_Eingr : 16|2@1+ (1.0,0.0) [0.0|3] "" Gateway_D4C7 + SG_ MO_Status_Normalbetrieb_02 : 18|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ MO_Schaltbeeinfl_Leistungsbegr : 19|1@1+ (1,0) [0|1] "" Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7 + SG_ MO_Schaltbeeinfl_Partikelfilter : 20|1@1+ (1,0) [0|1] "" Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7 + SG_ MO_Prio_MIN_Wunschdrehzahl : 21|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ MO_Freig_Anlass : 22|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ MO_Aussp_Anlass : 23|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ MO_MAX_Wunschdrehzahl : 24|9@1+ (25,0) [0|12750] "Unit_MinutInver" Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ MO_Prio_MAX_Wunschdrehzahl : 33|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ MO_Luftpfad_aktiv : 34|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7 + SG_ MO_v_Begrenz_Aktiv : 35|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ MO_v_Begrenz_Aktivierbar : 36|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ MO_Verbot_EKP : 37|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ MO_Anf_Pruefimpuls : 38|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ MO_Anf_KL75 : 39|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ MO_Charisma_FahrPr : 40|3@1+ (1.0,0.0) [0.0|7] "" Gateway_D4C7 + SG_ MO_Charisma_Status : 43|2@1+ (1.0,0.0) [0.0|3] "" Gateway_D4C7 + SG_ MO_Charisma_Umschaltung : 45|2@1+ (1.0,0.0) [0.0|3] "" Gateway_D4C7 + SG_ MO_Handshake_STH : 47|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ MO_MIN_Wunschdrehzahl : 48|8@1+ (25,0) [0|6350] "Unit_MinutInver" Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ MO_Drehzahlbeeinflussung : 56|8@1+ (0.39,0) [0.00|99.45] "Unit_PerCent" Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + +BO_ 1088 Motor_06: 8 Motor_EDC17_D4 + SG_ MO_Kuehlerluefter_MUX M : 0|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ MO_Kuehlerluefter_1 m0 : 1|7@1+ (1,0) [0|100] "Unit_PerCent" Gateway_D4C7 + SG_ MO_Kuehlerluefter_2 m1 : 1|7@1+ (1,0) [0|100] "Unit_PerCent" Gateway_D4C7 + SG_ MO_HYB_Status_HV_Ladung : 8|3@1+ (1.0,0.0) [0.0|7] "" Gateway_D4C7 + SG_ WIV_Anzeige_aktiv : 12|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ WIV_Oelmin_Warn : 13|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ WIV_Sensorfehler : 14|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ WIV_Schieflage : 15|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ WIV_Oelstand : 16|4@1+ (12.5,0) [0.0|100.0] "Unit_PerCent" Gateway_D4C7 + SG_ MO_Zustand_HWP : 20|2@1+ (1.0,0.0) [0.0|3] "" Gateway_D4C7 + SG_ WIV_Oelsystem_aktiv : 24|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ WIV_nicht_betriebswarm : 25|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ WIV_Ueberfuell_Warn : 26|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ WIV_laufender_Motor : 27|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ MO_HYB_Text_1 : 28|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ MO_HYB_Text_2 : 29|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ MO_HYB_Text_3 : 30|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ MO_Text_Motorstart : 32|4@1+ (1.0,0.0) [0.0|15] "" Gateway_D4C7 + SG_ MO_HYB_Text_5 : 36|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ MO_HYB_Text_6 : 37|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ MO_HYB_Text_7 : 38|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ WIV_Oeldyn_avl : 39|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ MO_Text_MSG_Werkstatt : 40|1@1+ (1,0) [0|1] "" Gateway_D4C7 + SG_ MO_Text_Partikelfil_Reg : 41|1@1+ (1,0) [0|1] "" Gateway_D4C7 + SG_ MO_Text_Fehler_Kraftstoffsys : 42|1@1+ (1,0) [0|1] "" Gateway_D4C7 + SG_ WIV_Oelmenge : 43|5@1+ (125,0) [0|3875] "Unit_MilliLiter" Gateway_D4C7 + SG_ MO_Systemlampe : 48|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ MO_OBD2_Lampe : 49|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ MO_Heissleuchte : 50|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ MO_Partikel_Lampe : 51|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ MO_Winterfahrprog : 52|1@1+ (1,0) [0|1] "" Gateway_D4C7 + SG_ WIV_Oelstand_nicht_vorhanden : 53|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ WIV_nachfuellanzeige_ein : 54|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ WIV_Ueberfuell_deaktiv : 55|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ WIV_Unterfuell_Warn : 56|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ MO_Tankdeckel_Lampe : 57|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ MO_Text_Tankdeckelwarn : 58|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ WIV_Enable_Oeldr_Motor : 59|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ WIV_Oeldr_Warn_Motor : 60|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ MO_Avus_Motorschutz : 61|2@1+ (1.0,0.0) [0.0|3] "" Gateway_D4C7 + SG_ MO_HYB_Fahrbereitschaft : 63|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + +BO_ 1600 Motor_07: 8 Motor_EDC17_D4 + SG_ MO_QBit_Ansaugluft_Temp : 0|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ MO_QBit_Oel_Temp : 1|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7,Getriebe_AL551_951_D4_C7 + SG_ MO_QBit_Kuehlmittel_Temp : 2|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ MO_Stellgliedtest_Soundaktuator : 3|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ MO_HYB_Fehler_HV_Netz : 4|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ MO_aktives_Getriebeheizen : 5|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ MO_Absperrventil_oeffnen : 6|2@1+ (1.0,0.0) [0.0|3] "" Gateway_D4C7 + SG_ MO_Ansaugluft_Temp : 8|8@1+ (0.75,-48) [-48.00|141.75] "Unit_DegreCelsi" Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ MO_Oel_Temp : 16|8@1+ (1,-60) [-60|192] "Unit_DegreCelsi" Gateway_D4C7,Getriebe_AL551_951_D4_C7 + SG_ MO_Kuehlmittel_Temp : 24|8@1+ (0.75,-48) [-48.00|141.75] "Unit_DegreCelsi" Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ MO_Hoeheninfo : 32|8@1+ (0.00781,0) [0.00000|1.98374] "" Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ MO_Kennfeldk : 40|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ MO_Versionsinfo : 41|6@1+ (1.0,0.0) [0.0|63] "" Gateway_D4C7 + SG_ MO_Getriebe_kuehlen : 47|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ MO_Mom_Traegheit_02 : 48|5@1+ (0.01,0) [0.00|0.31] "Unit_KiloGramMeterSquar" Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ MO_Heizungspumpenansteuerung : 53|4@1+ (10,0) [0|100] "Unit_PerCent" Gateway_D4C7 + SG_ MO_SpannungsAnf : 57|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ MO_Nachlaufzeit_Heizungspumpe : 58|6@1+ (15,0) [0|945] "Unit_Secon" Gateway_D4C7 + +BO_ 1607 Motor_09: 8 Motor_EDC17_D4 + SG_ MO_ITM_Kuehlmittel_Temp : 0|8@1+ (0.75,-48) [-45.75|143.25] "Unit_DegreCelsi" Gateway_D4C7 + SG_ MO_E85_Sensor : 8|4@1+ (10,0) [0|100] "Unit_PerCent" Gateway_D4C7 + SG_ SCR_Anz_Motorstarts : 12|4@1+ (1,0) [0|8] "" Gateway_D4C7 + SG_ SCR_Reichweite : 16|15@1+ (1,0) [0|32766] "" Gateway_D4C7 + SG_ SCR_Warnstufe_1 : 32|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ SCR_Warnstufe_2 : 33|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ SCR_Text : 34|3@1+ (1.0,0.0) [0.0|7] "" Gateway_D4C7 + SG_ SCR_Akustik : 37|2@1+ (1.0,0.0) [0.0|3] "" Gateway_D4C7 + SG_ MO_Kraftstofffilter_Wasser : 40|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ SCR_Systemfehler : 41|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ SCR_Inducement_Strategie : 42|2@1+ (1.0,0.0) [0.0|3] "" Gateway_D4C7 + SG_ MO_CO2_Faktor : 44|12@1+ (1,0) [1|4094] "Unit_GramPerLiter" Gateway_D4C7 + SG_ MO_MKB_MUX M : 56|2@1+ (1.0,0.0) [0.0|3] "" Gateway_D4C7 + SG_ MO_MKB_01 m0 : 59|5@1+ (1.0,0.0) [0.0|31] "" Gateway_D4C7 + SG_ MO_MKB_02 m1 : 59|5@1+ (1.0,0.0) [0.0|31] "" Gateway_D4C7 + SG_ MO_MKB_03 m2 : 59|5@1+ (1.0,0.0) [0.0|31] "" Gateway_D4C7 + SG_ MO_MKB_04 m3 : 59|5@1+ (1.0,0.0) [0.0|31] "" Gateway_D4C7 + +BO_ 276 Motor_10: 8 Motor_EDC17_D4 + SG_ Motor_10_CHK : 0|8@1+ (1,0) [0|255] "" Gateway_D4C7 + SG_ Motor_10_BZ : 8|4@1+ (1,0) [0|15] "" Gateway_D4C7 + SG_ MO_Sig_Fahrpedalgradient : 12|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ MO_BKV_Unterdruckwarnung : 13|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ MO_Zylinderabschaltung : 14|2@1+ (1.0,0.0) [0.0|3] "" Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7 + SG_ MO_Fahrpedalgradient : 16|8@1+ (25,0) [0|6350] "Unit_PerCentPerSecon" Gateway_D4C7 + SG_ MO_Schubabschaltung : 24|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ MO_rel_Saugrohrdruck : 25|6@1+ (18,0) [0|1116] "Unit_MilliBar" Gateway_D4C7 + SG_ MO_rel_Saugrohrdruck_gem_err : 31|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ MO_BKV_Unterdruck : 32|8@1+ (4,0) [0|1012] "Unit_MilliBar" Gateway_D4C7 + +BO_ 1648 Motor_18: 8 Motor_EDC17_D4 + SG_ MO_Anzahl_Abgesch_Zyl : 47|3@1+ (1.0,0.0) [0.0|7] "" Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7 + SG_ MO_Zylabsch_Texte : 50|2@1+ (1.0,0.0) [0.0|3] "" Gateway_D4C7 + SG_ MO_E85_BS_Texte : 52|3@1+ (1.0,0.0) [0.0|7] "" Gateway_D4C7 + SG_ MO_Drehzahl_Warnung : 55|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ MO_obere_Drehzahlgrenze : 56|8@1+ (50,0) [50|12750] "Unit_MinutInver" Gateway_D4C7 + +BO_ 1010 Motor_19: 8 Motor_EDC17_D4 + SG_ Motor_19_BZ : 8|4@1+ (1,0) [0|15] "" SCR_C7 + SG_ MO_SCR_Tankheizung : 43|1@1+ (1.0,0.0) [0.0|1] "" SCR_C7 + SG_ MO_SCR_Dosierpumpe_Zustand : 44|3@1+ (1.0,0.0) [0.0|7] "" SCR_C7 + SG_ MO_SCR_Leitungsheizung : 47|1@1+ (1.0,0.0) [0.0|1] "" SCR_C7 + SG_ MO_SCR_Dosierpumpe_Wartezeit : 48|7@1+ (1,0) [0|120] "Unit_Secon" SCR_C7 + SG_ MO_SCR_Transferpumpe : 55|1@1+ (1.0,0.0) [0.0|1] "" SCR_C7 + SG_ MO_SCR_Dosierpumpe_Soll : 56|8@1+ (0.4,0) [0.0|100.0] "Unit_PerCent" SCR_C7 + +BO_ 1601 Motor_Code_01: 8 Motor_EDC17_D4 + SG_ Motor_Code_01_CHK : 0|8@1+ (1,0) [0|255] "" Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ Motor_Code_01_BZ : 8|4@1+ (1,0) [0|15] "" Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ MO_Faktor_Momente : 12|2@1+ (1.0,0.0) [0.0|3] "" EPB_D4,Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ MO_Hybridfahrzeug : 14|2@1+ (1.0,0.0) [0.0|3] "" Gateway_D4C7 + SG_ MO_Code : 16|8@1+ (1,0) [0|255] "" EPB_D4,Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,SAK_C7 + SG_ MO_Getriebe_Code : 24|6@1+ (1.0,0.0) [0.0|63] "" EPB_D4,Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ MO_StartStopp_Codiert : 30|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ MO_Anzahl_Zyl : 32|4@1+ (1,0) [0|15] "" Gateway_D4C7 + SG_ MO_Kraftstoffart : 36|4@1+ (1.0,0.0) [0.0|15] "" EPB_D4,Gateway_D4C7 + SG_ MO_Hubraum : 40|7@1+ (0.1,0) [0.0|12.7] "Unit_Liter" Gateway_D4C7 + SG_ MO_Ansaugsystem : 47|1@1+ (1.0,0.0) [0.0|1] "" EPB_D4,Gateway_D4C7 + SG_ MO_Leistung : 48|9@1+ (1,0) [0|511] "Unit_KiloWatt" Gateway_D4C7 + SG_ MO_Abgastyp : 57|6@1+ (1.0,0.0) [0.0|63] "" Gateway_D4C7,Getriebe_AL551_951_D4_C7 + SG_ MO_Einspritzart : 63|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + +BO_ 969 MotorSlave_01: 1 Motor_Slave_D4 + SG_ MOS_KD_Fehler : 0|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + +BO_ 1696 NightVision_01: 8 Gateway_D4C7 + SG_ NV_aktiv : 12|1@1+ (1.0,0.0) [0.0|1] "" Airbag_D4 + SG_ NV_Texte : 13|3@1+ (1.0,0.0) [0.0|7] "" Vector__XXX + SG_ NV_Gong : 16|2@1+ (1.0,0.0) [0.0|3] "" Airbag_D4 + SG_ NV_Symbol : 18|1@1+ (1.0,0.0) [0.0|1] "" Airbag_D4 + SG_ NV_Hinweise : 19|2@1+ (1.0,0.0) [0.0|3] "" Vector__XXX + SG_ NV_Piktogramm_aktiv : 21|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NV_Akustik_deaktiviert_Icon : 22|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NV_FGM_deaktiviert_Icon : 23|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NV_KD_Fehler : 63|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + +BO_ 1753 NMH_EPB: 7 EPB_D4 + SG_ NMH_EPB_Start_1 : 0|1@1+ (1.0,0.0) [0.0|1] "" EPB_D4,Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4,Motor_Slave_D4,SCR_C7 + SG_ NMH_EPB_Start_2 : 1|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_EPB_Normal_Mode_1 : 2|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_EPB_Normal_Mode_2 : 3|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_EPB_Car_WakeUp : 6|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_EPB_Per_WakeUp : 8|5@1+ (1.0,0.0) [0.0|31] "" Vector__XXX + SG_ NMH_EPB_Fkt_WakeUp : 13|3@1+ (1.0,0.0) [0.0|7] "" Vector__XXX + SG_ NMH_EPB_NM_aktiv_Klemme_15 : 16|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_EPB_NM_aktiv_Diagnose : 17|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_EPB_NM_aktiv_Start : 18|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_EPB_NM_aktiv_Schalter : 19|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_EPB_NM_aktiv_Bedarf_Anzeige : 20|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_EPB_NM_aktiv_v_groesser_Null : 21|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_EPB_kein_NL : 24|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_EPB_NL_Temp_Modell : 25|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_EPB_NL_Min : 26|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_EPB_NL_AutoAdjust : 27|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NM_EPB_Signalfehler : 32|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_EPB_TimeOut_Fehler : 33|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_EPB_CAN_Diag_deaktiv : 34|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_EPB_KompSchutz : 35|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_EPB_Mute_Mode : 36|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_EPB_Transport_Mode : 37|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_EPB_Abschaltstufe_aktiv : 38|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_EPB_Eindraht_Fehler : 39|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_EPB_Lokalaktiv : 48|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_EPB_Subsystemaktiv : 49|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + +BO_ 1728 NMH_Gateway: 7 Gateway_D4C7 + SG_ NMH_GW_Start_1 : 0|1@1+ (1.0,0.0) [0.0|1] "" EPB_D4,Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4,Motor_Slave_D4,SCR_C7 + SG_ NMH_GW_Start_2 : 1|1@1+ (1.0,0.0) [0.0|1] "" EPB_D4,Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4,Motor_Slave_D4,SCR_C7 + SG_ NMH_GW_Normal_Mode_1 : 2|1@1+ (1.0,0.0) [0.0|1] "" EPB_D4,Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4,Motor_Slave_D4,SCR_C7 + SG_ NMH_GW_Normal_Mode_2 : 3|1@1+ (1.0,0.0) [0.0|1] "" EPB_D4,Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4,Motor_Slave_D4,SCR_C7 + SG_ NMH_GW_Car_WakeUp : 6|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_GW_Per_WakeUp : 8|5@1+ (1.0,0.0) [0.0|31] "" Vector__XXX + SG_ NMH_GW_Fkt_WakeUp : 13|3@1+ (1.0,0.0) [0.0|7] "" Vector__XXX + SG_ NMH_GW_NM_aktiv_Klemme_15 : 16|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_GW_NM_aktiv_Diagnose : 17|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_GW_NM_aktiv_Start : 18|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_GW_NM_aktiv_BDM : 19|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_GW_NM_aktiv_Warnblinken : 20|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_GW_NM_aktiv_ESP : 21|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_GW_Abschaltstufe_3 : 24|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_GW_SG_Fehlerdauer : 25|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_GW_STH_Wakeup : 26|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_GW_NL_Diagnose : 27|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NM_GW_Signalfehler : 32|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_GW_TimeOut_Fehler : 33|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_GW_CAN_Diag_deaktiv : 34|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_GW_KompSchutz : 35|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_GW_Mute_Mode : 36|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_GW_Transport_Mode : 37|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_GW_Abschaltstufe_aktiv : 38|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_GW_Eindraht_Fehler : 39|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_GW_ACAN : 40|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_GW_KombiCAN : 41|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_GW_KomfortCAN : 42|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_GW_Infotainment : 43|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_GW_Fahrwerk : 44|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_GW_WakeUp_CAN_Bus : 45|3@1+ (1.0,0.0) [0.0|7] "" Vector__XXX + +BO_ 1730 NMH_Getriebe: 7 Getriebe_AL551_951_D4_C7 + SG_ NMH_GE_Start_1 : 0|1@1+ (1.0,0.0) [0.0|1] "" EPB_D4,Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4,Motor_Slave_D4,SCR_C7 + SG_ NMH_GE_Start_2 : 1|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_GE_Normal_Mode_1 : 2|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_GE_Normal_Mode_2 : 3|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_GE_Car_WakeUp : 6|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_GE_Per_WakeUp : 8|5@1+ (1.0,0.0) [0.0|31] "" Vector__XXX + SG_ NMH_GE_Fkt_WakeUp : 13|3@1+ (1.0,0.0) [0.0|7] "" Vector__XXX + SG_ NMH_GE_NM_aktiv_Klemme_15 : 16|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_GE_NM_aktiv_Diagnose : 17|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_GE_NM_aktiv_Start : 18|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_GE_N_Haltephase : 19|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_GE_kein_NL : 24|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_GE_NL_Daten_EEPROM : 25|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_GE_NL_Drucksens : 26|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_GE_NL_Abtrieb : 27|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_GE_NL_Waehlhebel : 28|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_GE_NL_Wegfahrsperre : 29|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NM_GE_Signalfehler : 32|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_GE_TimeOut_Fehler : 33|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_GE_CAN_Diag_deaktiv : 34|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_GE_KompSchutz : 35|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_GE_Mute_Mode : 36|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_GE_Transport_Mode : 37|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_GE_Abschaltstufe_aktiv : 38|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_GE_Eindraht_Fehler : 39|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_GE_Lokalaktiv : 48|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_GE_Subsystemaktiv : 49|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_GSG_Subbusaktiv : 50|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + +BO_ 1729 NMH_Motor: 7 Motor_EDC17_D4 + SG_ NMH_MO_Start_1 : 0|1@1+ (1.0,0.0) [0.0|1] "" EPB_D4,Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4,Motor_Slave_D4,SCR_C7 + SG_ NMH_MO_Start_2 : 1|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_MO_Normal_Mode_1 : 2|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_MO_Normal_Mode_2 : 3|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_MO_Car_WakeUp : 6|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_MO_Per_WakeUp : 8|5@1+ (1.0,0.0) [0.0|31] "" Vector__XXX + SG_ NMH_MO_Fkt_WakeUp : 13|3@1+ (1.0,0.0) [0.0|7] "" Vector__XXX + SG_ NMH_MO_NM_aktiv_Klemme_15 : 16|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_MO_NM_aktiv_Diagnose : 17|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_MO_NM_aktiv_Start : 18|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_MO_NM_aktiv_EKP_Vorlauf : 19|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_MO_NM_aktiv_STH_Betrieb : 20|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_MO_NM_aktiv_HV_Abschaltung : 21|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_MO_kein_NL : 24|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_MO_NL_Kuehlerluefter : 25|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_MO_NL_Diagnose : 26|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_MO_NL_WFS : 27|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_MO_NL_EEPROM : 28|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_MO_NL_Sonstige : 29|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NM_MO_Signalfehler : 32|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_MO_TimeOut_Fehler : 33|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_MO_CAN_Diag_deaktiv : 34|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_MO_KompSchutz : 35|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_MO_Mute_Mode : 36|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_MO_Transport_Mode : 37|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_MO_Abschaltstufe_aktiv : 38|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_MO_Eindraht_Fehler : 39|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_MO_Lokalaktiv : 48|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_MO_Subsystemaktiv : 49|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + +BO_ 1736 NMH_Motor_Slave: 7 Motor_Slave_D4 + SG_ NMH_MO_SL_Start_1 : 0|1@1+ (1.0,0.0) [0.0|1] "" EPB_D4,Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4,Motor_Slave_D4,SCR_C7 + SG_ NMH_MO_SL_Start_2 : 1|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_MO_SL_Normal_Mode_1 : 2|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_MO_SL_Normal_Mode_2 : 3|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_MO_SL_Car_WakeUp : 6|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_MO_SL_Per_WakeUp : 8|5@1+ (1.0,0.0) [0.0|31] "" Vector__XXX + SG_ NMH_MO_SL_Fkt_WakeUp : 13|3@1+ (1.0,0.0) [0.0|7] "" Vector__XXX + SG_ NMH_MO_SL_TimeOut_Fehler : 33|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_MO_SL_CAN_Diag_deaktiv : 34|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_MO_SL_KompSchutz : 35|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_MO_SL_Mute_Mode : 36|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_MO_SL_Transport_Mode : 37|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_MO_SL_Abschaltstufe_aktiv : 38|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_MO_SL_Busfehler : 39|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_MO_Sl_Lokalaktiv : 48|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_MO_SL_Subsystemaktiv : 49|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + +BO_ 1782 NMH_SCR: 7 SCR_C7 + SG_ NMH_SCR_Start_1 : 0|1@1+ (1.0,0.0) [0.0|1] "" EPB_D4,Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4,Motor_Slave_D4,SCR_C7 + SG_ NMH_SCR_Start_2 : 1|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_SCR_Normal_Mode_1 : 2|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_SCR_Normal_Mode_2 : 3|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_SCR_Car_WakeUp : 6|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_SCR_Per_WakeUp : 8|5@1+ (1.0,0.0) [0.0|31] "" Vector__XXX + SG_ NMH_SCR_Fkt_WakeUp : 13|3@1+ (1.0,0.0) [0.0|7] "" Vector__XXX + SG_ NMH_SCR_Klemme_15 : 16|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_SCR_Diagnose : 17|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_SCR_MindestAktivZeit : 18|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_SCR_NL_Datem_EEPROM : 24|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_SCR_Signalfehler : 32|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_SCR_TimeOut_Fehler : 33|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_SCR_CAN_Diag_deaktiv : 34|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_SCR_KompSchutz : 35|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_SCR_Mute_Mode : 36|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_SCR_Transport_Mode : 37|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_SCR_Abschaltstufe_aktiv : 38|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_SCR_Busfehler : 39|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_SCR_Lokalaktiv : 48|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ NMH_SCR_Subsystemaktiv : 49|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + +BO_ 913 OBD_01: 8 Motor_EDC17_D4 + SG_ OBD_Calc_Load_Val : 0|8@1+ (0.39215686274509803,0) [0E-17|99.99999999999999765] "Unit_PerCent" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ OBD_Eng_Cool_Temp : 8|8@1+ (1,-40) [-40|215] "Unit_DegreCelsi" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ OBD_Abs_Throttle_Pos : 16|8@1+ (0.39215686274509803,0) [0E-17|99.99999999999999765] "Unit_PerCent" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ OBD_Abs_Load_Val : 24|16@1+ (0.39215686274509803,0) [0E-17|25699.99999999999939605] "Unit_PerCent" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ OBD_Abs_Pedal_Pos : 40|8@1+ (0.39215686274509803,0) [0E-17|99.99999999999999765] "Unit_PerCent" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ OBD_Kaltstart_Denominator : 59|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ OBD_Minimum_Trip : 60|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ OBD_Driving_Cycle : 61|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,SCR_C7 + SG_ OBD_Warm_Up_Cycle : 62|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,SCR_C7 + SG_ OBD_Normed_Trip : 63|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7,SCR_C7 + +BO_ 803 PCF_01: 8 Gateway_D4C7 + SG_ PCF_01_CRC : 0|8@1+ (1,0) [0|255] "" Airbag_D4 + SG_ PCF_01_BZ : 8|4@1+ (1,0) [0|15] "" Airbag_D4 + SG_ PCF_Objektstatus : 12|3@1+ (1.0,0.0) [0.0|7] "" Airbag_D4 + SG_ PCF_Fahrer_aktiv_erkannt : 15|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ PCF_Time_to_collision : 16|8@1+ (0.01,0) [0.00|2.50] "Unit_Secon" Airbag_D4 + SG_ PCF_v_rel : 24|7@1+ (0.5,0) [0.5|63.5] "Unit_MeterPerSecon" Airbag_D4 + SG_ PCF_dy_Kollisionsueberdeckung : 31|5@1+ (0.1,0) [0.1|2.9] "Unit_Meter" Vector__XXX + +BO_ 802 PCR_01: 8 Gateway_D4C7 + SG_ PCR_Sensorstatus : 12|1@1+ (1.0,0.0) [0.0|1] "" Airbag_D4 + SG_ PCR_Obj_vx_rel : 13|11@1+ (0.1,-102.3) [-102.3|102.3] "Unit_MeterPerSecon" Airbag_D4 + SG_ PCR_Obj_vy_rel : 24|11@1+ (0.1,-102.3) [-102.3|102.3] "Unit_MeterPerSecon" Airbag_D4 + SG_ PCR_Obj_TTC : 35|9@1+ (0.01,0) [0.00|5.10] "Unit_Secon" Airbag_D4 + SG_ PCR_Obj_Guete : 44|7@1+ (1,0) [0|100] "Unit_PerCent" Airbag_D4 + SG_ PCR_Crashwahrscheinlichkeit : 51|7@1+ (1,0) [0|100] "Unit_PerCent" Airbag_D4 + +BO_ 929 PSD_01: 8 Gateway_D4C7 + SG_ PSD_Pos_Segment_ID : 0|6@1+ (1,0) [2|63] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Pos_Segmentlaenge : 6|7@1+ (2,0) [0|254] "Unit_Meter" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Pos_Inhibitzeit : 13|5@1+ (10,0) [0|310] "Unit_MilliSecon" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Pos_Standort : 18|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Pos_Laengsfehler : 19|3@1+ (1.0,0.0) [0.0|7] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Segment_ID : 22|6@1+ (1,0) [2|63] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Vorgaenger_Segment_ID : 28|6@1+ (1,0) [2|63] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Strassenklasse : 34|2@1+ (1.0,0.0) [0.0|3] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Segmentlaenge : 36|7@1+ (2,0) [0|254] "Unit_Meter" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Rampe : 43|2@1+ (1.0,0.0) [0.0|3] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Endkruemmung : 45|8@1+ (1,0) [0|254] "Unit_None" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Endkruemmung_Vorz : 53|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Endsteigung : 54|5@1+ (0.5,0) [0.0|14.5] "Unit_PerCent" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Endsteigung_Vorz : 59|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_ADAS_Qualitaet : 60|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Fahrspuren : 61|2@1+ (1.0,0.0) [0.0|3] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_wahrscheinlichster_Pfad : 63|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + +BO_ 930 PSD_02: 8 Gateway_D4C7 + SG_ PSD_Multiplex M : 0|2@1+ (1.0,0.0) [0.0|3] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Sys_Segment_ID m0 : 2|6@1+ (1,0) [2|63] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Abz_Segment_ID m1 : 2|6@1+ (1,0) [2|63] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Ges_Segment_ID m2 : 2|6@1+ (1,0) [2|63] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Ort_Laenge_VZ m3 : 2|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Ort_Laenge m3 : 3|25@1+ (0.00001,0) [0.00000|180.00000] "Unit_DegreOfArc" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Sys_Laendercode m0 : 8|8@1+ (1.0,0.0) [0.0|255] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Abz_Segmentlaenge m1 : 8|7@1+ (2,0) [0|254] "Unit_Meter" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Ges_Geschwindigkeit m2 : 8|5@1+ (1.0,0.0) [0.0|31] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Ges_Geschwindigkeit_Typ m2 : 13|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Ges_Geschwindigkeit_Gespann m2 : 14|2@1+ (1.0,0.0) [0.0|3] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Abz_Vorgaenger_Segment_ID m1 : 15|6@1+ (1,0) [2|63] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Sys_Geschwindigkeit_Einheit m0 : 16|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Ges_Geschwindigkeit_Witter m2 : 16|2@1+ (1.0,0.0) [0.0|3] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Sys_Verkehrsrichtung m0 : 17|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Sys_Release_Monat m0 : 18|4@1+ (1,0) [1|12] "Unit_Month" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Ges_Geschwindigkeit_Tag_Anf m2 : 18|3@1+ (1.0,0.0) [0.0|7] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Abz_Geschwindigkeit m1 : 21|5@1+ (1.0,0.0) [0.0|31] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Ges_Geschwindigkeit_Tag_Ende m2 : 21|3@1+ (1.0,0.0) [0.0|7] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Sys_Release_Jahr m0 : 22|5@1+ (1,2000) [2000|2031] "Unit_Year" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Ges_Geschwindigkeit_Std_Anf m2 : 24|5@1+ (1,0) [0|24] "Unit_Hours" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Abz_Geschwindigkeit_Typ m1 : 26|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Sys_Tunnel m0 : 27|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Abz_Strassenklasse m1 : 27|2@1+ (1.0,0.0) [0.0|3] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Sys_Bruecke m0 : 28|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Ort_Breite_VZ m3 : 28|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Sys_Fahrsp_Gegenr m0 : 29|2@1+ (1.0,0.0) [0.0|3] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Abz_ADAS_Qualitaet m1 : 29|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Ges_Geschwindigkeit_Std_Ende m2 : 29|5@1+ (1,0) [0|24] "Unit_Hours" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Ort_Breite m3 : 29|24@1+ (0.00001,0) [0.00000|90.00000] "Unit_DegreOfArc" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Abz_Abzweigerichtung m1 : 30|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Sys_TMC_Baustelle m0 : 31|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Abz_Abzweigewinkel m1 : 31|4@1+ (1.0,0.0) [0.0|15] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Sys_TMC_Stau m0 : 32|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Ges_alter_Geschw m2 : 34|5@1+ (1.0,0.0) [0.0|31] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Abz_Rampe m1 : 35|2@1+ (1.0,0.0) [0.0|3] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Abz_Anfangskruemmung m1 : 37|8@1+ (1,0) [0|254] "Unit_None" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Ges_alter_Geschw_Gespann m2 : 39|2@1+ (1.0,0.0) [0.0|3] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Ges_alter_Geschw_Witter m2 : 41|2@1+ (1.0,0.0) [0.0|3] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Ges_alter_Geschw_Tag_Anf m2 : 43|3@1+ (1.0,0.0) [0.0|7] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Abz_Anfangskruemmung_Vorz m1 : 45|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Sys_Anfangskruemmung m0 : 46|8@1+ (1,0) [0|254] "Unit_None" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Abz_Endkruemmung m1 : 46|8@1+ (1,0) [0|254] "Unit_None" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Ges_alter_Geschw_Tag_Ende m2 : 46|3@1+ (1.0,0.0) [0.0|7] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Ges_alter_Geschw_Std_Anf m2 : 49|5@1+ (1,0) [0|24] "Unit_Hours" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Ort_Hoehe m3 : 53|11@1+ (5,-1000) [-1000|8000] "Unit_Meter" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Sys_Anfangskruemmung_Vorz m0 : 54|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Abz_Endkruemmung_Vorz m1 : 54|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Ges_alter_Geschw_Std_Ende m2 : 54|5@1+ (1,0) [0|24] "Unit_Hours" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Sys_Anfangssteigung m0 : 55|5@1+ (0.5,0) [0.0|14.5] "Unit_PerCent" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Abz_Endsteigung m1 : 55|5@1+ (0.5,0) [0.0|14.5] "Unit_PerCent" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Ges_Ueberholverbot m2 : 59|2@1+ (1.0,0.0) [0.0|3] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Sys_Anfangssteigung_Vorz m0 : 60|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Abz_Endsteigung_Vorz m1 : 60|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Sys_Ortschaft m0 : 61|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Abz_Fahrspuren m1 : 61|2@1+ (1.0,0.0) [0.0|3] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Ges_Wechselverkehrszeichen m2 : 61|3@1+ (1.0,0.0) [0.0|7] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Sys_Digitalisierung m0 : 62|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Sys_Zielfuehrung m0 : 63|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ PSD_Abz_wahrscheinlichster_Pfad m1 : 63|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + +BO_ 2033 Request_Airbag_Deployment: 8 Gateway_D4C7 + SG_ Request_Airbag_Deployment : 0|64@1+ (1.0,0.0) [0.0|18446744073709551615] "" Airbag_D4 + +BO_ 2041 Response_Airbag_Deployment: 8 Airbag_D4 + SG_ Response_Airbag_Deployment : 0|64@1+ (1.0,0.0) [0.0|18446744073709551615] "" Gateway_D4C7 + +BO_ 1528 SAK_01: 8 SAK_C7 + SG_ SAK_Charisma_FahrPr : 16|3@1+ (1.0,0.0) [0.0|7] "" Vector__XXX + SG_ SAK_Charisma_Status : 19|2@1+ (1.0,0.0) [0.0|3] "" Vector__XXX + SG_ SAK_Charisma_Umschaltung : 21|2@1+ (1.0,0.0) [0.0|3] "" Vector__XXX + SG_ SAK_KD_Fehler : 23|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + +BO_ 1011 SCR_01: 8 SCR_C7 + SG_ SCR_01_BZ : 8|4@1+ (1,0) [0|15] "" Motor_EDC17_D4 + SG_ SCR_Dosierpumpe_Drehzahl : 23|11@1+ (4,-4080) [-4080|4100] "Unit_MinutInver" Motor_EDC17_D4 + SG_ SCR_Druck : 34|10@1+ (5,0) [0|5000] "Unit_MilliVolt" Motor_EDC17_D4 + SG_ SCR_Level_Aktivtank : 44|10@1+ (5,0) [0|5000] "Unit_MilliVolt" Motor_EDC17_D4 + SG_ SCR_Level_Passivtank : 54|10@1+ (5,0) [0|5000] "Unit_MilliVolt" Motor_EDC17_D4 + +BO_ 1507 SCR_02: 8 SCR_C7 + SG_ SCR_Heizkreis_3_Strom : 0|8@1+ (0.1,0) [0.0|14.0] "Unit_Amper" Motor_EDC17_D4 + SG_ SCR_02_BZ : 8|4@1+ (1,0) [0|15] "" Motor_EDC17_D4 + SG_ SCR_KD_Fehler : 13|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ SCR_Guetesensor : 14|10@1+ (5,0) [0|5000] "Unit_MilliVolt" Motor_EDC17_D4 + SG_ SCR_Temp_Aktivtank : 24|8@1+ (20,0) [0|5000] "Unit_MilliVolt" Motor_EDC17_D4 + SG_ SCR_Temp_Passivtank : 32|8@1+ (20,0) [0|5000] "Unit_MilliVolt" Motor_EDC17_D4 + SG_ SCR_Leitungsheizung_Strom : 40|8@1+ (0.1,0) [0.0|14.0] "Unit_Amper" Motor_EDC17_D4 + SG_ SCR_Transferpumpe_Strom : 48|8@1+ (0.1,0) [0.0|14.0] "Unit_Amper" Motor_EDC17_D4 + SG_ SCR_Tankheizung_Strom : 56|8@1+ (0.1,0) [0.0|14.0] "Unit_Amper" Motor_EDC17_D4 + +BO_ 1508 SCR_03: 8 SCR_C7 + SG_ SCR_03_BZ : 8|4@1+ (1,0) [0|15] "" Motor_EDC17_D4 + SG_ SCR_Spannungsversorgung_Status : 12|4@1+ (1.0,0.0) [0.0|15] "" Motor_EDC17_D4 + SG_ SCR_VersorgungSensoren_Status : 16|4@1+ (1.0,0.0) [0.0|15] "" Motor_EDC17_D4 + SG_ SCR_Heizkreis_3_Status : 20|4@1+ (1.0,0.0) [0.0|15] "" Motor_EDC17_D4 + SG_ SCR_Guetesensor_Status : 24|4@1+ (1.0,0.0) [0.0|15] "" Motor_EDC17_D4 + SG_ SCR_Leitungsheizung_Status : 28|4@1+ (1.0,0.0) [0.0|15] "" Motor_EDC17_D4 + SG_ SCR_Tankheizung_Status : 32|4@1+ (1.0,0.0) [0.0|15] "" Motor_EDC17_D4 + SG_ SCR_Druck_Status : 36|4@1+ (1.0,0.0) [0.0|15] "" Motor_EDC17_D4 + SG_ SCR_Dosierpumpe_Status_Spule : 40|4@1+ (1.0,0.0) [0.0|15] "" Motor_EDC17_D4 + SG_ SCR_Transferpumpe_Status : 44|4@1+ (1.0,0.0) [0.0|15] "" Motor_EDC17_D4 + SG_ SCR_Level_Aktivtank_Status : 48|4@1+ (1.0,0.0) [0.0|15] "" Motor_EDC17_D4 + SG_ SCR_Level_Passivtank_Status : 52|4@1+ (1.0,0.0) [0.0|15] "" Motor_EDC17_D4 + SG_ SCR_Temp_Aktivtank_Status : 56|4@1+ (1.0,0.0) [0.0|15] "" Motor_EDC17_D4 + SG_ SCR_Temp_Passivtank_Status : 60|4@1+ (1.0,0.0) [0.0|15] "" Motor_EDC17_D4 + +BO_ 1509 SCR_04: 8 SCR_C7 + SG_ SCR_04_BZ : 8|4@1+ (1,0) [0|15] "" Motor_EDC17_D4 + SG_ SCR_Ansteuerung_Transferpumpe : 12|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4 + SG_ SCR_Ansteuerung_Dosierpumpe : 13|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4 + SG_ SCR_Ansteuerung_Heizkreis_3 : 14|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4 + SG_ SCR_Ansteuerung_Leitungsheizung : 15|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4 + SG_ SCR_Ansteuerung_Tankheizung : 16|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4 + SG_ SCR_CAL_CVN_CRC_32 : 32|32@1+ (1.0,0.0) [0.0|4294967295] "" Motor_EDC17_D4 + +BO_ 1526 SCR_05: 8 SCR_C7 + SG_ SCR_05_BZ : 8|4@1+ (1,0) [0|15] "" Motor_EDC17_D4 + SG_ SCR_Steuergeraet_Heizung_Status : 48|2@1+ (1.0,0.0) [0.0|3] "" Motor_EDC17_D4 + SG_ SCR_Steuergeraet_Pumpe_Status : 50|2@1+ (1.0,0.0) [0.0|3] "" Motor_EDC17_D4 + SG_ SCR_Steuergeraet_Relais_Status : 52|2@1+ (1.0,0.0) [0.0|3] "" Motor_EDC17_D4 + SG_ SCR_Steuergeraet_Bus_Status : 56|2@1+ (1.0,0.0) [0.0|3] "" Motor_EDC17_D4 + SG_ SCR_Steuergeraet_Codierung_St000 : 58|2@1+ (1.0,0.0) [0.0|3] "" Motor_EDC17_D4 + SG_ SCR_Steuergeraet_Datensatz_St001 : 60|2@1+ (1.0,0.0) [0.0|3] "" Motor_EDC17_D4 + SG_ SCR_Steuergeraet_Defekt_Status : 62|2@1+ (1.0,0.0) [0.0|3] "" Motor_EDC17_D4 + +BO_ 1510 SCR_CAL_ID1: 8 SCR_C7 + SG_ SCR_CAL_ID_Name_01 : 0|8@1+ (1.0,0.0) [0.0|255] "" Motor_EDC17_D4 + SG_ SCR_CAL_ID_Name_02 : 8|8@1+ (1.0,0.0) [0.0|255] "" Motor_EDC17_D4 + SG_ SCR_CAL_ID_Name_03 : 16|8@1+ (1.0,0.0) [0.0|255] "" Motor_EDC17_D4 + SG_ SCR_CAL_ID_TN_01 : 24|8@1+ (1.0,0.0) [0.0|255] "" Motor_EDC17_D4 + SG_ SCR_CAL_ID_TN_02 : 32|8@1+ (1.0,0.0) [0.0|255] "" Motor_EDC17_D4 + SG_ SCR_CAL_ID_TN_03 : 40|8@1+ (1.0,0.0) [0.0|255] "" Motor_EDC17_D4 + SG_ SCR_CAL_ID_TN_04 : 48|8@1+ (1.0,0.0) [0.0|255] "" Motor_EDC17_D4 + SG_ SCR_CAL_ID_TN_05 : 56|8@1+ (1.0,0.0) [0.0|255] "" Motor_EDC17_D4 + +BO_ 1512 SCR_CAL_ID2: 8 SCR_C7 + SG_ SCR_CAL_ID_TN_06 : 0|8@1+ (1.0,0.0) [0.0|255] "" Motor_EDC17_D4 + SG_ SCR_CAL_ID_TN_07 : 8|8@1+ (1.0,0.0) [0.0|255] "" Motor_EDC17_D4 + SG_ SCR_CAL_ID_TN_08 : 16|8@1+ (1.0,0.0) [0.0|255] "" Motor_EDC17_D4 + SG_ SCR_CAL_ID_Leer : 24|8@1+ (1.0,0.0) [0.0|255] "" Motor_EDC17_D4 + SG_ SCR_CAL_ID_Index_01 : 32|8@1+ (1.0,0.0) [0.0|255] "" Motor_EDC17_D4 + SG_ SCR_CAL_ID_Index_02 : 40|8@1+ (1.0,0.0) [0.0|255] "" Motor_EDC17_D4 + SG_ SCR_CAL_ID_Index_03 : 48|8@1+ (1.0,0.0) [0.0|255] "" Motor_EDC17_D4 + SG_ SCR_CAL_ID_Index_04 : 56|8@1+ (1.0,0.0) [0.0|255] "" Motor_EDC17_D4 + +BO_ 133 SCU_01: 8 SCU_D4 + SG_ SCU_01_CHK : 0|8@1+ (1,0) [0|255] "" Airbag_D4,ESP_D4,Gateway_D4C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4,QSP_D4 + SG_ SCU_01_BZ : 8|4@1+ (1,0) [0|15] "" Airbag_D4,ESP_D4,Gateway_D4C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4,QSP_D4 + SG_ SCU_Ue_Winkel_ADS : 16|12@1+ (0.1,0) [0.0|409.3] "Unit_DegreOfArc" Airbag_D4,ESP_D4,Gateway_D4C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4,QSP_D4 + SG_ SCU_VZ_Ue_Winkel_ADS : 28|1@1+ (1.0,0.0) [0.0|1] "" Airbag_D4,ESP_D4,Gateway_D4C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4,QSP_D4 + SG_ SCU_Soll_Ue_Winkel : 29|11@1+ (0.1,0) [0.0|204.5] "Unit_DegreOfArc" ESP_D4,Gateway_D4C7,QSP_D4 + SG_ SCU_max_Gradient : 40|9@1+ (1,0) [0|510] "" ESP_D4,Gateway_D4C7,QSP_D4 + SG_ SCU_VZ_Soll_Ue_Winkel : 49|1@1+ (1.0,0.0) [0.0|1] "" ESP_D4,Gateway_D4C7,QSP_D4 + SG_ SCU_Status : 50|3@1+ (1.0,0.0) [0.0|7] "" ESP_D4,Gateway_D4C7,QSP_D4 + SG_ SCU_KD_Fehler : 53|1@1+ (1.0,0.0) [0.0|1] "" ESP_D4,Gateway_D4C7,QSP_D4 + SG_ SCU_01_CRC : 56|8@1+ (1,0) [0|255] "" ESP_D4,Gateway_D4C7,QSP_D4 + +BO_ 784 SCU_02: 8 SCU_D4 + SG_ SCU_Warnlampe : 12|2@1+ (1.0,0.0) [0.0|3] "" Gateway_D4C7 + SG_ SCU_Warnungen : 14|2@1+ (1.0,0.0) [0.0|3] "" Gateway_D4C7 + SG_ SCU_Charisma_FahrPr : 16|3@1+ (1.0,0.0) [0.0|7] "" Gateway_D4C7 + SG_ SCU_Charisma_Status : 19|2@1+ (1.0,0.0) [0.0|3] "" Gateway_D4C7 + SG_ SCU_Charisma_Umschaltung : 21|2@1+ (1.0,0.0) [0.0|3] "" Gateway_D4C7 + +BO_ 1313 STH_01: 8 Gateway_D4C7 + SG_ STH_Funk_ein : 0|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ STH_Funk_aus : 1|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ STH_Zusatzheizung : 2|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ STH_LED : 3|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ STH_Pumpe_ein : 4|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ STH_Geblaese : 5|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ STH_EKP_Anst : 6|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ STH_Start_folgt : 7|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ STH_Ventiloeffnungszeit : 8|6@1+ (1,0) [0|63] "Unit_Minut" Vector__XXX + SG_ STH_Ventil_Status : 14|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ STH_Waermeeintrag : 16|6@1+ (1,0) [0|63] "" Vector__XXX + SG_ STH_KVS : 24|13@1+ (1,0) [0|8191] "Unit_MilliLiter" Vector__XXX + SG_ STH_Fehlerstatus : 37|3@1+ (1.0,0.0) [0.0|7] "" Vector__XXX + SG_ STH_Heizleistung : 40|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ STH_Wassertemp : 48|8@1+ (0.75,-40) [-40.00|142.25] "Unit_DegreCelsi" Vector__XXX + SG_ STH_Motorvorwaermung : 59|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ STH_Servicemode : 60|1@1+ (1,0) [0|1] "" Vector__XXX + SG_ STH_war_aktiv : 61|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ STH_KVS_Ueberlauf : 62|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ STH_KD_Fehler : 63|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + +BO_ 1172 STS_01: 8 Gateway_D4C7 + SG_ STS_01_CHK : 0|8@1+ (1,0) [0|255] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ STS_01_BZ : 8|4@1+ (1,0) [0|15] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ STS_Car_not_under_theft : 12|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ STS_Car_under_theft : 13|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ STS_Anlassersperre : 15|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ STS_Typencodierung : 16|5@1+ (1.0,0.0) [0.0|31] "" Vector__XXX + SG_ STS_KD_Fehler : 22|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ STS_LIN_aktiv : 23|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ STS_Standlicht : 24|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ STS_Fahrlicht : 25|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ STS_Alarm_still : 26|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ STS_Texte : 27|4@1+ (1.0,0.0) [0.0|15] "" Vector__XXX + SG_ STS_Laderelais : 38|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ STS_Summer : 48|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ STS_Alarm_Blinker : 50|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ STS_Notstart : 51|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ STS_Signalhorn : 55|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ STS_Leerlaufschaltung : 56|1@1+ (1.0,0.0) [0.0|1] "" Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + +BO_ 783 SWA_01: 8 Gateway_D4C7 + SG_ SWA_Status_CHK : 0|8@1+ (1,0) [0|255] "" Vector__XXX + SG_ SWA_Status_BZ : 8|4@1+ (1,0) [0|15] "" Vector__XXX + SG_ SWA_Anzeigen : 12|4@1+ (1.0,0.0) [0.0|15] "" Kombi_D4 + SG_ SWA_Blindheit_erkannt : 16|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ SWA_rel_Nichtverf : 17|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ SWA_rel_Fehler : 18|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ SWA_Sta_aktiv : 19|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ SWA_Sta_passiv : 20|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ SWA_Standziele_li : 24|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ SWA_Kolonne_li : 25|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ SWA_Infostufe_SWA_li : 26|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ SWA_Warnung_SWA_li : 27|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ SWA_Kolonne_mi : 33|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ SWA_Standziele_re : 40|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ SWA_Kolonne_re : 41|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ SWA_Infostufe_SWA_re : 42|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ SWA_Warnung_SWA_re : 43|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ SWA_Gischtzaehler : 48|7@1+ (1,0) [0|100] "Unit_PerCent" Vector__XXX + SG_ SWA_KD_Fehler : 59|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + +BO_ 1413 Systeminfo_01: 8 Gateway_D4C7 + SG_ SI_Int_CAN_gespiegelt : 0|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ SI_CAN_Komfort_Sleep : 1|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ SI_CAN_Dashboard_Sleep : 2|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ SI_CAN_Antrieb_Sleep : 3|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ SI_Infotainment_Sleep : 4|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ SI_CAN_Extended_Sleep : 5|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ SI_Fahrwerk_Sleep : 6|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ SI_Diagnose_Aktiv : 7|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ SI_QRS_Mode : 8|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7 + SG_ SI_T_Mode : 9|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7,Motor_EDC17_D4,Motor_ME17_BY,Motor_MED17_SIMOS8_D4 + SG_ SI_NWDF : 10|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ SI_NWDF_gueltig : 11|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ SI_Sammelfehler : 12|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ GW_KD_Fehler : 13|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ SI_MOST_Status : 15|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + SG_ SI_Sammel_SG_Fehler : 56|6@1+ (1,0) [0|60] "" Vector__XXX + SG_ SI_MO_WU : 63|1@1+ (1.0,0.0) [0.0|1] "" Vector__XXX + +BO_ 1214 TPD_SCU_01: 8 Gateway_D4C7 + SG_ TPD_SCU_Data_1 : 0|64@1+ (1.0,0.0) [0.0|18446744073709551615] "" SCU_D4 + +BO_ 768 TPD_Tester_01: 8 SCU_D4 + SG_ TPD_Tester_Data_1 : 0|64@1+ (1.0,0.0) [0.0|18446744073709551615] "" Gateway_D4C7 + +BO_ 769 TPD_Tester_02: 8 SCU_D4 + SG_ TPD_Tester_Data_2 : 0|64@1+ (1.0,0.0) [0.0|18446744073709551615] "" Gateway_D4C7 + +BO_ 770 TPD_Tester_03: 8 SCU_D4 + SG_ TPD_Tester_Data_3 : 0|64@1+ (1.0,0.0) [0.0|18446744073709551615] "" Gateway_D4C7 + +BO_ 771 TPD_Tester_04: 8 SCU_D4 + SG_ TPD_Tester_Data_4 : 0|64@1+ (1.0,0.0) [0.0|18446744073709551615] "" Gateway_D4C7 + +BO_ 772 TPD_Tester_05: 8 SCU_D4 + SG_ TPD_Tester_Data_5 : 0|64@1+ (1.0,0.0) [0.0|18446744073709551615] "" Gateway_D4C7 + +BO_ 773 TPD_Tester_06: 8 SCU_D4 + SG_ TPD_Tester_Data_6 : 0|64@1+ (1.0,0.0) [0.0|18446744073709551615] "" Gateway_D4C7 + +BO_ 774 TPD_Tester_07: 8 SCU_D4 + SG_ TPD_Tester_Data_7 : 0|64@1+ (1.0,0.0) [0.0|18446744073709551615] "" Gateway_D4C7 + +BO_ 775 TPD_Tester_08: 8 SCU_D4 + SG_ TPD_Tester_Data_8 : 0|64@1+ (1.0,0.0) [0.0|18446744073709551615] "" Gateway_D4C7 + +BO_ 542 TPS_SCU: 7 SCU_D4 + SG_ TPS_SCU_Data : 0|56@1+ (1.0,0.0) [0.0|72057594037927935] "" Gateway_D4C7 + +BO_ 512 TPS_Tester: 7 Gateway_D4C7 + SG_ TPS_Tester_Data : 0|56@1+ (1.0,0.0) [0.0|72057594037927935] "" SCU_D4 + +BO_ 268 TSK_02: 8 XXX + SG_ TSK_02_CHK : 0|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX + SG_ TSK_Status : 16|2@1+ (1,0) [0|3] "" XXX + +BO_ 786 TSK_03: 8 Motor_EDC17_D4 + SG_ TSK_03_CHK : 0|8@1+ (1,0) [0|255] "" Gateway_D4C7 + SG_ TSK_03_BZ : 8|4@1+ (1,0) [0|15] "" Gateway_D4C7 + SG_ FAS_Wunschgeschw : 12|10@1+ (0.32,0) [0.00|326.72] "Unit_KiloMeterPerHour" Gateway_D4C7 + SG_ FAS_Status_Prim_Anz : 22|2@1+ (1.0,0.0) [0.0|3] "" Gateway_D4C7 + SG_ FAS_Texte_Primaeranz : 48|7@1+ (1.0,0.0) [0.0|127] "" Gateway_D4C7 + SG_ FAS_Status_Anzeige : 61|3@1+ (1.0,0.0) [0.0|7] "" Gateway_D4C7 + +BO_ 270 TSK_04: 8 Motor_EDC17_D4 + SG_ TSK_04_CHK : 0|8@1+ (1,0) [0|255] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ TSK_04_BZ : 8|4@1+ (1,0) [0|15] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ TSK_zul_Regelabw : 12|6@1+ (0.024,0) [0.000|1.512] "Unit_MeterPerSeconSquar" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ TSK_ax_Getriebe : 18|9@1+ (0.024,-2.016) [-2.016|10.224] "Unit_MeterPerSeconSquar" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ TSK_Wunsch_Uebersetz : 27|10@1+ (0.0245,0) [0.0245|25.0635] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ TSK_Freig_WU : 37|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ TSK_Limiter_aktiv : 38|1@1+ (1.0,0.0) [0.0|1] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ TSK_Status_GRA_ACC_02 : 62|2@1+ (1.0,0.0) [0.0|3] "" Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + +BO_ 273 TSK_05: 8 Motor_EDC17_D4 + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" EPB_D4,Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" EPB_D4,Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ TSK_QBit_Steigung : 12|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ TSK_Status_GRA_ACC_01 : 16|2@1+ (1.0,0.0) [0.0|3] "" Gateway_D4C7 + SG_ TSK_Fahrzeugmasse : 18|5@1+ (200,500) [500|6500] "Unit_KiloGram" Gateway_D4C7 + SG_ TSK_QBit_Fahrzeugmasse : 23|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ TSK_Fahrzeugmasse_02 : 24|8@1+ (32,0) [0|8128] "Unit_KiloGram" Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ TSK_Steigung : 40|8@1+ (0.8,-101.6) [-101.6|101.6] "Unit_PerCent" Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ TSK_Getriebeinfo : 51|2@1+ (1.0,0.0) [0.0|3] "" Gateway_D4C7 + SG_ TSK_Codierung_ACC : 53|1@1+ (1.0,0.0) [0.0|1] "" EPB_D4,Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ TSK_Zwangszusch_ESP : 54|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + SG_ TSK_Freig_Verzoeg_Anf : 55|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7,Getriebe_AL551_951_D4_C7,Getriebe_DL501_C7,Getriebe_VL381_C7 + SG_ TSK_Verzoeg_Anf_02 : 56|8@1+ (0.024,-3.984) [-3.984|2.136] "Unit_MeterPerSeconSquar" Gateway_D4C7 + +BO_ 1716 VIN_01: 8 Gateway_D4C7 + SG_ VIN_01_MUX M : 0|2@1+ (1,0) [0|3] "" Airbag_D4,EPB_D4,LWS_D4,SCR_C7,SCU_D4 + SG_ KS_Geheimnis_1 m0 : 8|8@1+ (1,0) [0|255] "" Airbag_D4,EPB_D4 + SG_ VIN_4 m1 : 8|8@1+ (1,0) [0|255] "" Airbag_D4,EPB_D4,SCR_C7 + SG_ VIN_11 m2 : 8|8@1+ (1,0) [0|255] "" Airbag_D4,EPB_D4,SCR_C7 + SG_ KS_Geheimnis_2 m0 : 16|8@1+ (1,0) [0|255] "" Airbag_D4,EPB_D4 + SG_ VIN_5 m1 : 16|8@1+ (1,0) [0|255] "" Airbag_D4,EPB_D4,SCR_C7 + SG_ VIN_12 m2 : 16|8@1+ (1,0) [0|255] "" Airbag_D4,EPB_D4,SCR_C7 + SG_ KS_Geheimnis_3 m0 : 24|8@1+ (1,0) [0|255] "" Airbag_D4,EPB_D4 + SG_ VIN_6 m1 : 24|8@1+ (1,0) [0|255] "" Airbag_D4,EPB_D4,SCR_C7 + SG_ VIN_13 m2 : 24|8@1+ (1,0) [0|255] "" Airbag_D4,EPB_D4,SCR_C7 + SG_ KS_Geheimnis_4 m0 : 32|8@1+ (1,0) [0|255] "" Airbag_D4,EPB_D4 + SG_ VIN_7 m1 : 32|8@1+ (1,0) [0|255] "" Airbag_D4,EPB_D4,SCR_C7 + SG_ VIN_14 m2 : 32|8@1+ (1,0) [0|255] "" Airbag_D4,EPB_D4,LWS_D4,SCR_C7,SCU_D4 + SG_ VIN_1 m0 : 40|8@1+ (1,0) [0|255] "" Airbag_D4,EPB_D4,SCR_C7 + SG_ VIN_8 m1 : 40|8@1+ (1,0) [0|255] "" Airbag_D4,EPB_D4,SCR_C7 + SG_ VIN_15 m2 : 40|8@1+ (1,0) [0|255] "" Airbag_D4,EPB_D4,LWS_D4,SCR_C7,SCU_D4 + SG_ VIN_2 m0 : 48|8@1+ (1,0) [0|255] "" Airbag_D4,EPB_D4,SCR_C7 + SG_ VIN_9 m1 : 48|8@1+ (1,0) [0|255] "" Airbag_D4,EPB_D4,SCR_C7 + SG_ VIN_16 m2 : 48|8@1+ (1,0) [0|255] "" Airbag_D4,EPB_D4,LWS_D4,SCR_C7,SCU_D4 + SG_ VIN_3 m0 : 56|8@1+ (1,0) [0|255] "" Airbag_D4,EPB_D4,SCR_C7 + SG_ VIN_10 m1 : 56|8@1+ (1,0) [0|255] "" Airbag_D4,EPB_D4,SCR_C7 + SG_ VIN_17 m2 : 56|8@1+ (1,0) [0|255] "" Airbag_D4,EPB_D4,LWS_D4,SCR_C7,SCU_D4 + +BO_ 1414 Waehlhebel_02: 8 Getriebe_AL551_951_D4_C7 + SG_ WH_KD_Fehler : 63|1@1+ (1.0,0.0) [0.0|1] "" Gateway_D4C7 + + +VAL_ 159 EPS_HCA_Status 0 "disabled" 1 "initializing" 2 "fault" 3 "ready" 4 "rejected" 5 "active" ; +VAL_ 269 ACC_Freigabe_Momentenanf 0 "Momanf_nicht_freigegeben" 1 "Momanf_freigegeben" ; +VAL_ 269 ACC_Freigabe_Verzanf 0 "Verzanf_nicht_freigegeben" 1 "Verzanf_freigegeben" ; +VAL_ 269 ACC_Getriebestellung_P 0 "P_Stellung_nicht_angefordert" 1 "Anforderung_P_Stellung" ; +VAL_ 269 ACC_limitierte_Anfahrdyn 0 "keine_Limitierung" 1 "Limitierung_Anfahrdynamik_angefordert" ; +VAL_ 269 ACC_Loeseanforderung 0 "keine_Anforderung" 1 "Loeseanforderung" ; +VAL_ 269 ACC_StartStopp_Info 0 "Motorlauf_langfristig_nicht_notwendig_Stoppfreigabe" 1 "Motoranlauf_nicht_zwingend_notwendig_Stoppverbot_keine_Startanforderung" 2 "Motoranlauf_zwingend_notwendig_Startanforderung" 3 "Systemfehler" ; +VAL_ 269 ACC_Vorbefuellung_Bremsanlage 0 "Vorbefuellung_AUS" 1 "Vorbefuellung_EIN" ; +VAL_ 269 ACC_Status_ACC 0 "ACC_OFF_Hauptschalter_aus" 1 "ACC_INIT" 2 "ACC_STANDBY" 3 "ACC_AKTIV_regelt" 4 "ACC_OVERRIDE" 5 "nicht_definiert" 6 "reversibler_Fehler_im_ACC_System" 7 "irreversibler_Fehler_im_ACC_System" ; +VAL_ 269 ACC_Betaetigung_EPB 0 "keine_EPB_Anforderung" 1 "EPB_Aktuator_schliessen" ; +VAL_ 269 ACC_Beeinflussung_ESP 0 "keine_Zwangszuschaltung" 1 "ESP_Zwangszuschaltung" ; +VAL_ 269 ACC_Anhalten 0 "kein_Anhalten_gewuenscht" 1 "Anhalten_gewuenscht" ; +VAL_ 269 ACC_KD_Fehler 0 "kein_KD_Fehler" 1 "KD_Fehler" ; +VAL_ 64 AB_RGS_Anst 4 "aktiv_Niveau_1" 5 "aktiv_Niveau_2" 6 "aktiv_Niveau_3" 7 "aktiv_Niveau_4" 8 "deaktiviert" ; +VAL_ 64 AB_Front_Crash 0 "kein_Front_Crash" 1 "Front_Crash" ; +VAL_ 64 AB_Heck_Crash 0 "kein_Heck_Crash" 1 "Heck_Crash" ; +VAL_ 64 AB_SF_Crash 0 "kein_Seiten_Crash_Fahrer" 1 "Seiten_Crash_Fahrer" ; +VAL_ 64 AB_SB_Crash 0 "kein_Seiten_Crash_Beifahrer" 1 "Seiten_Crash_Beifahrer" ; +VAL_ 64 AB_Rollover_Crash 0 "kein_Rollover" 1 "Rollover" ; +VAL_ 64 AB_Crash_Int 0 "kein_Crash" 1 "Crash_Intensitaet_1" 2 "Crash_Intensitaet_2_(nur_Stellgliedtest_B8)" 3 "Crash_Intensitaet_2_(nur_D4_C7_Colorado_NF_PAG__Crash_im_B8)" 4 "Crash_Intensitaet_3_(alt_VW/AUDI__Stellgiedtest_B8)" 5 "Crash_Intensitaet_3_(alt_PAG)" 7 "Crash_Intensitaet_3" ; +VAL_ 64 AB_Lampe 0 "Aus" 1 "Ein" ; +VAL_ 64 AB_Deaktiviert 0 "aktiv" 1 "deaktiviert" ; +VAL_ 64 AB_VB_deaktiviert 0 "Beifahrerairbag_aktiv" 1 "Beifahrerairbag_deaktiviert" ; +VAL_ 64 AB_Systemfehler 0 "kein_Fehler" 1 "Airbag_Systemfehler" ; +VAL_ 64 AB_Diagnose 0 "nicht_in_Diagnose" 1 "in_Diagnose" ; +VAL_ 64 AB_Stellgliedtest 0 "nicht_im_Stellgliedtest" 1 "Airbag_im_Stellgliedtest" ; +VAL_ 64 AB_Erh_Auf_VB 0 "keine_Anzeige" 1 "Beifahrerairbag_deaktiviert" 2 "Beifahrerairbag_aktiviert" 3 "nicht_definiert" ; +VAL_ 64 AB_Gurtwarn_VF 0 "keine_Warnung" 1 "Gurtwarnung_ausloesen" ; +VAL_ 64 AB_Gurtwarn_VB 0 "keine_Warnung" 1 "Gurtwarnung_ausloesen" ; +VAL_ 64 AB_Anzeige_Fussg 0 "keine_FSG_Aktion_ausgeloest" 1 "Motorhaube_offen" 2 "Systemfehler" ; +VAL_ 64 AB_Texte_AKS 0 "keine_AKS_Ausloesung" 1 "AKS_ausgeloest" 2 "AKS_Systemfehler" ; +VAL_ 64 AB_PAO_Leuchte_Anf 0 "Leuchte_ausschalten" 1 "Leuchte_einschalten" ; +VAL_ 64 AB_MKB_gueltig 0 "Multikollisionsbremsung_nicht_freigeschaltet" 1 "Multikollisionsbremsung_freigeschaltet" ; +VAL_ 64 AB_MKB_Anforderung 0 "Multikollisionsbremsung_nicht_angefordert" 1 "Multikollisionsbremsung_angefordert" ; +VAL_ 64 AB_Versorgungsspannung 0 "plausibel" 1 "unplausibel" ; +VAL_ 64 AB_KD_Fehler 0 "kein_KD_Fehler" 1 "KD_Fehler" ; +VAL_ 1312 AB_Belegung_VB 0 "nicht_verfuegbar" 1 "Fehler" 2 "nicht_belegt" 3 "belegt" ; +VAL_ 1312 AB_Gurtschloss_FA 0 "nicht_verbaut" 1 "nicht_verf�gbar (Fehler oder Init)" 2 "nicht_gesteckt" 3 "gesteckt" ; +VAL_ 1312 AB_Gurtschloss_BF 0 "nicht_verbaut" 1 "nicht_verf�gbar (Fehler oder Init)" 2 "nicht_gesteckt" 3 "gesteckt" ; +VAL_ 1312 AB_Gurtschloss_Reihe2_FA 0 "nicht_verbaut" 1 "nicht_verf�gbar (Fehler oder Init)" 2 "nicht_gesteckt" 3 "gesteckt" ; +VAL_ 1312 AB_Gurtschloss_Reihe2_MI 0 "nicht_verbaut" 1 "nicht_verf�gbar (Fehler oder Init)" 2 "nicht_gesteckt" 3 "gesteckt" ; +VAL_ 1312 AB_Gurtschloss_Reihe2_BF 0 "nicht_verbaut" 1 "nicht_verf�gbar (Fehler oder Init)" 2 "nicht_gesteckt" 3 "gesteckt" ; +VAL_ 1312 AB_Gurtschloss_Reihe3_FA 0 "nicht_verbaut" 1 "nicht_verf�gbar (Fehler oder Init)" 2 "nicht_gesteckt" 3 "gesteckt" ; +VAL_ 1312 AB_Gurtschloss_Reihe3_MI 0 "nicht_verbaut" 1 "nicht_verf�gbar (Fehler oder Init)" 2 "nicht_gesteckt" 3 "gesteckt" ; +VAL_ 1312 AB_Gurtschloss_Reihe3_BF 0 "nicht_verbaut" 1 "nicht_verf�gbar (Fehler oder Init)" 2 "nicht_gesteckt" 3 "gesteckt" ; +VAL_ 1312 AB_Sitzpos_Sens_FA 0 "nicht verf�gbar" 1 "Fehler" 2 "Sitz nicht vorne" 3 "Sitz vorne" ; +VAL_ 1312 AB_Sitzpos_Sens_BF 0 "nicht verf�gbar" 1 "Fehler" 2 "Sitz nicht vorne" 3 "Sitz vorne" ; +VAL_ 1633 AAG_Bremsl_durch_ECD 0 "Bremslicht_ist_aus" 1 "Bremslicht_durch_ECD_aktiv" ; +VAL_ 1633 AAG_Anhaenger_abgesteckt 1 "Anhaenger_wurde_bei_KL15_aus_abgesteckt" ; +VAL_ 1633 AAG_NSL_aktiv 1 "Anhaenger_Nebelschusslicht_aktiv" ; +VAL_ 1633 AAG_Anhaenger_erkannt 0 "kein_Anhaenger_erkannt" 1 "AAG_Anhaenger_erkannt" ; +VAL_ 1633 AAG_Blinker_H_aktiv 1 "Anhaenger_Blinker_aktiv" ; +VAL_ 1633 AAG_Blinker_HL_def 1 "Anhaenger_Blinker_links_defekt" ; +VAL_ 1633 AAG_Blinker_HR_def 1 "Anhaenger_Blinker_rechts_defekt" ; +VAL_ 1633 AAG_Bremslicht_H_def 1 "Anhaenger_Bremslicht_defekt" ; +VAL_ 1633 AAG_Schlusslicht_HL_def 1 "Anhaenger_Schlusslicht_links_defekt" ; +VAL_ 1633 AAG_Schlusslicht_HR_def 1 "Anhaenger_Schlusslicht_rechts_defekt" ; +VAL_ 1633 AAG_KD_Fehler 0 "kein_KD_Fehler" 1 "KD_Fehler" ; +VAL_ 1633 AAG_AVS_Fehler 0 "iO" 1 "niO" 2 "niO_Fahrzeugstopp_erforderlich" 3 "tbd" ; +VAL_ 1633 AAG_AVS_Stati 0 "endlage eingefahren erreicht" 1 "endlage ausgefahren erreicht" 2 "ausfahren automatik " 3 "einfahren automatik" 4 "ausfahren manuell " 5 "einfahren manuell" 6 "zwischenposition" 7 "nicht initialisiert" ; +VAL_ 777 BEM_Segel_Info 0 "keine_Anforderung" 1 "Mindestdrehzahl_1" 2 "Mindestdrehzahl_2" 3 "Segelveto" ; +VAL_ 777 BEM_P_Generator 255 "Fehler" ; +VAL_ 777 BEM_n_LLA 0 "keine_Erhoehung" 1 "Stufe_1" 2 "Stufe_2" 3 "Stufe_3" ; +VAL_ 777 BEM_01_Abschaltstufen 0 "Stufe_0_keine_Einschraenkung" 1 "Stufe_1" 2 "Stufe_2" 3 "Stufe_3" 4 "Transportmodus" 7 "Ruhestrommessmodus" ; +VAL_ 777 BEM_Anf_KL 0 "keine Anforderung" 1 "Anforderung K�hlerl�fter Ansteuerung" ; +VAL_ 777 BEM_StartStopp_Info 0 "Motorlauf_nicht_notwendig_(Stoppfreigabe)" 1 "Motoranlauf_nicht_zwingend_notwendig_(Stoppverbot,keine_Startanforderung)" 2 "Motoranlauf_zwingend_notwendig_(Startanforderung)" 3 "Systemfehler" ; +VAL_ 901 CHA_Systemstatus 0 "Status in Ordnung" 1 "reserviert" 2 "reserviert" 3 "reserviert" ; +VAL_ 901 CHA_Fahrer_Umschaltung 0 "keine_oder_automatische Umschaltung" 1 "manuelle_Umschaltung" ; +VAL_ 901 CHA_Ziel_FahrPr_MO 0 "nicht_belegt" 1 "Programm_1" 2 "Programm_2" 3 "Programm_3" 4 "Programm_4" 5 "Programm_5" 6 "Programm_6" 7 "Programm_7" ; +VAL_ 901 CHA_Ziel_FahrPr_GE 0 "nicht_belegt" 1 "Programm_1" 2 "Programm_2" 3 "Programm_3" 4 "Programm_4" 5 "Programm_5" 6 "Programm_6" 7 "Programm_7" ; +VAL_ 901 CHA_Ziel_FahrPr_ST 0 "nicht_belegt" 1 "Programm_1" 2 "Programm_2" 3 "Programm_3" 4 "Programm_4" 5 "Programm_5" 6 "Programm_6" 7 "Programm_7" ; +VAL_ 901 CHA_Ziel_FahrPr_SCU 0 "nicht_belegt" 1 "Programm_1" 2 "Programm_2" 3 "Programm_3" 4 "Programm_4" 5 "Programm_5" 6 "Programm_6" 7 "Programm_7" ; +VAL_ 901 CHA_Ziel_FahrPr_DR 0 "nicht_belegt" 1 "Programm_1" 2 "Programm_2" 3 "Programm_3" 4 "Programm_4" 5 "Programm_5" 6 "Programm_6" 7 "Programm_7" ; +VAL_ 901 CHA_Ziel_FahrPr_QS 0 "nicht_belegt" 1 "Programm_1" 2 "Programm_2" 3 "Programm_3" 4 "Programm_4" 5 "Programm_5" 6 "Programm_6" 7 "Programm_7" ; +VAL_ 901 CHA_Ziel_FahrPr_AFS 0 "nicht_belegt" 1 "Programm_1" 2 "Programm_2" 3 "Programm_3" 4 "Programm_4" 5 "Programm_5" 6 "Programm_6" 7 "Programm_7" ; +VAL_ 901 CHA_Ziel_FahrPr_RGS 0 "nicht_belegt" 1 "Programm_1" 2 "Programm_2" 3 "Programm_3" 4 "Programm_4" 5 "Programm_5" 6 "Programm_6" 7 "Programm_7" ; +VAL_ 901 CHA_Ziel_FahrPr_EPS 0 "nicht_belegt" 1 "Programm_1" 2 "Programm_2" 3 "Programm_3" 4 "Programm_4" 5 "Programm_5" 6 "Programm_6" 7 "Programm_7" ; +VAL_ 901 CHA_Ziel_FahrPr_ACC 0 "nicht_belegt" 1 "Programm_1" 2 "Programm_2" 3 "Programm_3" 4 "Programm_4" 5 "Programm_5" 6 "Programm_6" 7 "Programm_7" ; +VAL_ 901 CHA_Ziel_FahrPr_SAK 0 "nicht_belegt" 1 "Programm_1" 2 "Programm_2" 3 "Programm_3" 4 "Programm_4" 5 "Programm_5" 6 "Programm_6" 7 "Programm_7" ; +VAL_ 1714 DGN_Verlernzaehler 255 "ung�ltiger Z�hlerstand oder kein g�ltiger Fahrzyklus" ; +VAL_ 1714 KBI_Kilometerstand 1048574 "Init" 1048575 "Fehler" ; +VAL_ 1714 UH_Monat 14 "reserviert" ; +VAL_ 1714 UH_Tag 0 "reserviert" ; +VAL_ 1714 Kombi_02_alt 0 "aktuell" 1 "veraltet" ; +VAL_ 1714 Uhrzeit_01_alt 0 "aktuell" 1 "veraltet" ; +VAL_ 1520 DI_KL_58d 254 "Init" 255 "Fehler" ; +VAL_ 1520 DI_KL_58s 126 "Init" 127 "Fehler" ; +VAL_ 1520 DI_KL_58st 126 "Init" 127 "Fehler" ; +VAL_ 1603 KBI_Einheit_Datum 0 "Tag/Monat/Jahr" 1 "Monat/Tag/Jahr" 2 "Jahr/Monat/Tag" 3 "reserviert" ; +VAL_ 1603 KBI_Einheit_Druck 0 "Druckangabe in bar" 1 "Druckangabe in psi" 2 "Druckangabe in kPa" 3 "tbd." ; +VAL_ 1603 KBI_Einheit_Streckenanz 0 "Kilometer" 1 "Meilen" ; +VAL_ 1603 KBI_MFA_v_Einheit_02 0 "kmh" 1 "mph" ; +VAL_ 1603 KBI_Einheit_Temp 0 "Grad Celsius �C" 1 "Grad Fahrenheit �F" ; +VAL_ 1603 KBI_Einheit_Uhrzeit 0 "24h" 1 " 12h AM/PM" ; +VAL_ 1603 KBI_Einheit_Verbrauch 0 "mpg UK" 1 "mpg USA" 2 "Liter/100km" 3 "km/Liter" ; +VAL_ 1603 KBI_Einheit_Volumen 0 "Liter" 1 "Gallonen UK" 2 "Gallonen USA" 3 "reserviert" ; +VAL_ 260 EPB_QBit_Laengsbeschleunigung 0 "g�ltiger Wert" 1 "Ersatz-, Init- oder Fehlerwert" ; +VAL_ 260 EPB_QBit_Pedalweg_Kuppl 0 "g�ltiger Wert" 1 "Ersatz-, Init- oder Fehlerwert" ; +VAL_ 260 EPB_BCM2_Motor_Wakeup 0 "keine Anforderung" 1 "Anforderung an BCM2 Wakeupleitung zum Motor hochzuziehen aufgrund von Car-Wakeup" ; +VAL_ 260 EPB_Freig_Verzoeg_Anf 0 "nicht freigegeben" 1 "freigegeben" ; +VAL_ 260 EPB_Laengsbeschleunigung 255 "Fehler" ; +VAL_ 260 EPB_Pedalweg_Kuppl 0 "Init" 255 "Fehler" ; +VAL_ 260 EPB_Anfahrwunsch_erkannt 0 "kein Anfahrwunsch erkannt" 1 "Anfahrwunsch erkannt" ; +VAL_ 260 EPB_DAA_Randbed_erf 0 "Randbed_nicht_erfuellt" 1 "Randbed_erfuellt" ; +VAL_ 260 EPB_Fehlerstatus 0 "kein Fehler in EPB - AVH darf von ESP ausgef�hrt werden" 1 "nur VW526: tempor�rer Fehler" 2 "nur VW526: EPB in Diagnose" 3 "Fehler in EPB - AVH darf von ESP nicht ausgef�hrt werden" ; +VAL_ 260 EPB_Schalterposition 0 "keine Fahreranforderung" 1 "Fahreranforderung �ffnen" 2 "Fahreranforderung Schlie�en" 3 "Fehler" ; +VAL_ 260 EPB_QBit_Schalterpos 0 "g�ltiger Wert (volle Funktion)" 1 " Ersatz-, Init- oder Fehlerwert (Schalter ausser Funktion)" ; +VAL_ 260 EPB_Konsistenz_ACC 0 "kein Fehler erkannt" 1 "Fehler erkannt" ; +VAL_ 260 EPB_Spannkraft 30 "Init" 31 "Fehler" ; +VAL_ 260 EPB_Status 0 "offen" 1 "Bremse_geschl_(Spannkraft_voll/reduziert)" 2 "Aktuator im Lauf" 3 "Fehler" ; +VAL_ 260 EPB_KD_Fehler 0 "kein_KD_Fehler" 1 "KD_Fehler" ; +VAL_ 781 EPB_Fehlerlampe_Gelb 0 "Aus" 1 "Ein" ; +VAL_ 781 EPB_Fehlerlampe_BKL 0 "BKL aus" 1 "BKL an" ; +VAL_ 781 EPB_Funktionslampe 0 "Aus" 1 "Ein" ; +VAL_ 781 EPB_Texte 0 "keine_Anzeige" 1 "Neigungswinkel_zu_gross" 2 "Parkbremse_von_Hand_oeffnen" 3 "EPB_in_Diagnose" 4 "Bremspedal_betaetigen" 5 "tbd." 6 "tbd." 7 "St�rung Anfahrassistent" 8 "Abschleppschutz blockiert" ; +VAL_ 781 EPB_Akustik 0 "Warnton aus" 1 "Warnton an" ; +VAL_ 781 EPB_Autoholdlampe 0 "Lampe aus (Autohold inaktiv)" 1 "Lampe ein (Autohold aktiv)" ; +VAL_ 781 EPB_Bremsbelag_Warn 0 "Bremsbelag_ok" 1 "Bremsbelag_unter_Minimum" ; +VAL_ 256 ASR_Moment_langsam 1022 "Init" 1023 "Fehler" ; +VAL_ 256 ASR_MSR_Moment_schnell 1022 "Init" 1023 "Fehler" ; +VAL_ 256 ESP_v_Signal 65533 "Unterspannung" 65534 "Init" 65535 "Fehler" ; +VAL_ 256 ASR_Tastung_passiv 0 "ASR_aktiviert" 1 "ASR_passiv_getastet_oder_Schwellen_geaendert" ; +VAL_ 256 ESP_Tastung_passiv 0 "ESP_aktiviert" 1 "ESP_passiv_getastet_oder_Schwellen_geaendert" ; +VAL_ 256 ESP_Systemstatus 0 "iO" 1 "Fehler" ; +VAL_ 256 ASR_Schalteingriff 0 "keine Anforderung" 1 "ASR_Schaltkennfeld" 2 "R�ckschaltung" 3 "Schaltverbot" ; +VAL_ 256 OBD_Schlechtweg 0 "kein Schlechtweg erkannt" 1 "Schlechtweg erkannt" ; +VAL_ 256 OBD_QBit_Schlechtweg 0 "gueltiger_Wert" 1 "Ersatz_Init_oder_Fehlerwert" ; +VAL_ 256 ESP_QBit_v_Signal 0 "gueltiger_Wert" 1 "Ersatz_Init_oder_Fehlerwert" ; +VAL_ 256 ABS_Bremsung 0 "keine_ABS_Regelung" 1 "ABS_Regelung_aktiv" ; +VAL_ 256 ASR_Anf 0 "keine_Anforderung" 1 "ASR_Anforderung" ; +VAL_ 256 MSR_Anf 0 "keine Anfoderung" 1 "MSR-Anforderung" ; +VAL_ 256 EBV_Eingriff 0 "kein EBV-Eingriff" 1 "EBV-Eingriff" ; +VAL_ 256 EDS_Eingriff 0 "kein_EDS_Eingriff" 1 "EDS_Eingriff" ; +VAL_ 256 ESP_Eingriff 0 "kein_ESP_Eingriff" 1 "ESP_Eingriff_aktiv" ; +VAL_ 256 ESP_ASP 0 "inaktiv" 1 "aktiv" ; +VAL_ 256 ESP_KD_Fehler 0 "kein_KD_Fehler" 1 "KD_Fehler" ; +VAL_ 257 ESP_QBit_Gierrate 0 "gueltiger_Wert" 1 "Ersatz_Init_oder_Fehlerwert" ; +VAL_ 257 ESP_QBit_Laengsbeschl 0 "gueltiger_Wert" 1 "Ersatz_Init_oder_Fehlerwert" ; +VAL_ 257 ESP_QBit_Querb 0 "gueltiger_Wert" 1 "Ersatz_Init_oder_Fehlerwert" ; +VAL_ 257 ESP_Stillstandsflag 0 "kein_Stillstand_erkannt" 1 "Stillstand_erkannt" ; +VAL_ 257 ESP_Querbeschleunigung 255 "Fehler" ; +VAL_ 257 ESP_Laengsbeschl 1022 "Signal_nicht_vorhanden" 1023 "Fehler" ; +VAL_ 257 ESP_Verteil_Wankmom 30 "Init" 31 "Fehler" ; +VAL_ 257 ESP_QBit_Anf_Vert_Wank 0 "gueltiger_Wert" 1 "Ersatz_Init_oder_Fehlerwert" ; +VAL_ 257 ESP_Gierrate 16383 "Fehler" ; +VAL_ 257 ESP_VZ_Gierrate 0 "positiv" 1 "negativ" ; +VAL_ 257 ESP_Notbremsanzeige 0 "keine_Notbremsung_erkannt" 1 "Notbremsung_erkannt" ; +VAL_ 257 ESP_SpannungsAnf 0 "keine_Anforderung" 1 "Anforderung_Spannungswert_1" ; +VAL_ 257 ESP_PLA_Abbruch 0 "Init" 1 "Geschwindigkeitsueberschreitung" 2 "Falscher_PLA_Status" 3 "Deaktivierung_durch_Abbruch_Lenkung" 4 "PLA_Bremsanforderung_nach_Stillstand" 5 "Abbruch_durch_Kl15_aus" 6 "Abbruch_durch_FT_offen" ; +VAL_ 257 ESP_Status_ESP_PLA 0 "ESP_PLA_deaktiv" 1 "ESP_PLA_Init" 2 "ESP_PLA_Fehler" 4 "ESP_PLA_aktivierbar" 6 "ESP_PLA_Bremse_aktiv" 8 "ESP_PLA_funktionsbereit" 9 "ESP_PLA_Neustart" 10 "ESP_PLA_Abbruch" ; +VAL_ 259 ESP_VL_FR 0 "Vorwaerts" 1 "Rueckwaerts" ; +VAL_ 259 ESP_VR_FR 0 "Vorwaerts" 1 "Rueckwaerts" ; +VAL_ 259 ESP_HL_FR 0 "Vorwaerts" 1 "Rueckwaerts" ; +VAL_ 259 ESP_HR_FR 0 "Vorwaerts" 1 "Rueckwaerts" ; +VAL_ 259 ESP_VL_Radgeschw 4093 "Unterspannung" 4094 "Init" 4095 "Fehler" ; +VAL_ 259 ESP_VR_Radgeschw 4093 "Unterspannung" 4094 "Init" 4095 "Fehler" ; +VAL_ 259 ESP_HL_Radgeschw 4093 "Unterspannung" 4094 "Init" 4095 "Fehler" ; +VAL_ 259 ESP_HR_Radgeschw 4093 "Unterspannung" 4094 "Init" 4095 "Fehler" ; +VAL_ 776 ESP_Meldungen 0 "keine_Anzeige_kein_Gong" 1 "Autohold_Hinweis_1_und_kein_Gong" 2 "Stoerung_Autohold_und_1x_Gong" 3 "Stoerung_Hillholder_und_1x_Gong" 4 "Uebernehmen_und_1x_Gong" ; +VAL_ 776 ESP_HDC_FktLampe 0 "Aus" 1 "Ein" ; +VAL_ 776 ESP_Lampe 0 "Aus" 1 "Ein" ; +VAL_ 776 ABS_Lampe 0 "Aus" 1 "Ein" ; +VAL_ 776 BK_Lampe 0 "Aus" 1 "Ein" ; +VAL_ 776 ESP_Akustik 0 "keine_Akustik" 1 "1x_Beep" ; +VAL_ 776 ESP_Diagnose 0 "ESP_nicht_in_Diagnose" 1 "ESP_in_Diagnose" ; +VAL_ 776 ESP_Textanzeigen_02 0 "kein_Text" 1 "ESP_Stoerung" 2 "ABS_Stoerung" 3 "ESP_ABS_Stoerung" 4 "nicht_definiert" 5 "ASR_Stoerung" 6 "ESP_switched_off" 7 "ASR_off" 8 "ESP_ASR_on" 9 "Stoerung_Hillholder" 10 "keine_Bremskraftverstaerkung" 11 "ASR_aktiviert" 12 "ABS_ASR_Stoerung" 13 "bitte_Reifen_pruefen" 14 "Stoerung_Autohold" 15 "ESP_offroad" 16 "Autohold_Hinweis_1" 17 "ESP_sport" 18 "ESP_Zwangsaktivierung" ; +VAL_ 776 ESP_Off_Lampe 0 "Lampe_aus" 1 "Lampe_ein" ; +VAL_ 776 ESP_m_Raddrehz 32765 "Unterspannung" 32766 "Init" 32767 "Fehler" ; +VAL_ 776 ESP_ASR_Lampe 0 "ESP_ASR_Lampe_aus" 1 "ESP_ASR_Lampe_an" ; +VAL_ 776 ESP_Fehlerstatus_Wegimp 0 "Wegimpulse_iO" 1 "Fehler" ; +VAL_ 776 ESP_Wegimp_Ueberlauf 0 "Reset und kein �berlauf" 1 "mindestens 1x �berlauf" ; +VAL_ 776 ESP_QBit_Wegimp_VA 0 "gueltiger_Wert" 1 "Ersatz_Init_oder_Fehlerwert" ; +VAL_ 776 ESP_Displaywarnungen 0 "keine_Warnung" 1 "BKL_Display_Warnung" ; +VAL_ 776 ESP_HDC_Regelgeschw 0 "nicht_verbaut" 125 "HDC_Standby" 127 "Fehler" ; +VAL_ 776 ESP_BKV_Warnung 0 "keine_Anzeige_kein_Gong" 1 "keine_Bremskraftverstaerkung_plus_1x_Gong" ; +VAL_ 262 ESP_QBit_Bremsdruck 0 "gueltiger_Wert" 1 "Ersatz_Init_oder_Fehlerwert" ; +VAL_ 262 ESP_QBit_Fahrer_bremst 0 "gueltiger_Wert" 1 "Ersatz_Init_oder_Fehlerwert" ; +VAL_ 262 ESP_Schwelle_Unterdruck 0 "kein_Signal" 1 "Unterdruck_kleiner_gleich_450_mbar" 2 "Unterdruck_groesser_450_mbar" 3 "Fehler_Unterdrucksensor" ; +VAL_ 262 ESP_Bremsdruck 1023 "Fehler" ; +VAL_ 262 ESP_Fahrer_bremst 0 "Bremsdruckschwelle_nicht_ueberschritten" 1 "Bremsdruckschwelle_ueberschritten" ; +VAL_ 262 ESP_Verz_TSK_aktiv 0 "TSK_Verzoegerung_inaktiv" 1 "TSK_Verzoegerung_aktiv" ; +VAL_ 262 ESP_Lenkeingriff_ADS 0 "kein_Lenkeingriff" 1 "stabilisierender_Lenkeingriff" ; +VAL_ 262 ESP_Konsistenz_TSK 0 "Botschaft_fuer_Verzoegerungsanforderung_konsistent" 1 "Botschaft_fuer_Verzoegerungsanforderung_nicht_konsistent" ; +VAL_ 262 ESP_Bremsruck_AWV2 0 "kein_Bremsruck_ausgefuehrt" 1 "Bremsruck_ausgefuehrt" ; +VAL_ 262 ESP_Konsistenz_AWV2 0 "Botschaft_fuer_AWV2_konsistent" 1 "Botschaft_fuer_AWV2_nicht_konsistent" ; +VAL_ 262 ECD_Fehler 0 "ECD_iO" 1 "ECD_Fehler" ; +VAL_ 262 ECD_nicht_verfuegbar 0 "ECD_Funktion_verfuegbar" 1 "ECD_Funktion_nicht_verfuegbar" ; +VAL_ 262 ESP_Status_Bremsentemp 0 "Bremse nicht �berhitzt" 1 "Bremse �berhitzt" ; +VAL_ 262 ESP_Autohold_Standby 0 "Autohold_nicht_im_Standby" 1 "Autohold_im_Standby" ; +VAL_ 262 ESP_HDC_Standby 0 "HDC_Funktion_nicht_im_Standby" 1 "HDC_Funktion_im_Standby" ; +VAL_ 262 ESP_HBA_aktiv 0 "HBA_nicht_aktiv" 1 "HBA_aktiv" ; +VAL_ 262 ESP_Prefill_ausgeloest 0 "nicht_ausgeloest" 1 "Prefill_ausgeloest" ; +VAL_ 262 ESP_Rueckwaertsfahrt_erkannt 0 "keine_Rueckwaetsfahrt" 1 "Rueckwaertsfahrt_erkannt" ; +VAL_ 262 ESP_Status_Anfahrhilfe 0 "Aus" 1 "Ein" ; +VAL_ 262 ESP_HDC_aktiv 0 "inaktiv" 1 "aktiv" ; +VAL_ 262 ESP_StartStopp_Info 0 "Motorlauf_nicht_notwendig_(Stoppfreigabe)" 1 "Motoranlauf_nicht_zwingend_notwendig_(Stoppverbot,keine_Startanforderung)" 2 "Motoranlauf_zwingend_notwendig_(Startanforderung)" 3 "Systemfehler" ; +VAL_ 262 ESP_Eingr_HL 0 "kein_Eingriff" 1 "ESP_Eingriff_HL" ; +VAL_ 262 ESP_Eingr_HR 0 "kein_Eingriff" 1 "ESP_Eingriff_HR" ; +VAL_ 262 ESP_Eingr_VL 0 "kein_Eingriff" 1 "ESP_Eingriff_VL" ; +VAL_ 262 ESP_Eingr_VR 0 "kein_Eingriff" 1 "ESP_Eingriff_VR" ; +VAL_ 262 ESP_BKV_Unterdruck 255 "Fehler" ; +VAL_ 262 ESP_Autohold_aktiv 0 "Autohold inaktiv" 1 "Autohold aktiv" ; +VAL_ 262 ESP_FStatus_Anfahrhilfe 0 "kein_Fehler" 1 "Fehler" ; +VAL_ 262 ESP_Verz_EPB_aktiv 0 "nicht aktiviert" 1 "aktiviert" ; +VAL_ 262 ECD_Bremslicht 0 "Aus" 1 "Ein" ; +VAL_ 262 ESP_Verzoeg_EPB_verf 0 "nicht verfuegbar" 1 "System verfuegbar" ; +VAL_ 262 ESP_Status_Bremsdruck 0 "Bremse drucklos" 1 "mit Bremsdruck" ; +VAL_ 262 ESP_Anforderung_EPB 0 "keine_Anforderung" 1 "Anforderung_Oeffnen" 2 "Anforderung_Schliessen" 3 "reserviert" ; +VAL_ 132 ESP_06_KD_Fehler 0 "kein_KD_Fehler" 1 "KD_Fehler" ; +VAL_ 132 ESP_VZ_Teilsollwinkel 0 "positiv" 1 "negativ" ; +VAL_ 132 ESP_Winkeleingriff 0 "kein Eingriff" 1 "Eingriff mit langsamer R�ckf�hrung" 2 "Eingriff mit mittlerer R�ckf�hrung" 3 "Eingriff mit schneller R�ckf�hrung" ; +VAL_ 132 ESP_Status_ADS 0 "ADS iO" 1 "ADS noch nicht verf�gbar" 2 "ADS tempor�r nicht verf�gbar" ; +VAL_ 132 ESP_v_ref 4093 "Unterspannung" 4095 "Fehler" ; +VAL_ 914 ESP_ACC_LDE 0 "Lebensdauerende_nicht_erreicht" 1 "Lebensdauerende_erreicht" ; +VAL_ 914 ESP_Quattro_Antrieb 0 "Front" 1 "Allrad" ; +VAL_ 914 ESP_Codierung_ADS 0 "Init" 1 "ESP_nicht_ADS_codiert" 2 "ADS_codiert" 3 "tbd" ; +VAL_ 914 ESP_RTA_HL 254 "Abgleich_nocht_nicht_genuegend_konvergent" 255 "Fehler" ; +VAL_ 914 ESP_RTA_HR 254 "Abgleich_nocht_nicht_genuegend_konvergent" 255 "Fehler" ; +VAL_ 914 ESP_RTA_VR 254 "Abgleich_nocht_nicht_genuegend_konvergent" 255 "Fehler" ; +VAL_ 914 OBD_Fehler_Radsensor_HL 0 "kein_Fehler" 1 "KS-" 2 "KS+" 3 "OC" 4 "OOR+" 5 "OOR-" 6 "RC+" 7 "RC-" 8 "KS+/OC" 9 "KS-/OC" 10 "KS-/KS+" 11 "KS-/KS+/OC" 12 "frei" 13 "frei" 14 "frei" 15 "frei" ; +VAL_ 914 OBD_Fehler_Radsensor_HR 0 "kein_Fehler" 1 "KS-" 2 "KS+" 3 "OC" 4 "OOR+" 5 "OOR-" 6 "RC+" 7 "RC-" 8 "KS+/OC" 9 "KS-/OC" 10 "KS-/KS+" 11 "KS-/KS+/OC" 12 "frei" 13 "frei" 14 "frei" 15 "frei" ; +VAL_ 914 OBD_Fehler_Radsensor_VL 0 "kein_Fehler" 1 "KS-" 2 "KS+" 3 "OC" 4 "OOR+" 5 "OOR-" 6 "RC+" 7 "RC-" 8 "KS+/OC" 9 "KS-/OC" 10 "KS-/KS+" 11 "KS-/KS+/OC" 12 "frei" 13 "frei" 14 "frei" 15 "frei" ; +VAL_ 914 OBD_Fehler_Radsensor_VR 0 "kein_Fehler" 1 "KS-" 2 "KS+" 3 "OC" 4 "OOR+" 5 "OOR-" 6 "RC+" 7 "RC-" 8 "KS+/OC" 9 "KS-/OC" 10 "KS-/KS+" 11 "KS-/KS+/OC" 12 "frei" 13 "frei" 14 "frei" 15 "frei" ; +VAL_ 914 ESP_Qualifizierung_Antriebsart 0 "alte_Bedeutung_Bit_ESP_Quattro_Antrieb" 1 "neue_Bedeutung_Bit_ESP_Quattro_Antrieb" ; +VAL_ 914 ESP_Offroad_Modus 0 "kein_ESP_Offroadmodus" 1 "ESP_Offroadmodus" ; +VAL_ 914 ESP_MKB_ausloesbar 0 "Multikollisionsbremsung_nicht_freigeschaltet" 1 "Multikollisionsbremsung_freigeschaltet" ; +VAL_ 914 ESP_MKB_Status 0 "Multikollisionsbremsung_nicht_aktiv" 1 "Multikollisionsbremsung_aktiv" ; +VAL_ 914 ESP_CM_Variante 0 "Standard" 1 "Erweitert" ; +VAL_ 914 ESP_OBD_Status 0 "MIL_aus" 1 "MIL_ein" ; +VAL_ 1623 ESP_BremsenTemp_hinten 0 "Temp_kleiner_99GradC" 1 "Temp_zwischen_100-199GradC" 2 "Temp_zwischen_200-299GradC" 3 "Temp_zwischen_300-399GradC" 4 "Temp_zwischen_400-499GradC" 5 "Temp_zwischen_500-599GradC" 6 "Temp_groesser_599GradC" 7 "Fehler" ; +VAL_ 924 BCM1_02_alt 0 "aktuell" 1 "veraltet" ; +VAL_ 924 Wischer_01_alt 0 "aktuell" 1 "veraltet" ; +VAL_ 924 Klima_02_alt 0 "aktuell" 1 "veraltet" ; +VAL_ 924 BCM1_01_alt 0 "aktuell" 1 "veraltet" ; +VAL_ 924 ESP_07_alt 0 "aktuell" 1 "veraltet" ; +VAL_ 924 TSG_BT_1_alt 0 "aktuell" 1 "veraltet" ; +VAL_ 924 TSG_HL_1_alt 0 "aktuell" 1 "veraltet" ; +VAL_ 924 TSG_HR_1_alt 0 "aktuell" 1 "veraltet" ; +VAL_ 924 Motor_02_alt 0 "aktuell" 1 "veraltet" ; +VAL_ 924 Klima_Sensor_02_alt 0 "aktuell" 1 "veraltet" ; +VAL_ 924 TSG_FT_1_alt 0 "aktuell" 1 "veraltet" ; +VAL_ 924 Motor_05_alt 0 "aktuell" 1 "veraltet" ; +VAL_ 924 QSP_01_alt 0 "aktuell" 1 "veraltet" ; +VAL_ 924 Parkhilfe_01_alt 0 "aktuell" 1 "veraltet" ; +VAL_ 924 Fahrwerk_02_alt 0 "aktuell" 1 "veraltet" ; +VAL_ 924 BCM1_MH_WIV_Schalter 0 "MH_geschlossen" 1 "MH_offen" ; +VAL_ 924 Wischer_vorne_aktiv 1 "Wischer vorne l�uft" ; +VAL_ 924 BCM1_Rueckfahrlicht_Schalter 0 "aus" 1 "betaetigt" ; +VAL_ 924 MO_Status_Normalbetrieb_01 0 "kein Normalbetrieb" 1 "Normalbetrieb erreicht" ; +VAL_ 924 KL_Zuheizer_Freigabe 0 "keine_Freigabe_Zuheizer" 1 "Zuheizerfreigabe" ; +VAL_ 924 BCM1_Vorwaertsgang_eingelegt 0 "Rueckwaertsgang bzw. restliche Gaenge eingelegt" 1 "Erster oder zweiter Gang eingelegt" ; +VAL_ 924 ESP_Codierung_ADS 0 "Init" 1 "ESP_nicht_ADS_codiert" 2 "ADS_codiert" 3 "tbd" ; +VAL_ 924 QSP_StartStopp_Info 0 "Motorlauf_nicht_notwendig_(Stoppfreigabe)" 1 "Motoranlauf_nicht_zwingend_notwendig_(Stoppverbot,keine_Startanforderung)" 2 "Motoranlauf_zwingend_notwendig_(Startanforderung)" 3 "Systemfehler" ; +VAL_ 924 FA_StartStopp_Info 0 "Motorlauf_nicht_notwendig_(Stoppfreigabe)" 1 "Motoranlauf_nicht_zwingend_notwendig_(Stoppverbot,keine_Startanforderung)" 2 "Motoranlauf_zwingend_notwendig_(Startanforderung)" 3 "Systemfehler" ; +VAL_ 924 PH_StartStopp_Info 0 "Motorlauf_nicht_notwendig_(Stoppfreigabe)" 1 "Motoranlauf_nicht_zwingend_notwendig_(Stoppverbot,keine_Startanforderung)" 2 "Motoranlauf_zwingend_notwendig_(Startanforderung)" 3 "Systemfehler" ; +VAL_ 924 KL_Beschlagsgefahr 0 "keine_Beschlagsgefahr" 1 "Beschlagsgefahr" ; +VAL_ 924 BCM1_GLW_Fernlicht_Anf 0 "Aus" 1 "Ein" ; +VAL_ 924 BCM1_RFahrlicht_Fzg_Anf 0 "Licht_nicht_angefordert" 1 "Licht ist einzuschalten" ; +VAL_ 924 FT_Tuer_geoeffnet 1 "Tuer offen" ; +VAL_ 924 MO_Handshake_STH 0 "keine EKP-Ansteuerung durch STH-Anforderung" 1 "EKP-Ansteuerung durch STH-Anforderung" ; +VAL_ 924 FT_Sperrklinke 0 "Schloss_in_Vorraste_und_Hauptraste" 1 "Tuer_auf_oder_Tuer_Position_zwischen_Vor_und_Hauptraste" ; +VAL_ 924 BCM1_OBD_FStatus_ATemp 0 "kein Fehler" 1 "KS-" 2 "KS+" 3 "OC (Leitungsunterbrechung)" 4 "OOR+ (out of range high)" 5 "OOR- (out of range low)" 6 "RC+ (Signal unplausibel hoch)" 7 "RC- (Signal unplausibel niedrig)" 8 "KS+/OC" 9 "KS-/OC" 10 "KS-/KS+" 11 "KS-/KS+/OC (allgemeiner Fehler)" ; +VAL_ 924 BCM1_Aussen_Temp_ungef 253 "nicht verbaut" 254 "Initwert" 255 "Fehler" ; +VAL_ 924 BCM1_Oeldruck_Schalter 0 "offen" 1 "geschlossen (p > p soll)" ; +VAL_ 924 BCM1_Oeldruck_Schalter_2 0 "offen" 1 "geschlossen" ; +VAL_ 924 BT_Tuer_geoeffnet 1 "Tuer_offen" ; +VAL_ 924 HL_Tuer_geoeffnet 1 "Tuer geoeffnet" ; +VAL_ 924 HR_Tuer_geoeffnet 1 "Tuer offen" ; +VAL_ 924 BCM1_Adaptive_Lichtvert_Anf 0 "Aus" 1 "Ein" ; +VAL_ 924 BCM1_Gleitende_Leuchtw_Anf 0 "Aus" 1 "Ein" ; +VAL_ 924 BCM1_Schalter_StartStopp 0 "Start_Stopp_ueber_Hauptschalter_deaktiviert" 1 "Start_Stopp_ueber_Hauptschalter_aktiviert" ; +VAL_ 924 ESP_Offroad_Modus 0 "kein_ESP_Offroadmodus" 1 "ESP_Offroadmodus" ; +VAL_ 924 MO_Freig_Reku 0 "Rekuperations-Modus aus" 1 "Empfehlung Spannungsanhebung" 2 "Empfehlung Spannungsabsenkung" 3 "Rekuperationsmodus aktiv, Spannungsvariation nicht notwendig" ; +VAL_ 1604 SMLS_01_alt 0 "aktuell" 1 "veraltet" ; +VAL_ 1604 BCM1_01_alt 0 "aktuell" 1 "veraltet" ; +VAL_ 1604 BCM1_02_alt 0 "aktuell" 1 "veraltet" ; +VAL_ 1604 BCM2_02_alt 0 "aktuell" 1 "veraltet" ; +VAL_ 1604 HYB_Anf_E_Mode_alt 0 "aktuell" 1 "veraltet" ; +VAL_ 1604 ESP_04_alt 0 "aktuell" 1 "veraltet" ; +VAL_ 1604 BH_Blinker_li 0 "nicht_betaetigt" 1 "Blinkerhebel_Richtung_links_betaetigt" ; +VAL_ 1604 BH_Blinker_re 0 "nicht_betaetigt" 1 "Blinkerhebel_Richtung_rechts_betaetigt" ; +VAL_ 1604 BM_Autobahn 0 "Autobahnblinken nicht aktiv " 1 "Autobahnblinken aktiv " ; +VAL_ 1604 BH_Fernlicht 0 "nicht_betaetigt" 1 "Blinkerhebel_in_Richtung_Fernlicht_betaetigt" ; +VAL_ 1604 BH_Lichthupe 0 "nicht_betaetigt" 1 "Blinkerhebel in Richtung Lichthupe betaetigt" ; +VAL_ 1604 BCM1_MH_Schalter 0 "MH_geschlossen" 1 "MH_offen" ; +VAL_ 1604 HYB_Anf_E_Mode 0 "Taster_nicht_betaetigt" 1 "Taster_betaetigt" ; +VAL_ 1604 HUD_NV_in_Anzeige 0 "NV_nicht_in_Anzeige" 1 "NV_in_Anzeige" ; +VAL_ 1604 BCM1_Touristen_Licht_Anf 0 "Licht_nicht_angefordert" 1 "Anforderung von Touristenlicht" ; +VAL_ 1604 LV_Abblendlicht_li_def 0 "OK" 1 "defekt" ; +VAL_ 1604 LV_Abblendlicht_re_def 0 "OK" 1 "defekt" ; +VAL_ 1604 LV_Abblendlicht_Anzeige 0 "nicht aktiv" 1 "aktiv" ; +VAL_ 1604 LV_AFL_aktiv_Anzeige 0 "nicht aktiv" 1 "aktiv" ; +VAL_ 1604 BCM1_Licht_Dunkelheit_aktiv 1 "Licht wegen Dunkelheit aktiv, nicht bei Autobahnlicht, Tagfahrlicht oder Regenlicht" ; +VAL_ 1604 LV_Nebelschlusslicht_Anzeige 0 "nicht aktiv" 1 "aktiv" ; +VAL_ 1604 BCM1_Linksverkehr 0 "Rechtsverkehr" 1 "Linksverkehr" ; +VAL_ 1604 BCM2_P_verriegelt 0 "WH nicht in Stellung P" 1 "WH in Stellung P" ; +VAL_ 1604 BCM1_LDS_Stellung 0 "Init" 1 "Stellung_0" 2 "Auto" 3 "Standlicht" 4 "Abblendlicht" 7 "Fehler" ; +VAL_ 1604 BCM1_Allwetterlicht_Anf 0 "Licht_nicht_angefordert" 1 "Licht_ist_einzuschalten" ; +VAL_ 1604 HUD_Anzeigefehler_NV 0 "kein_Fehler" 1 "Anzeigefehler" ; +VAL_ 1604 ESP_Diagnose 0 "ESP_nicht_in_Diagnose" 1 "ESP_in_Diagnose" ; +VAL_ 130 GE_Schaltvorgang 0 "keine Schaltung" 1 "Schaltung aktiv" ; +VAL_ 130 GE_Status_Kupplung 0 "Kupplung ge�ffnet" 1 "Kupplung geregelt" 2 "Kupplung geschlossen" 3 "Fehler" ; +VAL_ 130 GE_Verbot_Ausblendung 0 "kein_Verbot" 1 "Verbot" ; +VAL_ 130 GE_MMom_Soll 1022 "kein Eingriff" 1023 "Fehler" ; +VAL_ 130 GE_MMom_Status 0 "keine Anforderung" 1 "reduzierender Getriebeeingriff" 2 "erh�hender Getriebeeingriff" 3 "�nderung mit Sprung" ; +VAL_ 130 GE_MMom_Vorhalt 1022 "keine_Anforderung" 1023 "Fehler" ; +VAL_ 130 GE_Freig_MMom_Vorhalt 0 "nicht_freigegeben" 1 "freigegeben" ; +VAL_ 130 GE_KD_Fehler 0 "kein_KD_Fehler" 1 "KD_Fehler" ; +VAL_ 131 GE_Anf_Zylabsch 0 "Umschaltung erlaubt" 1 "Umschaltung verboten" 3 "VMB-Empfehlung" ; +VAL_ 131 GE_Synchro_Wunschdrehz 511 "Fehler" ; +VAL_ 131 GE_Synchro_Zeit 255 "Fehler" ; +VAL_ 131 GE_Mom_Begr_Gradient 255 "keine Begrenzung (Init)" ; +VAL_ 131 GE_Anheb_Solldrehz_Leerlauf 255 "Fehler" ; +VAL_ 131 GE_Vorsteuermoment 510 "Init" 511 "Fehler" ; +VAL_ 131 GE_Drehzahlmesser_Daempfung 0 "normale D�mpfung" 1 "dynamische D�mpfung" ; +VAL_ 131 GE_Schubabschalt_Unt 0 "inaktiv" 1 "aktiv" ; +VAL_ 131 GE_Freigabe_Synchro 0 "inaktiv" 1 "aktiv" ; +VAL_ 131 GE_HYB_DZ_Eingriff 0 "kein_Drehzahleingriff" 1 "Slip_Start" 2 "Low_Speed_Modus" ; +VAL_ 258 GE_Freig_Langfr_Schutzmom 0 "nicht freigegeben" 1 "freigegeben" ; +VAL_ 258 GE_Uefkt 1023 "Fehler" ; +VAL_ 258 GE_Zielgang 0 "Gang P/N (ausgekuppelt)" 1 "Gang 1" 2 "Gang 2" 3 "Gang 3" 4 "Gang 4" 5 "Gang 5" 6 "Gang 6" 7 "Gang 7" 8 "Gang R" 11 "Gang 8" 12 "Gang 9" 14 "Istgang nicht definiert" 15 "Fehler" ; +VAL_ 258 GE_StartStopp_Info 0 "Motorlauf_nicht_notwendig_(Stoppfreigabe)" 1 "Motoranlauf_nicht_zwingend_notwendig_(Stoppverbot,keine_Startanforderung)" 2 "Motoranlauf_zwingend_notwendig_(Startanforderung)" 3 "Systemfehler" ; +VAL_ 258 GE_Langfr_Schutzmom 1022 "Init" 1023 "Fehler" ; +VAL_ 258 GE_Waehlhebel 0 "UNDEFINED" 1 "INIT" 5 "P" 6 "R" 7 "N" 8 "D" 9 "S" 10 "E" 13 "T" 14 "T" ; +VAL_ 258 GE_Eingangsdrehz 16382 "Init" 16383 "Fehler" ; +VAL_ 258 GE_Notlauf 0 "kein Notlauf / Init" 1 "Getriebe im Notlauf" ; +VAL_ 258 GE_Codierung_MSG 0 "Codierung iO / Init" 1 "Codierung niO" ; +VAL_ 1089 GE_Index_Fahrwid 255 "Fehler" ; +VAL_ 1089 GE_Heizwunsch 0 "maximaler_Waermebedarf" 1 "kein_Waermebedarf" 2 "Kuehlbedarf" 3 "Notfall_(maximaler_Kuehlbedarf)" ; +VAL_ 1089 GE_OBD_Status 0 "MIL aus" 1 "MIL ein" ; +VAL_ 1089 GE_LFR_Adaption 0 "fuer_Adaption_geeignet" 1 "fuer_Adaption_nicht_geeignet" ; +VAL_ 1089 GE_OBD_AbsperrVent 0 "kein_Fehler" 1 "KS-" 2 "KS+" 3 "OC" 4 "OOR+" 5 "OOR-" 6 "RC+" 7 "RC-" 8 "KS+/OC" 9 "KS-/OC" 10 "KS-/KS+" 11 "KS-/KS+/OC" 12 "frei" 13 "frei" 14 "frei" 15 "frei" ; +VAL_ 1089 GE_Grenzkriechmoment 62 "Init" 63 "Fehler" ; +VAL_ 1089 GE_Charisma_FahrPr 0 "nicht_belegt" 1 "Programm_1" 2 "Programm_2" 3 "Programm_3" 4 "Programm_4" 5 "Programm_5" 6 "Programm_6" 7 "Programm_7" ; +VAL_ 1089 GE_Charisma_Status 0 "Init" 1 "verfuegbar" 2 "nicht_verfuegbar" 3 "asynchron_durch_Fahrerwunsch" ; +VAL_ 1089 GE_Charisma_Umschaltung 0 "Idle" 1 "Erkennung_Umschaltaufforderung" 2 "Steuerbotschaft_nicht_definiert" 3 "Umschaltung_verzoegert" ; +VAL_ 1089 GE_Freigabe_Verfallsinfo_WFS 0 "aus" 1 "ein" ; +VAL_ 1089 GE_Verlustmoment 255 "Fehler" ; +VAL_ 1089 GE_amax_moeglich 511 "Wert ist nicht definiert" ; +VAL_ 1089 GE_Sumpftemperatur 255 "Fehler" ; +VAL_ 1424 KY_Funkschl_Nr 0 "kein authorisierter Schluessel erkannt" 1 "aktive_Funkschluessel_Nr_01" 2 "aktive_Funkschluessel_Nr_02" 3 "aktive_Funkschluessel_Nr_03" 4 "aktive_Funkschluessel_Nr_04" 5 "aktive_Funkschluessel_Nr_05" 6 "aktive_Funkschluessel_Nr_06" 7 "aktive_Funkschluessel_Nr_07" 8 "aktive_Funkschluessel_Nr_08" 9 "ungueltig_09" 10 "ungueltig_10" 11 "ungueltig_11" 12 "ungueltig_12" 13 "ungueltig_13" 14 "ungueltig_14" 15 "ungueltig_15" ; +VAL_ 1424 KY_ID_Geb_autorisiert 0 "Schluessel_nicht_authorisiert" 1 "Schluessel authorisiert" ; +VAL_ 1424 KY_ID_Geb_steckt 0 "kein_Schluessel_im_Zuendschloss" 1 " Schluessel steckt im Zuendschloss" ; +VAL_ 1424 KY_FFB_Frequenz 1 "433 MHz" 2 "315 MHz" 3 "868 MHz" ; +VAL_ 1424 KY_HF_Aktiv 0 "Funktempfang_nicht_aktiv" 1 "HF_Funkempfang_aktiv" ; +VAL_ 1424 KY_LF_Aktiv 0 "Funktempfang_nicht_aktiv" 1 "LF_Funkempfang_aktiv" ; +VAL_ 1424 KY_ELV_verr 0 "ELV_nicht_verriegelt" 1 "ELV verriegelt" ; +VAL_ 1424 KY_ELV_entr 0 "ELV_nicht_entriegelt" 1 "ELV entriegelt" ; +VAL_ 1424 KY_ELV_enable_Anforderung 0 "Freigabe_nicht_angefordert" 1 "Freigabe ELV wird angefordert" ; +VAL_ 1424 KY_Valet_Parking 0 "kein_Valet_Schluessel_erkannt" 1 "Valet Schluessel erkannt" ; +VAL_ 1424 KY_Keyless_Verbau 0 "kein_Keyless_verbaut" 1 "Keyless verbaut" ; +VAL_ 1424 FBS_Warn_Lenkung_def 0 "iO" 1 "defekt" ; +VAL_ 1424 FBS_Warn_LenkVerriegelung_def 0 "i.O." 1 "defekt" ; +VAL_ 1424 FBS_Warn_Schluessel_Batt 0 "i.O." 1 "defekt" ; +VAL_ 1424 FBS_Prio_Warn_04 1 "Kombi Prio Warnung FBS 4" ; +VAL_ 1424 FBS_Prio_Warn_05 1 "Kombi Prio Warnung FBS 5" ; +VAL_ 1424 KYL_Warn_kein_Schluessel 1 "kein Schluessel erkannt" ; +VAL_ 1424 KYL_Warn_Kessy_defekt 0 "Kessy_i.O." 1 "Kessy defekt" ; +VAL_ 1424 KY_KYL_Prio_Warn_03 1 "Kombi Prio Warnung Keyless 3" ; +VAL_ 1424 KY_KYL_Prio_Warn_04 1 "Kombi Prio Warnung Keyless 4" ; +VAL_ 1424 KY_KYL_Prio_Warn_05 1 "Kombi Prio Warnung Keyless 5" ; +VAL_ 1424 KY_WFS_Safe 1 "WFS nicht deaktiviert" ; +VAL_ 1424 KY_WFS_LZ 0 "nicht def." 1 "LZ 1" 2 "LZ 2" 3 "LZ 3" ; +VAL_ 1424 KY_StartStopp_Info 0 "Motorlauf_nicht_notwendig_(Stoppfreigabe)" 1 "Motoranlauf_nicht_zwingend_notwendig_(Stoppverbot,keine_Startanforderung)" 2 "Motoranlauf_zwingend_notwendig_(Startanforderung)" 3 "Systemfehler" ; +VAL_ 1424 KYL_Notzuendschloss 0 "nicht_verbaut" 1 "verbaut" ; +VAL_ 1424 KYL_Warn_Notzuendschloss 0 "Aus" 1 "Ein" ; +VAL_ 1424 FBS_KD_Fehler 0 "kein_KD_Fehler" 1 "KD_Fehler" ; +VAL_ 960 ZV_verriegelt_extern_soll_02 1 "Fahrzeug verriegelt extern; Sollzusstand" ; +VAL_ 960 ZAS_Kl_S 0 "aus" 1 "S_Kontakt_ein" ; +VAL_ 960 ZAS_Kl_15 0 "aus" 1 "ein" ; +VAL_ 960 ZAS_Kl_X 0 "aus" 1 "ein" ; +VAL_ 960 ZAS_Kl_50 0 "aus" 1 "KL50_ein_Startwunsch_Fahrer" ; +VAL_ 959 KL_Drehz_Anh 0 "keine_Anhebung" 1 "Drehzahlanhebung_vom_Motor_angefordert" ; +VAL_ 959 KL_Vorwarn_Komp_ein 1 "Vorwarnung Kompressor ein" ; +VAL_ 959 KL_Handshake_BEM 0 "keine_Leistungsaenderung_in_den_Heizsystemen_aktiv" 1 "Heizleistungsaenderung_wird_gerade_durchgefuehrt" ; +VAL_ 959 KL_Komp_Moment_alt 1 "veraltet_bzw_Ermittlung_des_Moments_nicht_moeglich__zB_keine_Drehzahl_kein_Kaeltemitteldruck" ; +VAL_ 959 KL_Vorwarn_HHS_ein 1 "Vorwarnung_Heckscheibenheizung_ein" ; +VAL_ 959 KL_Vorwarn_HFS_ein 1 "Vorwarnung_Frontscheibenheizung_ein" ; +VAL_ 959 KL_Vorwarn_Zuheizer_ein 1 "Vorwarnung_Zuheizer_ein" ; +VAL_ 959 KL_KD_Fehler 0 "kein_KD_Fehler" 1 "KD_Fehler" ; +VAL_ 959 KL_Comp_rev_rq 255 "Fehler" ; +VAL_ 959 KL_Charisma_FahrPr 0 "nicht_belegt" 1 "Programm_1" 2 "Programm_2" 3 "Programm_3" 4 "Programm_4" 5 "Programm_5" 6 "Programm_6" 7 "Programm_7" ; +VAL_ 959 KL_Charisma_Status 0 "Init" 1 "verfuegbar" 2 "nicht_verfuegbar" 3 "asynchron_durch_Fahrerwunsch" ; +VAL_ 959 KL_Charisma_Umschaltung 0 "Idle" 1 "Erkennung_Umschaltaufforderung" 2 "Steuerbotschaft_nicht_definiert" 3 "Umschaltung_verzoegert" ; +VAL_ 959 KL_Last_Kompr 255 "Fehler" ; +VAL_ 959 KL_Anf_KL 255 "Fehler" ; +VAL_ 959 KL_4_Zonen 0 "2_Zonen_Klimaanlage" 1 "4_Zonen_Klimaanlage" ; +VAL_ 959 KL_AC_Schalter 0 "aus" 1 "ein" ; +VAL_ 959 KL_Zustand 0 "aus" 1 "ein" ; +VAL_ 959 KL_Thermomanagement 0 "keine_Freigabe_TMM__max_Heizbedarf" 1 "kleine_Freigabe_TMM" 2 "mittlere_Freigabe_TMM" 3 "volle_Freigabe_TMM__kein_Heizbedarf" ; +VAL_ 959 KL_Comp_enable 0 "Disable" 1 "Enable" ; +VAL_ 959 KL_StartStopp_Info 0 "Motorlauf_nicht_notwendig_(Stoppfreigabe)" 1 "Motoranlauf_nicht_zwingend_notwendig_(Stoppverbot,keine_Startanforderung)" 2 "Motoranlauf_zwingend_notwendig_(Startanforderung)" 3 "Systemfehler" ; +VAL_ 959 KL_Diag_Absperrvent 0 "kein_Fehler" 1 "KS-" 2 "KS+" 3 "OC" 4 "OOR+" 5 "OOR-" 6 "RC+" 7 "RC-" 8 "KS+/OC" 9 "KS-/OC" 10 "KS-/KS+" 11 "KS-/KS+/OC" ; +VAL_ 779 KBI_ABS_Lampe 0 "ABS Lampe aus" 1 "ABS Lampe ein" ; +VAL_ 779 KBI_ESP_Lampe 0 "ESP Lampe aus" 1 "ESP Lampe ein" ; +VAL_ 779 KBI_BKL_Lampe 0 "BKL aus" 1 "BKL ein" ; +VAL_ 779 KBI_Airbag_Lampe 0 "Airbag Lampe aus" 1 "Airbag Lampe ein" ; +VAL_ 779 KBI_SILA_gueltig 0 "ungueltig" 1 "gueltig" ; +VAL_ 779 KBI_Vorglueh_System_Lampe 0 "Lampe aus" 1 "Lampe ein" ; +VAL_ 779 KBI_NV_in_Anzeige 0 "NV_nicht_in_Anzeige" 1 "NV_in_Anzeige" ; +VAL_ 779 KBI_Anzeigestatus_ACC 0 "keine_ACC_Anzeige" 1 "ACC_Anzeige_aktiv" ; +VAL_ 779 KBI_Tankwarnung 0 "Lampe aus" 1 "Lampe ein" ; +VAL_ 779 KBI_MFA_v_Einheit_01 0 "kmh" 1 "mph" ; +VAL_ 779 KBI_im_Stellgliedtest 0 "kein Stellgliedtest" 1 "Kombi im Stellgliedtest" ; +VAL_ 779 KBI_Anzeigefehler_LDW 0 "nicht vorhanden bzw. unterst�tzt" 1 "Anzeige iO" 2 "Anzeigefehler" 3 "nicht definiert" ; +VAL_ 779 KBI_Variante_USA 0 "keine USA-Variante" 1 "USA-Variante" ; +VAL_ 779 KBI_Oeldruckwarnung 0 "inaktiv" 1 "aktiv" ; +VAL_ 779 KBI_Handbremse 0 "nicht_angezogen" 1 "angezogen" ; +VAL_ 779 KBI_PLA_in_Anzeige 0 "PLA_nicht_in_Anzeige" 1 "PLA_in_Anzeige" ; +VAL_ 779 KBI_Anzeigefehler_NV 0 "kein_Anzeigefehler" 1 "Anzeigefehler" ; +VAL_ 779 KBI_Einheit_Tacho 0 "km/h" 1 "mph" ; +VAL_ 779 KBI_Konsistenz_ACC 0 "ACC Botschaft konsistent" 1 "ACC Botschaft inkonsistent " ; +VAL_ 779 KBI_Fehler_Anzeige_ACC 0 " iO" 1 "Anzeigefehler ACC" ; +VAL_ 779 KBI_Anzeigefehler_SWA 0 "nicht vorhanden bzw. unterst�tzt" 1 "Anzeige iO" 2 "Anzeigefehler" 3 "nicht definiert" ; +VAL_ 779 KBI_KD_Fehler 0 "kein_KD_Fehler" 1 "KD_Fehler" ; +VAL_ 1719 KBI_Kilometerstand 1048574 "Init" 1048575 "Fehler" ; +VAL_ 1719 KBI_Reset_Standzeit 0 "Standzeit iO" 1 "KL30 war weg" ; +VAL_ 1719 KBI_Inhalt_Tank 127 "Fehler" ; +VAL_ 1719 KBI_FStatus_Tank 0 "Tankf�llstand i.O." 1 "Tankf�llstand n.i.O" ; +VAL_ 1719 KBI_QBit_Aussen_Temp_gef 0 "gueltiger_Wert" 1 "Ersatz_Init_oder_Fehlerwert" ; +VAL_ 1719 KBI_Aussen_Temp_gef 253 "nicht verbaut" 254 "Init" 255 "Fehler" ; +VAL_ 1720 WFS_Schluessel_Fahrberecht 0 "kein authorisierter Schluessel erkannt " 1 "aktive_Funkschluessel_Nr_01" 2 "aktive_Funkschluessel_Nr_02" 3 "aktive_Funkschluessel_Nr_03" 4 "aktive_Funkschluessel_Nr_04" 5 "aktive_Funkschluessel_Nr_05" 6 "aktive_Funkschluessel_Nr_06" 7 "aktive_Funkschluessel_Nr_07" 8 "aktive_Funkschluessel_Nr_08" 9 "ungueltig_09" 10 "ungueltig_10" 11 "ungueltig_11" 12 "ungueltig_12" 13 "ungueltig_13" 14 "ungueltig_14" 15 "ungueltig_15" ; +VAL_ 1720 KBI_BCmE_aktiv 0 "Anzeige_nicht_aktiv" 1 "Anzeige_aktiv" ; +VAL_ 1720 KBI_Sparhinweis_quittiert 0 "nicht_quittiert" 1 "quittiert" ; +VAL_ 285 EPS_Notlauf 0 "kein_Notlauf" 1 "Notlauf_Unterspannung" 2 "Notlauf_Ueberspannung" 3 "reserviert" 4 "Notlauf_Uebertemperatur" 5 "Notlauf_Unterspannung_und_Uebertemperatur" 6 "Notlauf_Ueberspannung_und_Uebertemperatur" 7 "reserviert" 8 "reserviert" 9 "reserviert" 10 "reserviert" 11 "reserviert" 12 "reserviert" 13 "reserviert" 14 "reserviert" 15 "reserviert" ; +VAL_ 285 EPS_Lastinfo 255 "Fehler" ; +VAL_ 285 EPS_Unterstuetzungsleistung 255 "Fehler" ; +VAL_ 285 EPS_Drehzahlreserve 127 "Fehler" ; +VAL_ 285 EPS_VZ_Drehzahlreserve 0 "positiv" 1 "negativ" ; +VAL_ 285 EPS_Leistungsanforderung 0 "keine_Anforderung" 1 "Anforderung_hoehere_Spannung_oder_Leistung" ; +VAL_ 1137 BCM2_Bremsl_durch_ECD 0 "Bremslicht_ist_aus" 1 "Bremslicht_durch_ECD_aktiv" ; +VAL_ 1137 LH_Aussenlicht_def 0 "OK" 1 "defekt" ; +VAL_ 1137 LH_Standlicht_H_aktiv 1 "Standlicht hinten aktiv" ; +VAL_ 1137 LH_Parklicht_HL_aktiv 0 "nicht aktiv" 1 "Parklicht hinten links aktiv" ; +VAL_ 1137 LH_Parklicht_HR_aktiv 0 "nicht aktiv" 1 "Parklicht hinten rechts aktiv" ; +VAL_ 1137 LH_Bremslicht_H_aktiv 1 "Bremslicht hinten aktiv" ; +VAL_ 1137 LH_Nebelschluss_aktiv 0 "nicht aktiv" 1 "aktiv" ; +VAL_ 1137 LH_Rueckfahrlicht_aktiv 0 "nicht aktiv" 1 "aktiv" ; +VAL_ 1137 LH_Blinker_HL_akt 1 "Blinker hinten links aktiv" ; +VAL_ 1137 LH_Blinker_HR_akt 1 "Blinker hinten rechts aktiv" ; +VAL_ 1137 LH_Blinker_li_def 0 "OK" 1 "Blinker hinten links defekt" ; +VAL_ 1137 LH_Bremsl_li_def 0 "OK" 1 "mindestens ein Bremslicht hinten links defekt" ; +VAL_ 1137 LH_Schlusslicht_li_def 0 "OK" 1 "mindestens ein Schlusslicht hinten links defekt" ; +VAL_ 1137 LH_Rueckf_li_def 0 "OK" 1 "R�ckfahrlicht hinten links defekt" ; +VAL_ 1137 LH_Nebel_li_def 0 "OK" 1 " Nebelschlusslicht hinten links defekt" ; +VAL_ 1137 LH_Schluss_Brems_Nebel_li_def 0 "iO" 1 "defekt" ; +VAL_ 1137 LH_Schluss_Brems_Nebel_re_def 0 "iO" 1 "defekt" ; +VAL_ 1137 LH_Schluss_Brems_li_def 0 "OK" 1 "defekt" ; +VAL_ 1137 LH_Schluss_Nebel_li_def 0 "OK" 1 "defekt" ; +VAL_ 1137 LH_SL_BRL_BLK_li_def 0 "OK" 1 "defekt" ; +VAL_ 1137 LH_Brems_Blk_li_def 0 "OK" 1 "defekt" ; +VAL_ 1137 LH_Blinker_re_def 0 "OK" 1 "Blinker hinten rechts defekt" ; +VAL_ 1137 LH_Bremsl_re_def 0 "OK" 1 "mindestens ein Bremslicht hinten rechts defekt" ; +VAL_ 1137 LH_Schlusslicht_re_def 0 "OK" 1 "mindestens ein Schlusslicht hinten rechts defekt" ; +VAL_ 1137 LH_Rueckf_re_def 0 "OK" 1 "R�ckfahrlicht hinten rechts defekt" ; +VAL_ 1137 LH_Nebel_re_def 0 "OK" 1 "Nebelschlusslicht hinten rechts defekt" ; +VAL_ 1137 LH_Schluss_Brems_re_def 0 "OK" 1 "defekt" ; +VAL_ 1137 LH_Schluss_Nebel_re_def 0 "OK" 1 "defekt" ; +VAL_ 1137 LH_SL_BRL_BLK_re_def 0 "OK" 1 "defekt" ; +VAL_ 1137 LH_Brems_Blk_re_def 0 "OK" 1 "defekt" ; +VAL_ 1137 LH_Kennzl_def 0 "OK" 1 "Kennzeichenbeleuchtung hinten defekt" ; +VAL_ 1137 LH_3_Bremsl_def 0 "OK" 1 "hochgesetzte Bremsleuchte defekt" ; +VAL_ 1137 LH_Nebel_mi_def 0 "OK" 1 " Nebelschlusslicht hinten Mitte defekt" ; +VAL_ 1137 LH_Rueckf_mi_def 0 "OK" 1 "R�ckfahllicht Mitte defekt" ; +VAL_ 1137 LH_Bremsl_li_ges_def 0 "OK" 1 "Alle Bremslichter hinten links defekt" ; +VAL_ 1137 LH_Bremsl_re_ges_def 0 "OK" 1 "Alle Bremslichter hinten rechts defekt" ; +VAL_ 267 LS_Hauptschalter 0 "Gerastet Aus" 1 "Ein" ; +VAL_ 267 LS_Abbrechen 0 "Tippschalter nicht betaetigt" 1 "Tippschalter betaetigt" ; +VAL_ 267 LS_Typ_Hauptschalter 0 "gerasteter_Lenkstockschalter" 1 "getasteter_Lenkstockschalter" ; +VAL_ 267 LS_Limiter 0 "Limiter aus" 1 "Limiter ein" ; +VAL_ 267 LS_Tip_Setzen 0 "Tippschalter nicht betaetigt" 1 "Tippschalter betaetigt" ; +VAL_ 267 LS_Tip_Hoch 0 "Tippschalter nicht betaetigt" 1 "Tippschalter betaetigt" ; +VAL_ 267 LS_Tip_Runter 0 "Tippschalter nicht betaetigt" 1 "Tippschalter betaetigt" ; +VAL_ 267 LS_Tip_Wiederaufnahme 0 "Tippschalter nicht betaetigt" 1 "Tippschalter betaetigt" ; +VAL_ 267 LS_Verstellung_Zeitluecke 0 "Taste nicht betaetigt" 1 "Dist -1" 2 "Dist +1" 3 "nicht belegt" ; +VAL_ 267 MFL_Tip_Down 0 "nicht_betaetigt" 1 "betaetigt" ; +VAL_ 267 MFL_Tip_Up 0 "nicht_betaetigt" 1 "betaetigt" ; +VAL_ 267 LS_Tiptronic_Fehler 0 " i. O." 1 "Fehler erkannt" ; +VAL_ 267 LS_Codierung 0 "kein Hebel, keine Tiptronic am Lenkrad" 1 "kein Hebel, Tiptronic am Lenkrad" 2 "GRA Hebel, keine Tiptronic am Lenkrad" 3 "GRA Hebel, Tiptronic am Lenkrad" 4 "ACC Hebel, keine Tiptronic am Lenkrad" 5 "ACC Hebel, Tiptronic am Lenkrad" 6 "nicht verwendet" 7 "nicht verwendet" ; +VAL_ 267 LS_Tip_Stufe_2 0 "Hebelbetaetigung_in_erster_Tipstufe__Keine_Hebelbetaetigung" 1 "Hebelbetaetigung_in_der_zweiten_Tipstufe" ; +VAL_ 267 LS_GRA_ACC_2stufig 0 "kein_zweistufiger_Hebel_verbaut" 1 "zweistufiger_Hebel_verbaut" ; +VAL_ 267 MFL_M_Taste 0 "nicht_betaetigt" 1 "betaetigt" ; +VAL_ 134 LWI_Sensorstatus 0 "iO" 1 "nicht kalibriert" ; +VAL_ 134 LWI_QBit_Sub_Daten 0 "LWS-Subinfo 'real' (Lenkradwinkelinformation ADS-tauglich) " 1 "LWS-Subinfo 'simuliert' (Lenkradwinkelinformation nicht ADS-tauglich )" ; +VAL_ 134 LWI_QBit_Lenkradwinkel 0 "g�ltiger Wert" 1 "ausserhalb der Spezifikation" ; +VAL_ 134 LWI_Lenkradwinkel 8190 "Init" 8191 "Fehler" ; +VAL_ 134 LWI_VZ_Lenkradwinkel 0 "positiv_links_von_der_Nullstellung" 1 "negativ" ; +VAL_ 134 LWI_VZ_Lenkradw_Geschw 0 "positiv_links_von_der_Nullstellung" 1 "negativ" ; +VAL_ 134 LWI_Lenkradw_Geschw 510 "Init" 511 "Fehler" ; +VAL_ 128 MO_Mom_o_ex 1022 "Init" 1023 "Fehler" ; +VAL_ 128 MO_Mom_m_ex 1022 "Init" 1023 "Fehler" ; +VAL_ 128 MO_Mom_Verlust 1022 "Init" 1023 "Fehler" ; +VAL_ 128 MO_Mom_Begrenzung 1022 "Init" 1023 "Fehler" ; +VAL_ 128 MO_Mom_Fahrerwunsch 1022 "Init" 1023 "Fehler" ; +VAL_ 128 MO_Kickdown 0 "kein Kickdown" 1 "Kickdown" ; +VAL_ 128 MO_KD_Fehler 0 "kein_KD_Fehler" 1 "KD_Fehler" ; +VAL_ 129 MO_Mom_ZWR 1022 "Init" 1023 "Fehler" ; +VAL_ 129 MO_Mom_Soll 1022 "Init" 1023 "Fehler" ; +VAL_ 129 MO_Mom_Ist 1022 "Init" 1023 "Fehler" ; +VAL_ 129 MO_Status_Zylabschalt_01 0 "alle Zylinder brennen" 1 "mindestens ein Zylinder wurde abgeschaltet" ; +VAL_ 129 MO_Status_Normalbetrieb_01 0 "kein Normalbetrieb" 1 "Normalbetrieb erreicht" ; +VAL_ 129 MO_StartStopp_Status 0 "System_in_diesem_KL15_Zyklus_nicht_verfuegbar" 1 "System_aktiv_keine_Freigabe_durch_StartStop_Koordinator" 2 "System_aktiv_alle Freigaben_liegen_vor" 3 "System_aktiv_mindestens_eine_Freigabe_fehlt" ; +VAL_ 129 MO_StartStopp_Motorstopp 0 "Motor_Stop_inaktiv" 1 "Motor_Stop_aktiv" ; +VAL_ 129 MO_StartStopp_Wiederstart 0 "Wiederstart_inaktiv" 1 "Wiederstart_aktiv" ; +VAL_ 129 MO_Ext_E_Fahrt_aktiv 0 "Rueckmeldung_E_Taster_aus " 1 "Rueckmeldung_E_Taster_ein" ; +VAL_ 129 MO_Gangposition 0 "Gang_N" 1 "Gang_1" 2 "Gang_2" 3 "Gang_3" 4 "Gang_4" 5 "Gang_5" 6 "Gang_6" 7 "Gang_7" 8 "Gang_8" 12 "Zwischengangstellung" 13 "Gang_R" 14 "Istgang_nicht_definiert" 15 "Fehler" ; +VAL_ 129 MO_StartStopp_Fahrerwunsch 0 "Init" 1 "Stoppverbot_durch_Fahrer" 2 "Stoppfreigabe_durch_Fahrer" 3 "Stoppanforderung_durch_Fahrer" ; +VAL_ 261 MO_QBit_Fahrpedalwerte_01 0 "gueltiger_Wert" 1 "Ersatz_Init_oder_Fehlerwert" ; +VAL_ 261 MO_QBit_Motormomente 0 "gueltiger_Wert" 1 "Ersatz_Init_oder_Fehlerwert" ; +VAL_ 261 MO_QBit_Fahrer_bremst 0 "gueltiger_Wert" 1 "Ersatz_Init_oder_Fehlerwert" ; +VAL_ 261 MO_QBit_Drehzahl_01 0 "gueltiger_Wert" 1 "Ersatz_Init_oder_Fehlerwert" ; +VAL_ 261 MO_Drehzahl_01 65535 "Fehler" ; +VAL_ 261 MO_Moment_im_Leerlauf 0 "kein_Leergas" 1 "Leergas" ; +VAL_ 261 MO_Interlock 0 "Interlockschalter nicht bet�tigt" 1 "Interlockschalter bet�tigt" ; +VAL_ 261 MO_BLS 0 "kein Bremsen" 1 "Bremse bet�tigt" ; +VAL_ 261 MO_Fahrer_bremst 0 "kein Bremsen" 1 "Bremse bet�tigt" ; +VAL_ 261 MO_Konsistenz_Bremsped 0 "Bremspedalinformation_plausibel" 1 "Bremspedalinformation_unplausibel" ; +VAL_ 261 MO_Kuppl_schalter 0 "Schalter sagt nicht bet�tigt (Eingekuppelt)" 1 "Schalter sagt bet�tigt (Ausgekuppelt)" ; +VAL_ 261 MO_Timeout_ESP 0 "Empfang i.O." 1 "Timeout" ; +VAL_ 261 MO_Motor_laeuft 0 "Motor l�uft nicht" 1 "Motor l�uft autark und stabil und darf mechanisch belastet werden" ; +VAL_ 261 MO_Solldrehz_Leerlauf 255 "Fehler" ; +VAL_ 261 MO_Fahrpedalrohwert_01 255 "Fehler" ; +VAL_ 261 MO_erste_Ungenauschwelle 0 "genau" 1 "Momente ungenauer >8%" ; +VAL_ 261 MO_QBit_Stressfaktor 0 "gueltiger_Wert" 1 "Ersatz_Init_oder_Fehlerwert" ; +VAL_ 263 MO_Istgang 0 "kein_Gang_eingelegt" 1 "Gang_1" 2 "Gang_2" 3 "Gang_3" 4 "Gang_4" 5 "Gang_5" 6 "Gang_6" ; +VAL_ 263 MO_Sollgang 0 "keine_Empfehlung" 1 "Gang_1" 2 "Gang_2" 3 "Gang_3" 4 "Gang_4" 5 "Gang_5" 6 "Gang_6" ; +VAL_ 263 MO_Oeldruck 255 "Fehler" ; +VAL_ 263 MO_Anzeigedrehz 4095 "Fehler" ; +VAL_ 263 MO_Schaltempf_verfbar 0 "nicht_verfuegbar" 1 "verfuegbar" ; +VAL_ 263 MO_Ladedruck 511 "Fehler" ; +VAL_ 263 MO_KVS_Ueberlauf 0 "kein Ueberlauf" 1 "Kraftstoffverbrauchsignale mindestens 1x �bergelaufen" ; +VAL_ 782 MO_EKlKomLeiRed 0 "keine_Leistungsbegr" 1 "Leistungsbegr_75" 2 "Leistungsbegr_50" 3 "Leistungsbegr_25" ; +VAL_ 782 MO_Freig_Reku 0 "Rekuperations-Modus aus" 1 "Empfehlung Spannungsanhebung" 2 "Empfehlung Spannungsabsenkung" 3 "Rekuperationsmodus aktiv, Spannungsvariation nicht notwendig" ; +VAL_ 782 MO_Klima_Eingr 0 "kein Eingriff" 1 "Klimakompressor ausschalten" 2 "Klimakompressor Leistungsreduzierung" 3 "Klimakompressor aufgrund der Heissleuchtenvorwarnung ausschalten" ; +VAL_ 782 MO_Status_Normalbetrieb_02 0 "kein Normalbetrieb" 1 "Normalbetrieb erreicht" ; +VAL_ 782 MO_Prio_MIN_Wunschdrehzahl 0 "Wunsch" 1 "Zwang" ; +VAL_ 782 MO_Freig_Anlass 0 "Start nicht zul�ssig" 1 "Startfreigabe" ; +VAL_ 782 MO_Aussp_Anlass 0 "Motor l�uft nicht stabil" 1 "Anlasser ausspuren (Motor l�uft stabil)" ; +VAL_ 782 MO_MAX_Wunschdrehzahl 511 "Fehler" ; +VAL_ 782 MO_Prio_MAX_Wunschdrehzahl 0 "Wunsch" 1 "Zwang" ; +VAL_ 782 MO_Luftpfad_aktiv 0 "kein Eingriff oder nur Eingriff �ber Z�ndpfad" 1 "Eingriff �ber Luftpfad" ; +VAL_ 782 MO_v_Begrenz_Aktiv 0 "inaktiv" 1 "aktiv" ; +VAL_ 782 MO_v_Begrenz_Aktivierbar 0 "V-Begrenzung nicht m�glich" 1 "V-Begrenzung m�glich" ; +VAL_ 782 MO_Verbot_EKP 0 "Ansteuerung zugelassen" 1 "Ansteuerung verboten" ; +VAL_ 782 MO_Anf_Pruefimpuls 0 "keine Anforderung" 1 "Anforderung" ; +VAL_ 782 MO_Anf_KL75 0 "Anforderung KL75 ausschalten" 1 "Anforderung KL75 einschalten" ; +VAL_ 782 MO_Charisma_FahrPr 0 "nicht_belegt" 1 "Programm_1" 2 "Programm_2" 3 "Programm_3" 4 "Programm_4" 5 "Programm_5" 6 "Programm_6" 7 "Programm_7" ; +VAL_ 782 MO_Charisma_Status 0 "Init" 1 "verfuegbar" 2 "nicht_verfuegbar" 3 "asynchron_durch_Fahrerwunsch" ; +VAL_ 782 MO_Charisma_Umschaltung 0 "Idle" 1 "Erkennung_Umschaltaufforderung" 2 "Steuerbotschaft_nicht_definiert" 3 "Umschaltung_verzoegert" ; +VAL_ 782 MO_Handshake_STH 0 "keine EKP-Ansteuerung durch STH-Anforderung" 1 "EKP-Ansteuerung durch STH-Anforderung" ; +VAL_ 782 MO_MIN_Wunschdrehzahl 255 "Fehler" ; +VAL_ 1088 MO_Kuehlerluefter_MUX 0 "Kuehlerluefter_1" 1 "Kuehlerluefter_2" ; +VAL_ 1088 MO_Kuehlerluefter_1 126 "Init" 127 "Fehler" ; +VAL_ 1088 MO_Kuehlerluefter_2 126 "Init" 127 "Fehler" ; +VAL_ 1088 MO_HYB_Status_HV_Ladung 0 "HV-Ladung_nicht_notwendig" 1 "HV-Ladung_notwendig_Freigaben_erforderlich" 2 "HV-Ladung laeuf" 3 "HV-Ladung_erfolgreich_Motorstart_moeglich" 4 "HV_Ladung_abgebrochen" ; +VAL_ 1088 WIV_Anzeige_aktiv 0 "Anzeige aus" 1 "WIV Anzeige aktiv" ; +VAL_ 1088 WIV_Oelmin_Warn 0 "in_Ordnung" 1 "Warnung" ; +VAL_ 1088 WIV_Sensorfehler 0 "in_Ordnung" 1 "Sensor_defekt" ; +VAL_ 1088 WIV_Schieflage 0 "Fahrzeug_gerade" 1 "Fahrzeug_in_Schieflage" ; +VAL_ 1088 MO_Zustand_HWP 0 "HWP_nicht_schaltbar" 1 "HWP_foerdert_nicht" 2 "HWP_foerdert" 3 "reserviert" ; +VAL_ 1088 WIV_Oelsystem_aktiv 0 "Anzeige_aus" 1 "Anzeige_aktiv" ; +VAL_ 1088 WIV_nicht_betriebswarm 0 "Motor_warm" 1 "Motor_nicht_betriebswarm" ; +VAL_ 1088 WIV_Ueberfuell_Warn 0 "in_Ordnung" 1 "Ueberfuellwarnung" ; +VAL_ 1088 WIV_laufender_Motor 0 "Messung_moeglich" 1 "Messung_nicht_moeglich" ; +VAL_ 1088 MO_HYB_Text_1 0 "kein_Text" 1 "Text_anzeigen" ; +VAL_ 1088 MO_HYB_Text_2 0 "kein_Text" 1 "Text_anzeigen" ; +VAL_ 1088 MO_HYB_Text_3 0 "kein_Text" 1 "Text_anzeigen" ; +VAL_ 1088 MO_Text_Motorstart 0 "keine_Anzeige" 1 "Motor_im_Stoppbetrieb" 2 "StartStopp_sicherheitsbedingt_deaktiviert" 3 "System_fordert_Wiederstart" 5 "Motorlauf_noetig" 9 "Unerwuenschter_Motorstillstand" 12 "Motor_startet" 13 "Kupplung_betaetigen" 14 "Waehlhebel_in_PN_Position" 15 "Bremse_treten" ; +VAL_ 1088 MO_HYB_Text_5 0 "kein_Text" 1 "Text_anzeigen" ; +VAL_ 1088 MO_HYB_Text_6 0 "kein_Text" 1 "Text_anzeigen" ; +VAL_ 1088 MO_HYB_Text_7 0 "kein_Text" 1 "Text_anzeigen" ; +VAL_ 1088 WIV_Oeldyn_avl 0 "Oeldyn_nicht_vorhanden" 1 "Oeldyn_vorhanden" ; +VAL_ 1088 MO_Systemlampe 0 "Lampe aus" 1 "Lampe ein" ; +VAL_ 1088 MO_OBD2_Lampe 0 "Lampe aus" 1 "Lampe ein" ; +VAL_ 1088 MO_Heissleuchte 0 "Lampe aus" 1 "Lampe ein" ; +VAL_ 1088 MO_Partikel_Lampe 0 "Lampe aus" 1 "Lampe ein" ; +VAL_ 1088 WIV_Oelstand_nicht_vorhanden 0 "�lstand vorhanden" 1 "�lstand nicht vorhanden" ; +VAL_ 1088 WIV_nachfuellanzeige_ein 0 "keine_Nachfuellanzeige" 1 "Nachfuellanzeige" ; +VAL_ 1088 WIV_Ueberfuell_deaktiv 0 "Ueberfuellwarnung_am_Kombi_aktiv" 1 "Ueberfuellwarnung_am_Kombi_deaktiv" ; +VAL_ 1088 WIV_Unterfuell_Warn 0 "in_Ordnung" 1 "Unterfuellwarnung" ; +VAL_ 1088 MO_Tankdeckel_Lampe 0 "Lampe aus" 1 "Lampe ein" ; +VAL_ 1088 MO_Text_Tankdeckelwarn 0 "kein Text" 1 "Anzeige Text Tankdeckelwarnung im Kombi" ; +VAL_ 1088 WIV_Enable_Oeldr_Motor 0 "Oeldruckauswertung_im_Kombi" 1 "Oeldruckauswertung_im_MSG" ; +VAL_ 1088 WIV_Oeldr_Warn_Motor 0 "keine_Warnung" 1 "niedrige_Oeldruckstufe_nicht_erreicht " ; +VAL_ 1088 MO_Avus_Motorschutz 0 "keine Warnung" 1 "Drehzahlwarnung Stufe 1" 2 "Drehzahlwarnung Stufe 2" 3 "Drehzahlwarnung Stufe 3" ; +VAL_ 1088 MO_HYB_Fahrbereitschaft 0 "keine_Fahrbereitschaft" 1 "Fahrbereitschaft" ; +VAL_ 1600 MO_QBit_Ansaugluft_Temp 0 "gueltiger_Wert" 1 "Ersatz_Init_oder_Fehlerwert" ; +VAL_ 1600 MO_QBit_Oel_Temp 0 "gueltiger_Wert" 1 "Ersatz_Init_oder_Fehlerwert" ; +VAL_ 1600 MO_QBit_Kuehlmittel_Temp 0 "gueltiger_Wert" 1 "Ersatz_Init_oder_Fehlerwert" ; +VAL_ 1600 MO_Stellgliedtest_Soundaktuator 0 "kein_Stellgliedtest" 1 "Anforderung_des_Stellgliedtest" ; +VAL_ 1600 MO_HYB_Fehler_HV_Netz 0 "i_O" 1 "kein_generatorischer_Betrieb_moeglich" ; +VAL_ 1600 MO_aktives_Getriebeheizen 0 "kein_Ventil_ansteuern" 1 "Ventil_muss_angesteuert_werden" ; +VAL_ 1600 MO_Absperrventil_oeffnen 0 "nicht_verfuegbar" 1 "Ansteuerung_Ventil_zulaessig" 2 "Ventil_oeffnen_oder_geoeffnet" 3 "Ventil_schliessen_oder_geschlossen" ; +VAL_ 1600 MO_Ansaugluft_Temp 254 "Init" 255 "Fehler" ; +VAL_ 1600 MO_Oel_Temp 253 "nicht_verbaut" 254 "Init" 255 "Fehler" ; +VAL_ 1600 MO_Kuehlmittel_Temp 254 "Init" 255 "Fehler" ; +VAL_ 1600 MO_Hoeheninfo 255 "Fehler" ; +VAL_ 1600 MO_Kennfeldk 0 "keine Kennfeldk�hlung vorhanden" 1 "Kennfeldk�hlung vorhanden" ; +VAL_ 1600 MO_Versionsinfo 0 "zum Projektbeginn 'aufger�umter CAN' " 1 "Motor_03_mit_10ms" 16 "MQB_mit_neuer_Momentenschnittstelle" ; +VAL_ 1600 MO_Getriebe_kuehlen 0 "nicht_kuehlen" 1 "kuehlen" ; +VAL_ 1600 MO_Heizungspumpenansteuerung 15 "nicht_verbaut" ; +VAL_ 1600 MO_SpannungsAnf 0 "keine_Anforderung" 1 "Anforderung" ; +VAL_ 1607 MO_ITM_Kuehlmittel_Temp 0 "nicht_verbaut" 2 "Fehler" ; +VAL_ 1607 MO_E85_Sensor 13 "nicht_verbaut" 15 "Fehler" ; +VAL_ 1607 SCR_Anz_Motorstarts 15 "keine Einschr�nkung (Anzeige Reichweite)" ; +VAL_ 1607 SCR_Reichweite 32767 "Init" ; +VAL_ 1607 SCR_Warnstufe_1 0 "nicht aktiv" 1 "Warnstufe 1 aktiv" ; +VAL_ 1607 SCR_Warnstufe_2 0 "nicht aktiv" 1 "Warnstufe 2 aktiv" ; +VAL_ 1607 SCR_Text 0 "kein Text" 1 "Warntext 1" 2 "Warntext 2" 3 "Hinweistext (nur AUDI)" 4 "Reserve" 5 "Warntext 'SCR-Systemfehler Stufe 1'" 6 "Warntext 'SCR-Systemfehler Stufe 2'" ; +VAL_ 1607 SCR_Akustik 0 "keine Akustik" 1 "Akustik 1" 2 "Akustik 2" 3 "Akustik_bei_Hinweis_(VW)" ; +VAL_ 1607 MO_Kraftstofffilter_Wasser 0 "keine_Anzeige" 1 "Abscheidevolumen_erschoepft" ; +VAL_ 1607 SCR_Systemfehler 0 "Warnung_nicht_aktiv" 1 "Warnung_aktiv" ; +VAL_ 1607 SCR_Inducement_Strategie 0 "Restart_Strategie" 1 "Reduced_Drivability_Strategie" ; +VAL_ 1607 MO_CO2_Faktor 0 "nicht_verbaut" 4095 "Fehler" ; +VAL_ 1607 MO_MKB_MUX 0 "MKB_01" 1 "MKB_02" 2 "MKB_03" 3 "MKB_04" ; +VAL_ 1607 MO_MKB_01 0 "Minus" 1 "A" 2 "B" 3 "C" 4 "D" 5 "E" 6 "F" 7 "G" 8 "H" 9 "I" 10 "J" 11 "K" 12 "L" 13 "M" 14 "N" 15 "O" 16 "P" 17 "Q" 18 "R" 19 "S" 20 "T" 21 "U" 22 "V" 23 "W" 24 "X" 25 "Y" 26 "Z" 27 "Leerzeichen" 28 "Leerzeichen" 29 "Leerzeichen" 30 "Leerzeichen" 31 "Unterstrich" ; +VAL_ 1607 MO_MKB_02 0 "Minus" 1 "A" 2 "B" 3 "C" 4 "D" 5 "E" 6 "F" 7 "G" 8 "H" 9 "I" 10 "J" 11 "K" 12 "L" 13 "M" 14 "N" 15 "O" 16 "P" 17 "Q" 18 "R" 19 "S" 20 "T" 21 "U" 22 "V" 23 "W" 24 "X" 25 "Y" 26 "Z" 27 "Leerzeichen" 28 "Leerzeichen" 29 "Leerzeichen" 30 "Leerzeichen" 31 "Unterstrich" ; +VAL_ 1607 MO_MKB_03 0 "Minus" 1 "A" 2 "B" 3 "C" 4 "D" 5 "E" 6 "F" 7 "G" 8 "H" 9 "I" 10 "J" 11 "K" 12 "L" 13 "M" 14 "N" 15 "O" 16 "P" 17 "Q" 18 "R" 19 "S" 20 "T" 21 "U" 22 "V" 23 "W" 24 "X" 25 "Y" 26 "Z" 27 "Leerzeichen" 28 "Leerzeichen" 29 "Leerzeichen" 30 "Leerzeichen" 31 "Unterstrich" ; +VAL_ 1607 MO_MKB_04 0 "Minus" 1 "A" 2 "B" 3 "C" 4 "D" 5 "E" 6 "F" 7 "G" 8 "H" 9 "I" 10 "J" 11 "K" 12 "L" 13 "M" 14 "N" 15 "O" 16 "P" 17 "Q" 18 "R" 19 "S" 20 "T" 21 "U" 22 "V" 23 "W" 24 "X" 25 "Y" 26 "Z" 27 "Leerzeichen" 28 "Leerzeichen" 29 "Leerzeichen" 30 "Leerzeichen" 31 "Unterstrich" ; +VAL_ 276 MO_Sig_Fahrpedalgradient 0 "Fahrpedalgradient positiv" 1 "Fahrpedalgradient negativ" ; +VAL_ 276 MO_BKV_Unterdruckwarnung 0 "Unterdruckhaushalt_iO" 1 "Unterdruckhaushalt_niO" ; +VAL_ 276 MO_Zylinderabschaltung 0 "Vollmotorbetrieb_VMB" 1 "Uebergang_HMB_in_VMB" 2 "Uebergang_VMB_in_HMB" 3 "Halbmotorbetrieb_HMB" ; +VAL_ 276 MO_Fahrpedalgradient 255 "Fehler" ; +VAL_ 276 MO_Schubabschaltung 0 "keine_Schubabschaltung" 1 "Schubabschaltung_aktiv" ; +VAL_ 276 MO_rel_Saugrohrdruck 0 "Init_Ueberdruck" 63 "Fehler" ; +VAL_ 276 MO_rel_Saugrohrdruck_gem_err 0 "errechnet" 1 "gemessen" ; +VAL_ 276 MO_BKV_Unterdruck 255 "Fehler" ; +VAL_ 1648 MO_Anzahl_Abgesch_Zyl 0 "Vollmotorbetrieb" 1 "1_Zylinder_abgeschaltet" 2 "2_Zylinder_abgeschaltet" 3 "3_Zylinder_abgeschaltet" 4 "4_Zylinder_abgeschaltet" 5 "5_Zylinder_abgeschaltet" 6 "6_Zylinder_abgeschaltet" 7 "8_Zylinder_abgeschaltet" ; +VAL_ 1648 MO_Zylabsch_Texte 0 "keine_Texte" 1 "Zylinderabschaltung_deaktivieren" 2 "Zylinderabschaltung_aktivieren" 3 "Zylinderabschaltung_unruhig" ; +VAL_ 1648 MO_E85_BS_Texte 0 "kein Text" 1 "FlexFuel Warm_Up_ Lampe" 2 "FlexFuel Warnung 3.Stufe " 3 "FlexFuel Warnung 1.Stufe " 4 "FlexFuel Warnung 2.Stufe " 5 "FlexFuel Warnung 4.Stufe " ; +VAL_ 1648 MO_Drehzahl_Warnung 0 "keinen_Warnhinweis_anzeigen" 1 "Warnhinweis_anzeigen" ; +VAL_ 1010 MO_SCR_Tankheizung 0 "Heizung_aus" 1 "Heizung_ein" ; +VAL_ 1010 MO_SCR_Dosierpumpe_Zustand 0 "frei" 1 "Drehzahlregelung" 2 "Druckregelung_langsam" 3 "Druckregelung_schnell" 4 "Pumpe_Stop" 5 "Rueckwaertsbetrieb" 6 "verzoegerter_Rueckwaertsbetrieb" 7 "Pumpe_heizen" ; +VAL_ 1010 MO_SCR_Leitungsheizung 0 "Heizung_aus" 1 "Heizung_ein" ; +VAL_ 1010 MO_SCR_Dosierpumpe_Wartezeit 125 "nicht_verbaut" 127 "Fehler" ; +VAL_ 1010 MO_SCR_Transferpumpe 0 "Pumpe_aus" 1 "Pumpe_ein" ; +VAL_ 1601 MO_Faktor_Momente 0 "nicht belegt" 1 "Faktor: x 0,5Nm" 2 "Faktor: x 1,0Nm" 3 "Faktor: x 2,0Nm" ; +VAL_ 1601 MO_Hybridfahrzeug 0 "kein_Hybridfahrzeug" 1 "Mild_Hybrid" 2 "Full_Hybrid" ; +VAL_ 1601 MO_Getriebe_Code 2 "DL501" 4 "VL381" 10 "AL651" 11 "AL551, AL951, AL1000-8A" 12 "PDK_PAG" 13 "AL551_Hybrid" 15 "Handschalter (konventionell)" 16 "AQ250" 17 "AQ450" 18 "DQ200" 19 "DQ250" 20 "DQ500" 21 "SQ100" 22 "SQ200" ; +VAL_ 1601 MO_StartStopp_Codiert 0 "Start_Stopp_nicht_verbaut" 1 "Start_Stopp_verbaut" ; +VAL_ 1601 MO_Kraftstoffart 0 "Diesel" 1 "Benzin" 2 "CNG" 3 "Erdgas" 4 "Wasserstoff" ; +VAL_ 1601 MO_Ansaugsystem 0 "Turbo" 1 "Sauger" ; +VAL_ 1601 MO_Einspritzart 0 "MPI" 1 " FSI / TDI" ; +VAL_ 969 MOS_KD_Fehler 0 "kein_KD_Fehler" 1 "KD_Fehler" ; +VAL_ 1696 NV_aktiv 0 "NV nicht aktiv" 1 "NV aktiv" ; +VAL_ 1696 NV_Texte 0 "kein_Text" 1 "Abblendlicht_einschalten" 2 "Fussgaengermarkierung_nicht_verfuegbar" 3 "zur_Zeit_nicht_verfuegbar" 4 "Systemfehler" ; +VAL_ 1696 NV_Gong 0 "kein_Gong" 1 "Gong_leise" 2 "Gong_mittel" 3 "Gong_laut" ; +VAL_ 1696 NV_Symbol 0 "kein_Symbol_anzeigen" 1 "Symbol_fuer_erkanntes_Objekt_anzeigen" ; +VAL_ 1696 NV_Hinweise 0 "keine_Anzeige" 1 "Disclaimer" 2 "Fussgaenger_Markierung_nicht_verfuegbar" 3 "Nachtsichtsystem_wird_initialisiert" ; +VAL_ 1696 NV_Piktogramm_aktiv 0 "keine_Anzeigenprioritaet" 1 "Anzeigenprioritaet" ; +VAL_ 1696 NV_Akustik_deaktiviert_Icon 0 "aus" 1 "ein" ; +VAL_ 1696 NV_FGM_deaktiviert_Icon 0 "aus" 1 "ein" ; +VAL_ 1696 NV_KD_Fehler 0 "kein_KD_Fehler" 1 "KD_Fehler" ; +VAL_ 1753 NMH_EPB_Start_1 1 "Zustand Start (<--Sleep)" ; +VAL_ 1753 NMH_EPB_Start_2 1 "Zustand Start (<--Prepare to Sleep)" ; +VAL_ 1753 NMH_EPB_Normal_Mode_1 1 "Zustand Normal Mode (<-- Start)" ; +VAL_ 1753 NMH_EPB_Normal_Mode_2 1 "Zustand Normal Mode (<-- Ready to Sleep)" ; +VAL_ 1753 NMH_EPB_Per_WakeUp 0 "Wenn Funktions-Wakeup" 1 "CAN-Wakeup" 2 "Periphrie-Wakeup Ursache nicht bekannt" 3 "Klemme 15 HW (falls vorhanden)" 4 "t.b.d." 5 "Schalter_EPB" ; +VAL_ 1753 NMH_EPB_Fkt_WakeUp 0 "Wenn Peripherie-Wakeup" ; +VAL_ 1753 NMH_EPB_NM_aktiv_Klemme_15 1 "Klemme 15 EIN" ; +VAL_ 1753 NMH_EPB_NM_aktiv_Diagnose 1 "Diagnose bei Kl 15 aus" ; +VAL_ 1753 NMH_EPB_NM_aktiv_Start 1 "Zustand 'START' (NM-high)" ; +VAL_ 1753 NMH_EPB_NM_aktiv_Schalter 1 "Schalter aktiv" ; +VAL_ 1753 NMH_EPB_NM_aktiv_Bedarf_Anzeige 1 "Kombi-Anzeige EPB" ; +VAL_ 1753 NMH_EPB_NM_aktiv_v_groesser_Null 1 "v > 0" ; +VAL_ 1753 NMH_EPB_kein_NL 1 "kein lokaler Nachlauf" ; +VAL_ 1753 NMH_EPB_NL_Temp_Modell 1 "Temperaturmodell aktiv" ; +VAL_ 1753 NMH_EPB_NL_AutoAdjust 0 "AutoAdjust_nicht_aktiv" 1 "AutoAdjust_aktiv" ; +VAL_ 1753 NM_EPB_Signalfehler 1 "Aktiver_Signalfehler_eingetragen" ; +VAL_ 1753 NMH_EPB_TimeOut_Fehler 1 "Aktiver Timeout Fehlerspeichereintrag " ; +VAL_ 1753 NMH_EPB_CAN_Diag_deaktiv 1 "CAN-Diagnose deaktiv" ; +VAL_ 1753 NMH_EPB_KompSchutz 1 "KS aktiv" ; +VAL_ 1753 NMH_EPB_Mute_Mode 1 "MuteMode aktiv" ; +VAL_ 1753 NMH_EPB_Transport_Mode 1 "Transportmodus aktiv" ; +VAL_ 1753 NMH_EPB_Abschaltstufe_aktiv 1 "Abschaltstufe aktiv" ; +VAL_ 1753 NMH_EPB_Eindraht_Fehler 1 "Eindrahtbetrieb erkannt" ; +VAL_ 1753 NMH_EPB_Lokalaktiv 0 "war nicht Lokalaktiv" 1 "war Lokalaktiv" ; +VAL_ 1753 NMH_EPB_Subsystemaktiv 0 "Subsystem war nicht lokalaktiv" 1 "war Lokalaktiv" ; +VAL_ 1728 NMH_GW_Start_1 1 "Zustand Start (<--Sleep)" ; +VAL_ 1728 NMH_GW_Start_2 1 "Zustand Start (<--Prepare to Sleep)" ; +VAL_ 1728 NMH_GW_Normal_Mode_1 1 "Zustand Normal Mode (<-- Start)" ; +VAL_ 1728 NMH_GW_Normal_Mode_2 1 "Zustand Normal Mode (<-- Ready to Sleep)" ; +VAL_ 1728 NMH_GW_Per_WakeUp 0 "Wenn_FunktionsWakeup" 1 "CAN_Wakeup__Weckendes_CAN_Segment_siehe_NMH_GW_WakeUp_CAN_Bus" 2 "P_WakeUp_Ursache_unbekannt" 3 "Klemme_15HW__falls_vorhanden" 4 "MOST_Wakeup" 5 "LIN_Wakeup" 6 "KL30_Reset" ; +VAL_ 1728 NMH_GW_Fkt_WakeUp 0 "Wenn_Peripherie_Wakeup" 1 "Funktionswakeup_EM" 2 "Car_Wakeup_empfangen" 3 "VNSM_VehicleNetworkStateManager" 4 "Alarm_RTC__Wecken_weil_Weckzeit_abgelaufen" 5 "Wecken_durch_Diagnose" ; +VAL_ 1728 NMH_GW_NM_aktiv_Klemme_15 1 "Klemme 15 EIN" ; +VAL_ 1728 NMH_GW_NM_aktiv_Diagnose 1 "Diagnose bei Kl 15 aus" ; +VAL_ 1728 NMH_GW_NM_aktiv_Start 1 "Zustand 'START' (NM-high)" ; +VAL_ 1728 NMH_GW_NM_aktiv_BDM 1 "BDM-Kommunikation" ; +VAL_ 1728 NMH_GW_NM_aktiv_Warnblinken 1 "Warnblinken aktiv" ; +VAL_ 1728 NMH_GW_NM_aktiv_ESP 1 "ESP aktiv (Wakeup/Sleep-Konzept)" ; +VAL_ 1728 NMH_GW_Abschaltstufe_3 1 "BEM aufgrund Abschaltstufe 3 aktiv" ; +VAL_ 1728 NMH_GW_SG_Fehlerdauer 1 "BEM aufgrund Steuergeraetefehlerdauer aktiv" ; +VAL_ 1728 NMH_GW_STH_Wakeup 1 "BEM aktiv aufgrund Standheizungswakeup" ; +VAL_ 1728 NMH_GW_NL_Diagnose 0 "keine_Diagnose_aktiv" 1 "Diagnose_war_lokal_aktiv" ; +VAL_ 1728 NM_GW_Signalfehler 1 "Aktiver_Signalfehler_eingetragen" ; +VAL_ 1728 NMH_GW_TimeOut_Fehler 1 "Aktiver Timeout Fehlerspeichereintrag " ; +VAL_ 1728 NMH_GW_CAN_Diag_deaktiv 1 "CAN Bus bezogene Eigendiagnose deaktiv" ; +VAL_ 1728 NMH_GW_KompSchutz 1 "KS aktiv" ; +VAL_ 1728 NMH_GW_Mute_Mode 1 "MuteMode aktiv" ; +VAL_ 1728 NMH_GW_Transport_Mode 1 "Transportmodus aktiv" ; +VAL_ 1728 NMH_GW_Abschaltstufe_aktiv 1 "Abschaltstufe aktiv" ; +VAL_ 1728 NMH_GW_Eindraht_Fehler 1 "Eindrahtbetrieb erkannt" ; +VAL_ 1728 NMH_GW_ACAN 1 "ACAN aktiv (Wakeup/Sleep-Konzept)" ; +VAL_ 1728 NMH_GW_KombiCAN 1 "KombiCAN aktiv (Wakeup/Sleep-Konzept)" ; +VAL_ 1728 NMH_GW_KomfortCAN 1 "KomfortCAN aktiv (Wakeup/Sleep-Konzept)" ; +VAL_ 1728 NMH_GW_Infotainment 1 "Infotainment aktiv (CAN oder MOST), Wakeup/Sleep-Konzept" ; +VAL_ 1728 NMH_GW_Fahrwerk 1 "BUS_Fahrwerk_aktiv (Wakeup/Sleep-Konzept)" ; +VAL_ 1728 NMH_GW_WakeUp_CAN_Bus 0 "Nicht zutreffend (kein CAN-Wakeup bzw. CarWakeup)" 1 "Antriebs-CAN" 2 "Kombi-CAN" 3 "Komfort-CAN" 4 "Infotainment-CAN (wenn verfuegbar)" 5 "Fahrwerks-CAN" 6 "Diagnose-CAN" ; +VAL_ 1730 NMH_GE_Start_1 1 "Zustand Start (<--Sleep)" ; +VAL_ 1730 NMH_GE_Start_2 1 "Zustand Start (<--Prepare to Sleep)" ; +VAL_ 1730 NMH_GE_Normal_Mode_1 1 "Zustand Normal Mode (<-- Start)" ; +VAL_ 1730 NMH_GE_Normal_Mode_2 1 "Zustand Normal Mode (<-- Ready to Sleep)" ; +VAL_ 1730 NMH_GE_Per_WakeUp 0 "wenn Funktionswakeup" 1 "CAN" 2 "P-Wakeup, Ursache nicht bekannt" 3 "KL 15 HW (falls vorhanden)" ; +VAL_ 1730 NMH_GE_Fkt_WakeUp 0 "wenn Peripheriewakeup" 1 "Ende_N_Haltephase" ; +VAL_ 1730 NMH_GE_NM_aktiv_Klemme_15 1 "Klemme 15 ein" ; +VAL_ 1730 NMH_GE_NM_aktiv_Diagnose 1 "Diagnose bei Kl 15 aus" ; +VAL_ 1730 NMH_GE_NM_aktiv_Start 1 "Zustand 'START' (NM-high)" ; +VAL_ 1730 NMH_GE_N_Haltephase 0 "keine_N_Haltephase" 1 "N_Haltephase_aktiv" ; +VAL_ 1730 NMH_GE_kein_NL 1 "kein lokaler Nachlauf" ; +VAL_ 1730 NMH_GE_NL_Daten_EEPROM 1 "EEPROM Datenspeicherung" ; +VAL_ 1730 NM_GE_Signalfehler 1 "Aktiver_Signalfehler_eingetragen" ; +VAL_ 1730 NMH_GE_TimeOut_Fehler 1 "Aktiver Timeout Fehlerspeichereintrag " ; +VAL_ 1730 NMH_GE_CAN_Diag_deaktiv 1 "CAN-Diagnose deaktiv" ; +VAL_ 1730 NMH_GE_KompSchutz 1 "KS aktiv" ; +VAL_ 1730 NMH_GE_Mute_Mode 1 "MuteMode aktiv" ; +VAL_ 1730 NMH_GE_Transport_Mode 1 "Transportmodus aktiv" ; +VAL_ 1730 NMH_GE_Abschaltstufe_aktiv 1 "Abschaltstufe aktiv" ; +VAL_ 1730 NMH_GE_Eindraht_Fehler 1 "Eindrahtbetrieb erkannt" ; +VAL_ 1730 NMH_GE_Lokalaktiv 0 "war nicht Lokalaktiv" 1 "war Lokalaktiv" ; +VAL_ 1730 NMH_GE_Subsystemaktiv 0 "Subsystem war nicht lokalaktiv" 1 "war Lokalaktiv" ; +VAL_ 1730 NMH_GSG_Subbusaktiv 0 "Subbus inaktiv" 1 "Subbus aktiv" ; +VAL_ 1729 NMH_MO_Start_1 1 "Zustand Start (<--Sleep)" ; +VAL_ 1729 NMH_MO_Start_2 1 "Zustand Start (<--Prepare to Sleep)" ; +VAL_ 1729 NMH_MO_Normal_Mode_1 1 "Zustand Normal Mode (<-- Start)" ; +VAL_ 1729 NMH_MO_Normal_Mode_2 1 "Zustand Normal Mode (<-- Ready to Sleep)" ; +VAL_ 1729 NMH_MO_Per_WakeUp 0 "Wenn Funktions-Wakeup" 1 "CAN-Wakeup" 2 "Peripherie-Wakeup Ursache nicht bekannt" 3 "Klemme 15 HW (falls vorhanden)" 4 "analog (Standheizung/Tuerkontakt)(nur MED9)" ; +VAL_ 1729 NMH_MO_Fkt_WakeUp 0 "Wenn_Peripherie_Wakeup" ; +VAL_ 1729 NMH_MO_NM_aktiv_Klemme_15 1 "Klemme 15 EIN" ; +VAL_ 1729 NMH_MO_NM_aktiv_Diagnose 1 "Diagnose bei Kl 15 aus " ; +VAL_ 1729 NMH_MO_NM_aktiv_Start 1 "Zustand 'START' (NM-high)" ; +VAL_ 1729 NMH_MO_NM_aktiv_EKP_Vorlauf 1 "EKP-Vorlauf" ; +VAL_ 1729 NMH_MO_NM_aktiv_STH_Betrieb 1 "STH-Betrieb" ; +VAL_ 1729 NMH_MO_NM_aktiv_HV_Abschaltung 0 "kein_Nachlauf" 1 "Abschaltung_aktiv" ; +VAL_ 1729 NMH_MO_kein_NL 1 "kein lokaler Nachlauf" ; +VAL_ 1729 NMH_MO_NL_Kuehlerluefter 1 "K�hlerl�fter Steuerung / Zusatzwasserpumpe aktiv" ; +VAL_ 1729 NMH_MO_NL_Diagnose 1 "Diagnosefunktionen aktiv" ; +VAL_ 1729 NMH_MO_NL_WFS 1 "WFS aktiv" ; +VAL_ 1729 NMH_MO_NL_EEPROM 1 "EEPROM Zugriffe RAM/ROM Tests" ; +VAL_ 1729 NMH_MO_NL_Sonstige 1 "Sonstige Nachl�ufe aktiv" ; +VAL_ 1729 NM_MO_Signalfehler 1 "Aktiver_Signalfehler_eingetragen" ; +VAL_ 1729 NMH_MO_TimeOut_Fehler 1 "Aktiver Timeout Fehlerspeichereintrag " ; +VAL_ 1729 NMH_MO_CAN_Diag_deaktiv 1 "CAN-Diagnose deaktiv" ; +VAL_ 1729 NMH_MO_KompSchutz 1 "KS aktiv" ; +VAL_ 1729 NMH_MO_Mute_Mode 1 "MuteMode aktiv" ; +VAL_ 1729 NMH_MO_Transport_Mode 1 "Transportmodus aktiv" ; +VAL_ 1729 NMH_MO_Abschaltstufe_aktiv 1 "Abschaltstufe aktiv" ; +VAL_ 1729 NMH_MO_Eindraht_Fehler 1 "Eindrahtbetrieb erkannt" ; +VAL_ 1729 NMH_MO_Lokalaktiv 0 "war nicht Lokalaktiv" 1 "war Lokalaktiv" ; +VAL_ 1729 NMH_MO_Subsystemaktiv 0 "Subsystem war nicht lokalaktiv" 1 "war Lokalaktiv" ; +VAL_ 1736 NMH_MO_SL_Start_1 1 "Zustand Start (<--Sleep)" ; +VAL_ 1736 NMH_MO_SL_Start_2 1 "Zustand Start (<--Prepare to Sleep)" ; +VAL_ 1736 NMH_MO_SL_Normal_Mode_1 1 "Zustand Normal Mode (<-- Start)" ; +VAL_ 1736 NMH_MO_SL_Normal_Mode_2 1 "Zustand Normal Mode (<-- Ready to Sleep)" ; +VAL_ 1736 NMH_MO_SL_Per_WakeUp 0 "Wenn Funktions-Wakeup" 1 "CAN-Wakeup" 2 "Peripherie-Wakeup Ursache nicht bekannt" 3 "Klemme 15 HW (falls vorhanden)" 4 "analog (Standheizung/Tuerkontakt)(nur MED9)" ; +VAL_ 1736 NMH_MO_SL_Fkt_WakeUp 0 "Wenn Peripherie-Wakeup" ; +VAL_ 1736 NMH_MO_SL_TimeOut_Fehler 1 "Aktiver Timeout Fehlerspeichereintrag " ; +VAL_ 1736 NMH_MO_SL_CAN_Diag_deaktiv 1 "CAN-Diagnose deaktiv" ; +VAL_ 1736 NMH_MO_SL_KompSchutz 1 "KS aktiv" ; +VAL_ 1736 NMH_MO_SL_Mute_Mode 1 "MuteMode aktiv" ; +VAL_ 1736 NMH_MO_SL_Transport_Mode 1 "Transportmodus aktiv" ; +VAL_ 1736 NMH_MO_SL_Abschaltstufe_aktiv 1 "Abschaltstufe aktiv" ; +VAL_ 1736 NMH_MO_SL_Busfehler 1 "Busfehler" ; +VAL_ 1736 NMH_MO_Sl_Lokalaktiv 0 "war_nicht_lokal_aktiv" 1 "war_lokal_aktiv" ; +VAL_ 1736 NMH_MO_SL_Subsystemaktiv 0 "Subsystem war nicht lokalaktiv" 1 "war Lokalaktiv" ; +VAL_ 1782 NMH_SCR_Start_1 1 "Zustand Start (<--Sleep)" ; +VAL_ 1782 NMH_SCR_Start_2 1 "Zustand Start (<--Prepare to Sleep)" ; +VAL_ 1782 NMH_SCR_Normal_Mode_1 1 "Zustand Normal Mode (<-- Start)" ; +VAL_ 1782 NMH_SCR_Normal_Mode_2 1 "Zustand Normal Mode (<-- Ready to Sleep)" ; +VAL_ 1782 NMH_SCR_Car_WakeUp 1 "Car Wake Up" ; +VAL_ 1782 NMH_SCR_Per_WakeUp 0 "Funktions-WakeUp" 1 "CAN" 2 "P_WakeUp_Ursache_unbekannt" 3 "KL_15_Hardware_falls_vorhanden" ; +VAL_ 1782 NMH_SCR_Fkt_WakeUp 0 "Peripheriewakeup" ; +VAL_ 1782 NMH_SCR_Klemme_15 1 "Klemme 15 ein" ; +VAL_ 1782 NMH_SCR_Diagnose 1 "Diagnose bei Kl 15 aus" ; +VAL_ 1782 NMH_SCR_MindestAktivZeit 1 "aktiv" ; +VAL_ 1782 NMH_SCR_NL_Datem_EEPROM 0 "kein_Nachlauf" 1 "EEPROM_schreibzugriff" ; +VAL_ 1782 NMH_SCR_Signalfehler 1 "Aktiver_Signalfehler_eingetragen" ; +VAL_ 1782 NMH_SCR_TimeOut_Fehler 1 "Aktiver Timeout Fehlerspeichereintrag" ; +VAL_ 1782 NMH_SCR_CAN_Diag_deaktiv 1 "CAN Bus bezogene Eigendiagnose deaktiviert" ; +VAL_ 1782 NMH_SCR_KompSchutz 1 "KS aktiv" ; +VAL_ 1782 NMH_SCR_Mute_Mode 1 "Mute Mode aktiv" ; +VAL_ 1782 NMH_SCR_Transport_Mode 1 "Transportmodus aktiv" ; +VAL_ 1782 NMH_SCR_Abschaltstufe_aktiv 1 "Funktionsabschaltung wegen Abschaltschaltstufe" ; +VAL_ 1782 NMH_SCR_Busfehler 1 "Busfehler" ; +VAL_ 1782 NMH_SCR_Lokalaktiv 0 "war_nicht_lokal_aktiv" 1 "war_lokal_aktiv" ; +VAL_ 1782 NMH_SCR_Subsystemaktiv 0 "Subsystem war nicht lokalaktiv" 1 "war Lokalaktiv" ; +VAL_ 913 OBD_Kaltstart_Denominator 0 "Denominator_nicht_hochzaehlen" 1 "Bedingungen_zum_Inkr_des_Kaltstart_Denom_erf" ; +VAL_ 913 OBD_Minimum_Trip 0 "kein_Min_Normed_Trip" 1 "Min_Normed_Trip" ; +VAL_ 913 OBD_Driving_Cycle 0 "kein Driving Cycle erkannt" 1 "DC erkannt" ; +VAL_ 913 OBD_Warm_Up_Cycle 0 "kein Warm Up Cycle erkannt" 1 "Warm Up Cycle erkannt" ; +VAL_ 913 OBD_Normed_Trip 0 "kein Normed Trip" 1 "Normed Trip erf�llt" ; +VAL_ 803 PCF_Objektstatus 0 "Kein_relevantes_Objekt_erkannt" 1 "Relevantes_Objekt_vorausfahrend" 2 "Relevantes_Objekt_stehend" 3 "Relevantes_Objekt_angehalten" 4 "Relevantes_Objekt_entgegenkommend" 5 "Ungueltig" 6 "Ungueltig" 7 "Ungueltig" ; +VAL_ 803 PCF_Fahrer_aktiv_erkannt 0 "Fahrer_nicht_aktiv" 1 "Fahrer_aktiv" ; +VAL_ 803 PCF_Time_to_collision 255 "Objektstatus=0x0__oder_berechneter_TTC_Wert_groesser_als_Maximalwert" ; +VAL_ 803 PCF_v_rel 0 " Objektstatus_0x0_oder _berechnete_v_rel_>= 0_(Objekt_entfernt_sich_oder_faehrt_vorraus_mit v_Obj_=_v_ego)" ; +VAL_ 803 PCF_dy_Kollisionsueberdeckung 0 "Keine_Ueberdeckung_oder_bei_Objektstatus_0x0" 30 "Ueberdeckung_groesser_Maximalwert" 31 "Objekueberdeckung_nicht_ermittelbar" ; +VAL_ 802 PCR_Sensorstatus 0 "Sensor_ok" 1 "Sensor_nok" ; +VAL_ 802 PCR_Obj_vx_rel 2047 "Fehler" ; +VAL_ 802 PCR_Obj_vy_rel 2047 "Fehler" ; +VAL_ 802 PCR_Obj_TTC 511 "Fehler" ; +VAL_ 802 PCR_Obj_Guete 127 "Fehler" ; +VAL_ 802 PCR_Crashwahrscheinlichkeit 127 "Fehler" ; +VAL_ 929 PSD_Pos_Segment_ID 0 "keine Position gegeben" 1 "Fehlerwert" ; +VAL_ 929 PSD_Pos_Standort 0 "mehrdeutiger_Standort" 1 "eindeutiger_Standort" ; +VAL_ 929 PSD_Pos_Laengsfehler 0 "keine Pr�diktion (off-road)" 1 "< 2m" 2 "< 5m" 3 "< 10m " 4 "< 20m" 5 "< 50m" 6 "> 50m " 7 "nicht erlaubt" ; +VAL_ 929 PSD_Segment_ID 0 "keine Segmentinformationen vorhanden" 1 "Fehlerwert" ; +VAL_ 929 PSD_Vorgaenger_Segment_ID 0 "keine Segmentinformation vorhanden" 1 "Fehlerwert" ; +VAL_ 929 PSD_Strassenklasse 0 "Rest_Feldweg_Schotterweg_Privatweg" 1 "Ortsstrasse" 2 "Bundes_Landstrasse" 3 "Autobahn" ; +VAL_ 929 PSD_Rampe 0 "Strasse_mit_Gegenverkehr" 1 "Auffahrt_Einbahnstr" 2 "Abfahrt_Einbahnstr" 3 "Einbahnstrasse" ; +VAL_ 929 PSD_Endkruemmung 255 "Gerade" ; +VAL_ 929 PSD_Endkruemmung_Vorz 0 "Kruemmung_positiv" 1 "Kruemmung_negativ" ; +VAL_ 929 PSD_Endsteigung 30 "gleich_oder_mehr_15_Prozent_Steigung" 31 "nicht_definiert" ; +VAL_ 929 PSD_Endsteigung_Vorz 0 "Gefaelle" 1 "Steigung" ; +VAL_ 929 PSD_ADAS_Qualitaet 0 "keine_ADAS_Qualitaet" 1 "ADAS_Qualitaet" ; +VAL_ 929 PSD_Fahrspuren 0 "Einbahnstrasse_in_falscher_Richtung" 1 "eine_Fahrspur" 2 "zwei_Fahrspuren" 3 "drei_Fahrspuren" ; +VAL_ 929 PSD_wahrscheinlichster_Pfad 0 "Pfad_mit_geringer_Wahrscheinlichkeit" 1 "wahrscheinlichster_Pfad" ; +VAL_ 930 PSD_Multiplex 0 "f�r System Informationen, die sich nur langsam �ndern" 1 "Informationen �ber ein Streckensegment" 2 "f�r Informationen �ber Geschwindigkeitsbegrenzungen und m�gliche Einschr�nkungen der Geschwindigkeitsbegrenzungen" 3 "Fahrzeugposition aus der Koppelortung" ; +VAL_ 930 PSD_Sys_Segment_ID 0 "keine Segmentinformationen vorhanden" 1 "nicht zulaessig" ; +VAL_ 930 PSD_Abz_Segment_ID 0 "keine Segmentinformationen vorhanden" 1 "nicht zulaessig" ; +VAL_ 930 PSD_Ges_Segment_ID 0 "keine Segmentinformationen vorhanden" 1 "nicht zulaessig" ; +VAL_ 930 PSD_Ort_Laenge_VZ 0 "Ost" 1 "West" ; +VAL_ 930 PSD_Ort_Laenge 33554431 "Keine GPS Position verfuegbar" ; +VAL_ 930 PSD_Ges_Geschwindigkeit 0 "Kein Geschwindigkeitsgebot" 1 "0 km/h < v_max < 5 km/h" 2 "5 km/h � v_max < 10km/h" 3 "10 km/h � v_max < 15 km/h" 4 "15 km/h � v_max < 20 km/h" 5 "20 km/h � v_max < 25 km/h" 6 "25 km/h � v_max < 30 km/h" 7 "30 km/h � v_max < 35 km/h" 8 "35 km/h � v_max < 40 km/h" 9 "40 km/h � v_max < 45 km/h" 10 "45 km/h � v_max < 50 km/h" 11 "50 km/h � v_max < 60 km/h" 12 "60 km/h � v_max < 70 km/h" 13 "70 km/h � v_max < 80 km/h" 14 "80 km/h � v_max < 90 km/h" 15 "90 km/h � v_max < 100 km/h" 16 "100 km/h � v_max < 110 km/h" 17 "110 km/h � v_max < 120 km/h" 18 " 120 km/h � v_max < 130 km/h" 19 "130 km/h � v_max < 140 km/h" 20 "140 km/h � v_max < 150 km/h" 21 "150 km/h � v_max < 160 km/h" 22 "160 km/h � v_max" 23 "Geschwindigkeitsgebot aufgehoben" 24 "..0x1F ung�ltig" ; +VAL_ 930 PSD_Ges_Geschwindigkeit_Typ 0 "Der Wert im Attribut Geschwindigkeitsbegrenzung entspricht der Geschwindigkeitsklasse von Navteq." 1 "Der Wert im Attribut Geschwindigkeitsbegrenzung entspricht einer explizit angegebenen Begrenzung der Geschwindigkeit." ; +VAL_ 930 PSD_Ges_Geschwindigkeit_Gespann 0 "alle Fahrzeuge" 1 "PKW mit Gespann" 2 "LKW, Busse, etc." ; +VAL_ 930 PSD_Abz_Vorgaenger_Segment_ID 0 "keine Segmentinformationen vorhanden" 1 "nicht zulaessig" ; +VAL_ 930 PSD_Sys_Geschwindigkeit_Einheit 0 "km/h" 1 "mph" ; +VAL_ 930 PSD_Ges_Geschwindigkeit_Witter 0 "Witterungsunabh�ngig" 1 "N�sse, Regen, Niederschlag" 2 "Gl�tte" 3 "Nebel" ; +VAL_ 930 PSD_Sys_Verkehrsrichtung 0 "Rechtsverkehr" 1 "Linksverkehr" ; +VAL_ 930 PSD_Ges_Geschwindigkeit_Tag_Anf 0 "kein Beginn definiert" 1 "Montag" 2 "Dienstag" 3 "Mittwoch" 4 "Donnerstag" 5 "Freitag" 6 "Samstag" 7 "Sonntag" ; +VAL_ 930 PSD_Abz_Geschwindigkeit 0 "kein Geschwindigkeitsgebot" 1 "0 km/h < v_max < 5 km/h" 2 "5 km/h � v_max < 10km/h" 3 "10 km/h � v_max < 15 km/h" 4 "15 km/h � v_max < 20 km/h" 5 "20 km/h � v_max < 25 km/h" 6 "25 km/h � v_max < 30 km/h" 7 "30 km/h � v_max < 35 km/h" 8 "35 km/h � v_max < 40 km/h" 9 "40 km/h � v_max < 45 km/h" 10 "45 km/h � v_max < 50 km/h" 11 "50 km/h � v_max < 60 km/h" 12 "60 km/h � v_max < 70 km/h" 13 "70 km/h � v_max < 80 km/h" 14 "80 km/h � v_max < 90 km/h" 15 "90 km/h � v_max < 100 km/h" 16 "100 km/h � v_max < 110 km/h" 17 "110 km/h � v_max < 120 km/h" 18 "120 km/h � v_max < 130 km/h" 19 "130 km/h � v_max < 140 km/h" 20 "140 km/h � v_max < 150 km/h" 21 "150 km/h � v_max < 160 km/h" 22 "160 km/h � v_max" 23 " Geschwindigkeitsgebot aufgehoben" 24 "..0x1F ung�ltig" ; +VAL_ 930 PSD_Ges_Geschwindigkeit_Tag_Ende 0 "kein Ende definiert" 1 "Montag" 2 "Dienstag" 3 "Mittwoch" 4 "Donnerstag" 5 "Freitag" 6 "Samstag" 7 "Sonntag" ; +VAL_ 930 PSD_Ges_Geschwindigkeit_Std_Anf 25 "kein Beginn f�r stundenweise Einschr�nkungen" ; +VAL_ 930 PSD_Abz_Geschwindigkeit_Typ 0 "Der Wert im Attribut Geschwindigkeitsbegrenzung entspricht der Geschwindigkeitsklasse von Navteq." 1 "Der Wert im Attribut Geschwindigkeitsbegrenzung entspricht einer explizit angegebenen Begrenzung der Geschwindigkeit" ; +VAL_ 930 PSD_Sys_Tunnel 0 "kein Tunnel oder keine Information verfuegbar" 1 "Tunnel" ; +VAL_ 930 PSD_Abz_Strassenklasse 0 " Rest (Feldweg, Schotter, Privatweg)" 1 "Ortsstra�e" 2 "Bundes-,Landstrasse" 3 "Autobahn" ; +VAL_ 930 PSD_Sys_Bruecke 0 "keine Bruecke oder keine Information verfuegbar" 1 "Bruecke" ; +VAL_ 930 PSD_Ort_Breite_VZ 0 "Nord" 1 "Sued" ; +VAL_ 930 PSD_Sys_Fahrsp_Gegenr 0 "keine Fahrspur" 1 "eine Fahrspur" 2 "mehr als eine Fahrspur" 3 "keine Information verfuegbar" ; +VAL_ 930 PSD_Abz_ADAS_Qualitaet 0 "keine ADAS Qualit�t" 1 "ADAS Qualit�t" ; +VAL_ 930 PSD_Ges_Geschwindigkeit_Std_Ende 25 "kein Ende f�r stundenweise Einschr�nkungen" ; +VAL_ 930 PSD_Abz_Abzweigerichtung 0 "rechts abzweigende Stra�e" 1 "links abzweigende Stra�e" ; +VAL_ 930 PSD_Sys_TMC_Baustelle 0 "keine Baustelle oder keine Information verfuegbar" 1 "Baustelle" ; +VAL_ 930 PSD_Abz_Abzweigewinkel 0 "0�: Stra�e verl�uft gerade aus" 1 "0� < Winkel � 12�" 2 "12� < Winkel � 24�" 3 "24� < Winkel � 36�" 4 "36� < Winkel � 48�" 5 "48� < Winkel � 60�" 6 "60� < Winkel � 72�" 7 "72� < Winkel � 84�" 8 "84� < Winkel � 96�" 9 "96� < Winkel � 108�" 10 "108� < Winkel � 120�" 11 "120� < Winkel � 132�" 12 "132� < Winkel � 144�" 13 "144� < Winkel � 156�" 14 "156� < Winkel � 168�" 15 "168� < Winkel � 180�" ; +VAL_ 930 PSD_Sys_TMC_Stau 0 "kein Stau oder keine Information verfuegbar" 1 "Stau" ; +VAL_ 930 PSD_Ges_alter_Geschw 0 "Kein Geschwindigkeitsgebot" 1 "0 km/h < v_max < 5 km/h" 2 "5 km/h � v_max < 10km/h" 3 "10 km/h � v_max < 15 km/h" 4 "15 km/h � v_max < 20 km/h" 5 "20 km/h � v_max < 25 km/h" 6 "25 km/h � v_max < 30 km/h" 7 "30 km/h � v_max < 35 km/h" 8 "35 km/h � v_max < 40 km/h" 9 "40 km/h � v_max < 45 km/h" 10 "45 km/h � v_max < 50 km/h" 11 "50 km/h � v_max < 60 km/h" 12 "60 km/h � v_max < 70 km/h" 13 "70 km/h � v_max < 80 km/h" 14 "80 km/h � v_max < 90 km/h" 15 "90 km/h � v_max < 100 km/h" 16 "100 km/h � v_max < 110 km/h" 17 "110 km/h � v_max < 120 km/h" 18 "120 km/h � v_max < 130 km/h" 19 "130 km/h � v_max < 140 km/h" 20 "140 km/h � v_max < 150 km/h" 21 "150 km/h � v_max < 160 km/h" 22 "160 km/h � v_max" 23 "Geschwindigkeitsgebot aufgehoben" 24 "..0x1F ung�ltig" ; +VAL_ 930 PSD_Abz_Rampe 0 "Stra�e mit Gegenverkehr" 1 "Auffahrt (Einbahnstr.) " 2 "Abfahrt (Einbahnstr.)" 3 "Einbahnstra�e" ; +VAL_ 930 PSD_Abz_Anfangskruemmung 255 "Gerade" ; +VAL_ 930 PSD_Ges_alter_Geschw_Gespann 0 "alle Fahrzeuge" 1 "PKW mit Gespann" 2 "LKW, Busse, etc." ; +VAL_ 930 PSD_Ges_alter_Geschw_Witter 0 "Witterungsunabh�ngig" 1 "N�sse, Regen, Niederschlag" 2 "Gl�tte" 3 "Nebel" ; +VAL_ 930 PSD_Ges_alter_Geschw_Tag_Anf 0 "kein Beginn definiert" 1 "Montag" 2 "Dienstag" 3 "Mittwoch" 4 "Donnerstag" 5 "Freitag" 6 "Samstag" 7 "Sonntag" ; +VAL_ 930 PSD_Abz_Anfangskruemmung_Vorz 0 "Kr�mmung positiv" 1 "Kr�mmung negativ" ; +VAL_ 930 PSD_Sys_Anfangskruemmung 255 "Gerade" ; +VAL_ 930 PSD_Abz_Endkruemmung 255 "Gerade" ; +VAL_ 930 PSD_Ges_alter_Geschw_Tag_Ende 0 "kein Ende definiert" 1 "Montag" 2 "Dienstag" 3 "Mittwoch" 4 "Donnerstag" 5 "Freitag" 6 "Samstag" 7 "Sonntag" ; +VAL_ 930 PSD_Ges_alter_Geschw_Std_Anf 25 "kein Beginn f�r stundenweise Einschr�nkungen" ; +VAL_ 930 PSD_Sys_Anfangskruemmung_Vorz 0 "Kr�mmung positiv" 1 "Kr�mmung negativ" ; +VAL_ 930 PSD_Abz_Endkruemmung_Vorz 0 "Kr�mmung positiv" 1 "Kr�mmung negativ" ; +VAL_ 930 PSD_Ges_alter_Geschw_Std_Ende 25 "kein Ende f�r stundenweise Einschr�nkungen" ; +VAL_ 930 PSD_Sys_Anfangssteigung 30 "gleich oder mehr als 15 % Steigung" 31 "ung�ltig" ; +VAL_ 930 PSD_Abz_Endsteigung 30 "gleich oder mehr als 15 % Steigung" 31 "ung�ltig" ; +VAL_ 930 PSD_Ges_Ueberholverbot 0 "kein �berholverbot" 1 "alle Fahrzeuge" 2 "�berholverbot f�r PKW mit Gespann" 3 "�berholverbot f�r LKW, Busse, etc." ; +VAL_ 930 PSD_Sys_Anfangssteigung_Vorz 0 "Gef�lle " 1 "Steigung" ; +VAL_ 930 PSD_Abz_Endsteigung_Vorz 0 "Gef�lle" 1 "Steigung" ; +VAL_ 930 PSD_Sys_Ortschaft 0 "au�erhalb der Ortschaft" 1 "innerhalb der Ortschaft" ; +VAL_ 930 PSD_Abz_Fahrspuren 0 "Einbahnstra�e in falscher Richtung" 1 "eine Fahrspur" 2 "zwei Fahrspuren" 3 "mehr als 2 Fahrspuren" ; +VAL_ 930 PSD_Ges_Wechselverkehrszeichen 0 "Kein Wechselverkehrszeichen" 1 "Wechselverkehrszeichen links" 2 "Wechselverkehrszeichen rechts" 3 "Wechselverkehrszeichen links und rechts" 4 "Wechselverkerhszeichen �ber der Fahrbahn" ; +VAL_ 930 PSD_Sys_Digitalisierung 0 "teildigitalisiert" 1 "volldigitalisiert" ; +VAL_ 930 PSD_Sys_Zielfuehrung 0 "Zielfuehrung nicht aktiv" 1 "Zielfuehrung aktiv" ; +VAL_ 930 PSD_Abz_wahrscheinlichster_Pfad 0 "Pfad mit geringer Wahrscheinlichkeit" 1 "wahrscheinlichster Pfad" ; +VAL_ 1528 SAK_Charisma_FahrPr 0 "nicht_belegt" 1 "Programm_1" 2 "Programm_2" 3 "Programm_3" 4 "Programm_4" 5 "Programm_5" 6 "Programm_6" 7 "Programm_7" ; +VAL_ 1528 SAK_Charisma_Status 0 "Init" 1 "verfuegbar" 2 "nicht_verfuegbar" 3 "asynchron_durch_Fahrerwunsch" ; +VAL_ 1528 SAK_Charisma_Umschaltung 0 "Idle" 1 "Erkennung_Umschaltaufforderung" 2 "Steuerbotschaft_nicht_definiert" 3 "Umschaltung_verzoegert" ; +VAL_ 1528 SAK_KD_Fehler 0 "kein_KD_Fehler" 1 "KD_Fehler" ; +VAL_ 1011 SCR_Dosierpumpe_Drehzahl 2047 "Fehler" ; +VAL_ 1011 SCR_Druck 1021 "nicht_verbaut" 1023 "Fehler" ; +VAL_ 1011 SCR_Level_Aktivtank 1021 "nicht_verbaut" 1023 "Fehler" ; +VAL_ 1011 SCR_Level_Passivtank 1021 "nicht_verbaut" 1023 "Fehler" ; +VAL_ 1507 SCR_Heizkreis_3_Strom 253 "nicht_verbaut" 255 "Fehler" ; +VAL_ 1507 SCR_KD_Fehler 0 "kein_KD_Fehler" 1 "KD_Fehler" ; +VAL_ 1507 SCR_Guetesensor 1021 "nicht_verbaut" 1023 "Fehler" ; +VAL_ 1507 SCR_Temp_Aktivtank 255 "Fehler" ; +VAL_ 1507 SCR_Temp_Passivtank 253 "nicht_verbaut" 255 "Fehler" ; +VAL_ 1507 SCR_Leitungsheizung_Strom 255 "Fehler" ; +VAL_ 1507 SCR_Transferpumpe_Strom 253 "nicht_verbaut" 255 "Fehler" ; +VAL_ 1507 SCR_Tankheizung_Strom 255 "Fehler" ; +VAL_ 1508 SCR_Spannungsversorgung_Status 0 "kein_Fehler" 1 "KS-" 2 "KS+" 3 "OC" 4 "OOR+(Ueberspannung)" 5 "OOR-(Unterspannung)" 6 "RC+" 7 "RC-" 8 "KS+/OC" 9 "KS-/OC" 10 "KS-/KS+" 11 "KS-/KS+/OC" 12 "OOR+(FktEinschr_Ueberspg)" 13 "OOR-(FktEinschr_Unterspg)" 14 "frei" 15 "Diagnose_noch_nicht_beendet" ; +VAL_ 1508 SCR_VersorgungSensoren_Status 0 "kein_Fehler" 1 "KS-" 2 "KS+" 3 "OC" 4 "OOR+" 5 "OOR-" 6 "RC+" 7 "RC-" 8 "KS+/OC" 9 "KS-/OC" 10 "KS-/KS+" 11 "KS-/KS+/OC" 12 "frei" 13 "frei" 14 "frei" 15 "Diagnose_noch_nicht_beendet" ; +VAL_ 1508 SCR_Heizkreis_3_Status 0 "kein_Fehler" 1 "KS- (Kurzschluss nach minus)" 2 "KS+ (Kurzschluss nach plus)" 3 "OC (Leitungsunterbrechung)" 4 "OOR+ (Signal zu gross)" 5 "OOR- (Signal zu klein)" 6 "RC+ (Signal unplausibel zu gross)" 7 "RC- (Signal unplausibel zu klein)" 8 "KS+/OC (Kurzschluss nach plus/Unterbrechung)" 9 "KS-/OC (Kurzschluss nach plus/Unterbrechung)" 10 "KS-/KS+ (Kurzschluss nach minus/plus)" 11 "KS-/KS+/OC (Kurzschluss nach minus/plus/Unterbrechung)" 12 "frei" 13 "frei" 14 "frei" 15 "frei" ; +VAL_ 1508 SCR_Guetesensor_Status 0 "kein_Fehler" 1 "KS- (Kurzschluss nach minus)" 2 "KS+ (Kurzschluss nach plus)" 3 "OC (Leitungsunterbrechung)" 4 "OOR+ (Signal zu gross)" 5 "OOR- (Signal zu klein)" 6 "RC+ (Signal unplausibel zu gross)" 7 "RC- (Signal unplausibel zu klein)" 8 "KS+/OC (Kurzschluss nach plus/Unterbrechung)" 9 "KS-/OC (Kurzschluss nach plus/Unterbrechung)" 10 "KS-/KS+ (Kurzschluss nach minus/plus)" 11 "KS-/KS+/OC (Kurzschluss nach minus/plus/Unterbrechung)" 12 "frei" 13 "frei" 14 "frei" 15 "frei" ; +VAL_ 1508 SCR_Leitungsheizung_Status 0 "kein_Fehler" 1 "KS- (Kurzschluss nach minus)" 2 "KS+ (Kurzschluss nach plus)" 3 "OC (Leitungsunterbrechung)" 4 "OOR+ (Signal zu gross)" 5 "OOR- (Signal zu klein)" 6 "RC+ (Signal unplausibel zu gross)" 7 "RC- (Signal unplausibel zu klein)" 8 "KS+/OC (Kurzschluss nach plus/Unterbrechung)" 9 "KS-/OC (Kurzschluss nach plus/Unterbrechung)" 10 "KS-/KS+ (Kurzschluss nach minus/plus)" 11 "KS-/KS+/OC (Kurzschluss nach minus/plus/Unterbrechung)" 12 "frei" 13 "frei" 14 "frei" 15 "frei" ; +VAL_ 1508 SCR_Tankheizung_Status 0 "kein_Fehler" 1 "KS- (Kurzschluss nach minus)" 2 "KS+ (Kurzschluss nach plus)" 3 "OC (Leitungsunterbrechung)" 4 "OOR+ (Signal zu gross)" 5 "OOR- (Signal zu klein)" 6 "RC+ (Signal unplausibel zu gross)" 7 "RC- (Signal unplausibel zu klein)" 8 "KS+/OC (Kurzschluss nach plus/Unterbrechung)" 9 "KS-/OC (Kurzschluss nach plus/Unterbrechung)" 10 "KS-/KS+ (Kurzschluss nach minus/plus)" 11 "KS-/KS+/OC (Kurzschluss nach minus/plus/Unterbrechung)" 12 "frei" 13 "frei" 14 "frei" 15 "frei" ; +VAL_ 1508 SCR_Druck_Status 0 "kein_Fehler" 1 "KS- (Kurzschluss nach minus)" 2 "KS+ (Kurzschluss nach plus)" 3 "OC (Leitungsunterbrechung)" 4 "OOR+ (Signal zu gross)" 5 "OOR- (Signal zu klein)" 6 "RC+ (Signal unplausibel zu gross)" 7 "RC- (Signal unplausibel zu klein)" 8 "KS+/OC (Kurzschluss nach plus/Unterbrechung)" 9 "KS-/OC (Kurzschluss nach plus/Unterbrechung)" 10 "KS-/KS+ (Kurzschluss nach minus/plus)" 11 "KS-/KS+/OC (Kurzschluss nach minus/plus/Unterbrechung)" 12 "frei" 13 "frei" 14 "frei" 15 "frei" ; +VAL_ 1508 SCR_Dosierpumpe_Status_Spule 0 "kein_Fehler" 1 "KS-" 2 "KS+" 3 "OC" 4 "OOR+" 5 "OOR-" 6 "RC+(Drehzahl_zu_hoch)" 7 "RC-(Drehzahl_zu_niedrig)" 8 "KS+/OC" 9 "KS-/OC" 10 "KS-/KS+" 11 "KS-/KS+/OC" 12 "KS_zwischen_Phasen" 13 "frei" 14 "frei" 15 "frei" ; +VAL_ 1508 SCR_Transferpumpe_Status 0 "kein_Fehler" 1 "KS- (Kurzschluss nach minus)" 2 "KS+ (Kurzschluss nach plus)" 3 "OC (Leitungsunterbrechung)" 4 "OOR+ (Signal zu gross)" 5 "OOR- (Signal zu klein)" 6 "RC+ (Signal unplausibel zu gross)" 7 "RC- (Signal unplausibel zu klein)" 8 "KS+/OC (Kurzschluss nach plus/Unterbrechung)" 9 "KS-/OC (Kurzschluss nach plus/Unterbrechung)" 10 "KS-/KS+ (Kurzschluss nach minus/plus)" 11 "KS-/KS+/OC (Kurzschluss nach minus/plus/Unterbrechung)" 12 "frei" 13 "frei" 14 "frei" 15 "frei" ; +VAL_ 1508 SCR_Level_Aktivtank_Status 0 "kein_Fehler" 1 "KS- (Kurzschluss nach minus)" 2 "KS+ (Kurzschluss nach plus)" 3 "OC (Leitungsunterbrechung)" 4 "OOR+ (Signal zu gross)" 5 "OOR- (Signal zu klein)" 6 "RC+ (Signal unplausibel zu gross)" 7 "RC- (Signal unplausibel zu klein)" 8 "KS+/OC (Kurzschluss nach plus/Unterbrechung)" 9 "KS-/OC (Kurzschluss nach plus/Unterbrechung)" 10 "KS-/KS+ (Kurzschluss nach minus/plus)" 11 "KS-/KS+/OC (Kurzschluss nach minus/plus/Unterbrechung)" 12 "frei" 13 "frei" 14 "frei" 15 "frei" ; +VAL_ 1508 SCR_Level_Passivtank_Status 0 "kein_Fehler" 1 "KS- (Kurzschluss nach minus)" 2 "KS+ (Kurzschluss nach plus)" 3 "OC (Leitungsunterbrechung)" 4 "OOR+ (Signal zu gross)" 5 "OOR- (Signal zu klein)" 6 "RC+ (Signal unplausibel zu gross)" 7 "RC- (Signal unplausibel zu klein)" 8 "KS+/OC (Kurzschluss nach plus/Unterbrechung)" 9 "KS-/OC (Kurzschluss nach plus/Unterbrechung)" 10 "KS-/KS+ (Kurzschluss nach minus/plus)" 11 "KS-/KS+/OC (Kurzschluss nach minus/plus/Unterbrechung)" 12 "frei" 13 "frei" 14 "frei" 15 "frei" ; +VAL_ 1508 SCR_Temp_Aktivtank_Status 0 "kein_Fehler" 1 "KS- (Kurzschluss nach minus)" 2 "KS+ (Kurzschluss nach plus)" 3 "OC (Leitungsunterbrechung)" 4 "OOR+ (Signal zu gross)" 5 "OOR- (Signal zu klein)" 6 "RC+ (Signal unplausibel zu gross)" 7 "RC- (Signal unplausibel zu klein)" 8 "KS+/OC (Kurzschluss nach plus/Unterbrechung)" 9 "KS-/OC (Kurzschluss nach plus/Unterbrechung)" 10 "KS-/KS+ (Kurzschluss nach minus/plus)" 11 "KS-/KS+/OC (Kurzschluss nach minus/plus/Unterbrechung)" 12 "frei" 13 "frei" 14 "frei" 15 "frei" ; +VAL_ 1508 SCR_Temp_Passivtank_Status 0 "kein_Fehler" 1 "KS- (Kurzschluss nach minus)" 2 "KS+ (Kurzschluss nach plus)" 3 "OC (Leitungsunterbrechung)" 4 "OOR+ (Signal zu gross)" 5 "OOR- (Signal zu klein)" 6 "RC+ (Signal unplausibel zu gross)" 7 "RC- (Signal unplausibel zu klein)" 8 "KS+/OC (Kurzschluss nach plus/Unterbrechung)" 9 "KS-/OC (Kurzschluss nach plus/Unterbrechung)" 10 "KS-/KS+ (Kurzschluss nach minus/plus)" 11 "KS-/KS+/OC (Kurzschluss nach minus/plus/Unterbrechung)" 12 "frei" 13 "frei" 14 "frei" 15 "frei" ; +VAL_ 1509 SCR_Ansteuerung_Transferpumpe 0 "nicht_aktiv" 1 "aktiv" ; +VAL_ 1509 SCR_Ansteuerung_Dosierpumpe 0 "nicht_aktiv" 1 "aktiv" ; +VAL_ 1509 SCR_Ansteuerung_Heizkreis_3 0 "nicht_aktiv" 1 "aktiv" ; +VAL_ 1509 SCR_Ansteuerung_Leitungsheizung 0 "nicht_aktiv" 1 "aktiv" ; +VAL_ 1509 SCR_Ansteuerung_Tankheizung 0 "nicht_aktiv" 1 "aktiv" ; +VAL_ 1526 SCR_Steuergeraet_Heizung_Status 0 "kein_Fehler" 1 "Endstufe_Tankheizung_ueberhitzt" 2 "Endstufe_Leitungsheizung_ueberhitzt" 3 "Diagnose_noch_nicht_beendet" ; +VAL_ 1526 SCR_Steuergeraet_Pumpe_Status 0 "kein_Fehler" 1 "Endstufe_Pumpe_ueberhitzt" 2 "Pumpe_blockiert" 3 "Diagnose_noch_nicht_beendet" ; +VAL_ 1526 SCR_Steuergeraet_Relais_Status 0 "kein_Fehler" 1 "KS+ (Ausgang Leistungsrelais) " 2 "KS-/OC (Ausgang Leistungsrelais)" 3 "Diagnose_noch_nicht_beendet" ; +VAL_ 1526 SCR_Steuergeraet_Bus_Status 0 "kein_Fehler" 1 "Bus_Kommunikation_Fehler" 2 "Bus_Kommunikation_Stoerung_(temporaer)" 3 "Diagnose_noch_nicht_beendet" ; +VAL_ 1526 SCR_Steuergeraet_Codierung_St000 0 "kein_Fehler" 1 "Steuergeraet_nicht_codiert" 2 "Steuergeraet_falsch_codiert" 3 "Diagnose_noch_nicht_beendet" ; +VAL_ 1526 SCR_Steuergeraet_Datensatz_St001 0 "kein_Fehler" 1 "ungueltiger_Datensatz" 2 "unplausibeler_Datensatz" 3 "Diagnose_noch_nicht_beendet" ; +VAL_ 1526 SCR_Steuergeraet_Defekt_Status 0 "kein_Fehler" 1 "Steuergeraet_defekt" 2 "Steuergeraet_Stoerung_(temporaer)" 3 "Diagnose_noch_nicht_beendet" ; +VAL_ 1510 SCR_CAL_ID_Name_01 48 "Fehler" ; +VAL_ 1510 SCR_CAL_ID_Name_02 48 "Fehler" ; +VAL_ 1510 SCR_CAL_ID_Name_03 48 "Fehler" ; +VAL_ 1512 SCR_CAL_ID_Leer 48 "Fehler" ; +VAL_ 133 SCU_Ue_Winkel_ADS 4094 "Init" 4095 "Fehler" ; +VAL_ 133 SCU_VZ_Ue_Winkel_ADS 0 "positiv" 1 "negativ" ; +VAL_ 133 SCU_Soll_Ue_Winkel 2046 "Init" 2047 "Fehler" ; +VAL_ 133 SCU_max_Gradient 511 "Fehler" ; +VAL_ 133 SCU_VZ_Soll_Ue_Winkel 0 "positiv" 1 "negativ" ; +VAL_ 133 SCU_Status 0 "betriebsbereit" 1 "Init" 2 "sichere �bersetzung" 3 "Motorsperre verriegelt" 4 "Synchronisierung l�uft" ; +VAL_ 133 SCU_KD_Fehler 0 "kein_KD_Fehler" 1 "KD_Fehler" ; +VAL_ 784 SCU_Warnlampe 0 "keine Anzeige (SCU_Status=0x0)" 1 "Warnlampe an (SCU_Status=0x1, 0x2, 0x3)" 2 "reserviert" 3 "Warnlampe Synchronisation (SCU_Status=0x4)" ; +VAL_ 784 SCU_Warnungen 0 "keine Anzeige (SCU_Status=0x0, 0x1)" 1 "ADS Stoerung (SCU_Status=0x2, 0x3)" 2 "ADS Initialisierung (SCU_Status=0x4)" 3 "reserviert" ; +VAL_ 784 SCU_Charisma_FahrPr 0 "nicht_belegt" 1 "Programm_1" 2 "Programm_2" 3 "Programm_3" 4 "Programm_4" 5 "Programm_5" 6 "Programm_6" 7 "Programm_7" ; +VAL_ 784 SCU_Charisma_Status 0 "Init (SCU_Status=0x1)" 1 "idle (SCU_Status=0x0, 0x4)" 2 "nicht verfuegbar (SCU_Status=0x2, 0x3)" 3 "reserviert" ; +VAL_ 784 SCU_Charisma_Umschaltung 0 "Idle" 1 "Erkennung_Umschaltaufforderung" 2 "Steuerbotschaft_nicht_definiert" 3 "Umschaltung_verzoegert" ; +VAL_ 1313 STH_Funk_ein 0 "kein Funkbefehl zum Einschalten" 1 "Funkbefehl zum Einschalten erhalten" ; +VAL_ 1313 STH_Funk_aus 0 "kein Funkbefehl" 1 "Funkbefehl zum Ausschalten erhalten" ; +VAL_ 1313 STH_Zusatzheizung 0 "Zuheizer aus" 1 "Zuheizer ein" ; +VAL_ 1313 STH_LED 0 "keine R�ckmeldung" 1 "Rueckmeldung Standheizung in Betrieb" ; +VAL_ 1313 STH_Geblaese 0 "kein Einschaltbefehl an die Klimaanlage, Gebl�se" 1 "Einschaltbefehl an die Klimaanlage, Gebl�se" ; +VAL_ 1313 STH_EKP_Anst 0 "EKP nicht ansteuern" 1 "EKP ansteuern" ; +VAL_ 1313 STH_Start_folgt 0 "kein_Start_folgt" 1 "Start_folgt" ; +VAL_ 1313 STH_Ventil_Status 0 "Ventil_offen__grosser_Kreislauf" 1 "Ventil_geschlossen__kleiner_Kreislauf" ; +VAL_ 1313 STH_Fehlerstatus 0 "kein Fehler" 1 "Batterie Low" 2 "Fuel Low" 3 "Hardware defekt" 4 "Heizgeraet verriegelt" ; +VAL_ 1313 STH_Wassertemp 254 "Init" 255 "Fehler" ; +VAL_ 1313 STH_Motorvorwaermung 0 "keine Motorvorw�rmung erfolgt" 1 "Aufheizung mit Motorvorw�rmung erfolgt" ; +VAL_ 1313 STH_war_aktiv 0 "war inaktiv" 1 "Standheizung war letzte halbe Stunde aktiv" ; +VAL_ 1313 STH_KVS_Ueberlauf 0 "kein �berlauf" 1 "Kraftstoffverbrauchssignal, mindestens ein �berlauf hat stattgefunden" ; +VAL_ 1313 STH_KD_Fehler 0 "kein_KD_Fehler" 1 "KD_Fehler" ; +VAL_ 1172 STS_Car_not_under_theft 0 "false" 1 "true" ; +VAL_ 1172 STS_Car_under_theft 0 "false" 1 "true" ; +VAL_ 1172 STS_Anlassersperre 0 "inaktiv" 1 "aktiv" ; +VAL_ 1172 STS_Typencodierung 0 "Basis" 1 "E-Gas" 4 "Sonderschutz" ; +VAL_ 1172 STS_KD_Fehler 0 "kein_KD_Fehler" 1 "KD_Fehler" ; +VAL_ 1172 STS_Standlicht 0 "inaktiv" 1 "aktiv" ; +VAL_ 1172 STS_Fahrlicht 0 "inaktiv" 1 "aktiv" ; +VAL_ 1172 STS_Alarm_still 0 "inaktiv" 1 "aktiv" ; +VAL_ 1172 STS_Texte 0 "kein_Text" 1 "Text_01" 2 "Text_02" 3 "Text_03" 4 "Text_04" 5 "Text_05" 6 "Text_06" 7 "Text_07" 8 "Text_08" 9 "Text_09" 10 "Text_10" 11 "Text_11" 12 "Text_12" 13 "Text_13" 14 "Init" 15 "Fehler" ; +VAL_ 1172 STS_Laderelais 0 "Relais_offen" 1 "Relais_geschlossen" ; +VAL_ 1172 STS_Summer 0 "inaktiv" 1 "aktiv" ; +VAL_ 1172 STS_Notstart 0 "kein_Notstart" 1 "Notstart" ; +VAL_ 1172 STS_Signalhorn 0 "inaktiv" 1 "aktiv" ; +VAL_ 1172 STS_Leerlaufschaltung 0 "Leerlaufschaltung_Aus" 1 "Leerlaufschaltung_Ein" ; +VAL_ 1413 SI_Int_CAN_gespiegelt 0 "interner CAN getrennt" 1 "interner CAN gespiegelt" ; +VAL_ 1413 SI_CAN_Komfort_Sleep 0 "keine_Busruhe" 1 "Busruhe" ; +VAL_ 1413 SI_CAN_Dashboard_Sleep 0 "keine_Busruhe" 1 "Busruhe" ; +VAL_ 1413 SI_CAN_Antrieb_Sleep 0 "keine_Busruhe" 1 "Busruhe" ; +VAL_ 1413 SI_Infotainment_Sleep 0 "keine_Busruhe" 1 "Busruhe" ; +VAL_ 1413 SI_CAN_Extended_Sleep 0 "keine_Busruhe" 1 "Busruhe" ; +VAL_ 1413 SI_Fahrwerk_Sleep 0 "keine_Busruhe" 1 "Busruhe" ; +VAL_ 1413 SI_Diagnose_Aktiv 0 "inaktiv" 1 "aktiv" ; +VAL_ 1413 SI_QRS_Mode 0 "QRS_Messmodus_nicht_aktiv" 1 "QRS_Messmodus_aktiv" ; +VAL_ 1413 SI_T_Mode 0 "Transportmodus_nicht_aktiv" 1 "Transportmodus_aktiv" ; +VAL_ 1413 SI_NWDF 0 "Ueberwachung_nicht_freigegeben" 1 "Ueberwachung_freigegeben" ; +VAL_ 1413 SI_NWDF_gueltig 0 "NWDF_wird_nicht_unterstuetzt" 1 "NWDF_wird_unterstuetzt" ; +VAL_ 1413 SI_Sammelfehler 0 "kein_Sammelfehler" 1 "Sammelfehler" ; +VAL_ 1413 GW_KD_Fehler 0 "kein_KD_Fehler" 1 "KD_Fehler" ; +VAL_ 1413 SI_MOST_Status 0 "MOST_sleep_(Licht_AUS)" 1 "MOST_aktiv_(Kommunikation_moeglich)" ; +VAL_ 1413 SI_Sammel_SG_Fehler 61 "Reserviert" 62 "Overflow" ; +VAL_ 1413 SI_MO_WU 0 "kein Wakeup angefordert" 1 "Wakeup MED9 angefordert" ; +VAL_ 786 FAS_Wunschgeschw 1022 "keine Anzeige" 1023 "nicht definiert" ; +VAL_ 786 FAS_Status_Prim_Anz 0 "Symbol nicht beleuchtet" 1 "Farbe 1 (typisch 'gr�n')" 2 "Farbe 2 (typisch 'rot')" 3 "Farbe 3 (typisch 'gelb')" ; +VAL_ 786 FAS_Texte_Primaeranz 0 "keine Anzeige " 1 "ACC nicht verfuegbar !" 2 "Auto_Auto_ _ _" 3 "Auto_ _Auto_ _" 4 "Auto_ _ _Auto_" 5 "Auto_ _ _ _Auto" 6 "Auto_Auto_ _ _ Gong (durchgestrichen)" 7 "Auto_ _Auto_ _ Gong (durchgestrichen)" 8 "Auto_ _ _Auto_ Gong (durchgestrichen)" 9 "Auto_ _ _ _Auto Gong (durchgestrichen)" 10 "ACC bereit" 11 "keine Abstandsregelung" 12 "ACC Sensor Sicht !" 13 "ACC nicht verfuegbar" 14 "o o o" 15 "Hochschalten" 16 "ESP Eingriff" 17 "Herunterschalten" 18 "Parkbremse !" 19 "Geschwindigkeitsgrenze" 20 "Waehlhebelposition !" 21 "VDA ACC-Symbol YYY km/h / mph" 22 "Tempolimit XXX km/h / mph" 23 "Kurve XXX km/h / mph" 24 "ACC Abschaltung" 25 "Symbol 'Eieruhr'" 26 "!" 27 "--- km/h / mph" 28 "XXX km/h / mph (Schriftart 2)" 29 "Lenkradwinkel" 30 "Anfahren bestaetigen" 31 "Fahrzeug verloren" 32 "Im Stand nicht moeglich" 33 "Ungueltiger Anfahrbefehl" 34 "Tuer offen !" 35 "Fahrer Gurtschloss offen !" 36 "Schalthebelposition !" 37 "Drehzahl !" 38 "Kurvenassistent aus" 39 "Tempolimit aus" 40 "Abbiegeassistent" 41 "Ortsanfang XXX km/h / mph" 42 "Ortsende XXX km/h / mph" 43 "Tempolimit Ende XXX km/h / mph" 44 "HDC aktiv" 45 "braking guard Bremsruck" 46 "braking guard aus " 47 "braking guard aus" 48 "Uebernehmen !" 49 "Steigung zu gross" 50 "Stehendes Objekt voraus" 51 "SET / 'GRA Symbol'___xxx km/h / mph" 52 "SET / 'GRA Symbol' xxx km/h / mph" 53 "ACC aus" 54 "ACC startet" 55 "ACC reinigen" 56 "ACC Fehler" 57 "ACC haelt an !" 58 "Bremse betaetigen !" 59 "Kupplung betaetigt" 60 "LIM AUS" 61 "LIM AKTIV " 62 "LIM PASSIV" 63 "LIM FEHLER" 64 "Bremse ueberhitzt !" 65 "Bremse haelt !" 66 "ESP PASSIV !" ; +VAL_ 786 FAS_Status_Anzeige 0 "ACC/GRA Hauptschalter aus" 1 "ACC in Init (nicht bei GRA)" 2 "ACC/GRA passiv" 3 "ACCGRA aktiv" 4 "ACC/GRA im Hintergrund (�bertreten)" 5 "frei" 6 "ACC reversibel aus (nicht bei GRA)" 7 "ACC/GRA irreversibel aus" ; +VAL_ 270 TSK_ax_Getriebe 511 "nicht definiert" ; +VAL_ 270 TSK_Freig_WU 0 "TSK_Uebersetzungswunsch nicht freigegeben" 1 "TSK_Uebersetzungswunsch freigegeben" ; +VAL_ 270 TSK_Limiter_aktiv 0 "Speed Limiter ist nicht aktiv" 1 "Speed Limiter aktiv und regelt" ; +VAL_ 270 TSK_Status_GRA_ACC_02 0 "nicht verbaut / kein ACC zul�ssig" 1 "GRA / ACC aktiv " 2 "GRA / ACC vom Fahrer �bersteuert" 3 "Fehler, GRA/ACC nicht m�glich " ; +VAL_ 273 TSK_QBit_Steigung 0 "gueltiger_Wert" 1 "Ersatz_Init_oder_Fehlerwert" ; +VAL_ 273 TSK_Status_GRA_ACC_01 0 "nicht_verbaut_kein_ACC_zulaessig" 1 "GRA_ACC_aktiv" 2 "GRA_ACC_vom_Fahrer_uebersteuert" 3 "Fehler_GRA_ACC_nicht_moeglich" ; +VAL_ 273 TSK_Fahrzeugmasse 31 "Fehler" ; +VAL_ 273 TSK_QBit_Fahrzeugmasse 0 "gueltiger_Wert" 1 "Ersatz_Init_oder_Fehlerwert" ; +VAL_ 273 TSK_Fahrzeugmasse_02 255 "Fehler" ; +VAL_ 273 TSK_Steigung 255 "Fehler" ; +VAL_ 273 TSK_Getriebeinfo 0 "Handschalter" 1 "AL_AQ_Getriebe" 2 "DL_DQ_Getriebe" 3 "CVT_Getriebe" ; +VAL_ 273 TSK_Codierung_ACC 0 "TSK_korrekt_auf_kein_ACC_codiert_oder_TSK_falsch_codiert" 1 "TSK_korrekt_auf_ACC_codiert" ; +VAL_ 273 TSK_Zwangszusch_ESP 0 "keine_ESP_ASR_Beeinflussung" 1 "ESP_ASR_Beeinflussung" ; +VAL_ 273 TSK_Freig_Verzoeg_Anf 0 "Verzoegerungsanforderung_nicht_freigegeben" 1 "Verzoegerungsanforderung_freigegeben" ; +VAL_ 1414 WH_KD_Fehler 0 "kein_KD_Fehler" 1 "KD_Fehler" ; diff --git a/opendbc/dbc/vw_mqb.dbc b/opendbc/dbc/vw_mqb.dbc index effe4c5b..d1ecb004 100644 --- a/opendbc/dbc/vw_mqb.dbc +++ b/opendbc/dbc/vw_mqb.dbc @@ -58,6 +58,7 @@ BO_ 290 ACC_06: 8 XXX BO_ 279 ACC_10: 8 XXX SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX + SG_ AWV_AWA_Status_EPS : 12|4@1+ (1,0) [0|7] "" XXX SG_ AWV1_Anf_Prefill : 16|1@1+ (1,0) [0|1] "" XXX SG_ ANB_CM_Info : 17|1@1+ (1,0) [0|1] "" XXX SG_ AWV2_Freigabe : 18|1@1+ (1,0) [0|1] "" XXX @@ -1329,6 +1330,7 @@ BO_ 159 LH_EPS_03: 8 XXX SG_ EPS_BLW_QBit : 30|1@1+ (1,0) [0|1] "" XXX SG_ EPS_VZ_BLW : 31|1@1+ (1,0) [0|1] "" XXX SG_ EPS_HCA_Status : 32|4@1+ (1,0) [0|15] "" XXX + SG_ EPS_AWA_Status : 36|4@1+ (1,0) [0|14] "" XXX SG_ EPS_Lenkmoment : 40|10@1+ (1,0) [0|8] "Unit_centiNewtoMeter" XXX SG_ EPS_Lenkmoment_QBit : 54|1@1+ (1,0) [0|1] "" XXX SG_ EPS_VZ_Lenkmoment : 55|1@1+ (1,0) [0|1] "" XXX @@ -1673,7 +1675,9 @@ CM_ SG_ 1720 KBI_Variante_USA "In diesem Signal wird die HW-Variante des Kombis VAL_ 159 EPS_HCA_Status 0 "disabled" 1 "initializing" 2 "fault" 3 "ready" 4 "rejected" 5 "active" 8 "preempted" ; +VAL_ 159 EPS_AWA_Status 0 "AWA_deaktiviert" 1 "AWA_Anf_nicht_ausfuehrbar" 2 "Kom_AWA_gestoert" 3 "EPS_bzgl_AWA_funktionsbereit" 4 "AWA_Anf_abgewiesen" 5 "AWA_Momeingriff_1_aktiv" 7 "AWA_Momeingriff_2_aktiv" 8 "AWA_abgewiesen_Momentenpriorisierung" 9 "Anf_abgewiesen_Bedienueblich" 14 "Init" ; VAL_ 173 GE_Fahrstufe 5 "P" 6 "R" 7 "N" 8 "D" 9 "S" 10 "E" 13 "T" 14 "T" ; +VAL_ 279 AWV_AWA_Status_EPS 0 "AWA_deactivated" 1 "AWA_request_not_executable" 2 "EPS_communication_disturbed" 3 "AWA_ready" 5 "AWA_torque_intervention_1" 7 "AWA_torque_intervention_2" ; VAL_ 288 TSK_Status 0 "init" 1 "disabled" 2 "enabled" 3 "regulating" 4 "accel_pedal_override" 5 "brake_only" 6 "temp_fault" 7 "perm_fault" ; VAL_ 288 TSK_v_Begrenzung_aktiv 0 "inaktiv" 1 "aktiv" ; VAL_ 288 TSK_Standby_Anf_ESP 0 "keine_Standby_Anforderung" 1 "Standby_Anforderung" ; diff --git a/opendbc/dbc/vw_pq.dbc b/opendbc/dbc/vw_pq.dbc index 28a42a64..97bea0cf 100644 --- a/opendbc/dbc/vw_pq.dbc +++ b/opendbc/dbc/vw_pq.dbc @@ -22,6 +22,7 @@ NS_ : SIG_GROUP_ SIG_VALTYPE_ SIGTYPE_VALTYPE_ + SG_MUL_VAL_ BS_: @@ -330,50 +331,64 @@ BO_ 1160 Motor_6: 8 XXX SG_ Sollmoment_f_r_Getriebe : 8|8@1+ (0.39,0) [0|99] "MDI" XXX SG_ Checksumme_Motor_6 : 0|8@1+ (1,0) [0|0] "" XXX -BO_ 1152 Motor_5: 8 XXX - SG_ CHECKSUM : 56|8@1+ (1,0) [0|0] "" XXX - SG_ Motortext_Bits__4_1_ : 52|4@1+ (1,0) [0|0] "" XXX - SG_ Doppelte_Momente : 51|1@1+ (1,0) [0|0] "" XXX - SG_ GRA_Hauptschalter : 50|1@1+ (1,0) [0|0] "" XXX - SG_ Anlasser_Ausspuren : 49|1@1+ (1,0) [0|0] "" XXX - SG_ Anlasser_Freigabe : 48|1@1+ (1,0) [0|0] "" XXX - SG_ Klimadrucksignal__Motor_5_ : 40|8@1+ (0.2,0) [0|50.8] "bar" XXX - SG_ K_hlerluefteransteuerung : 32|8@1+ (0.4,0) [0|101.6] "%" XXX - SG_ Verbrauch_Ueberlauf : 31|1@1+ (1,0) [0|0] "" XXX - SG_ Kraftstoffverbrauchssignal : 16|15@1+ (1,0) [0|32767] "ul" XXX - SG_ Klimakompressor_Leistungsreduzi : 15|1@1+ (1,0) [0|0] "" XXX - SG_ Kennfeldkuehlung : 14|1@1+ (1,0) [0|0] "" XXX - SG_ Klimakompressor_aus__Motor_5_ : 13|1@1+ (1,0) [0|0] "" XXX - SG_ CAT_Warnung : 12|1@1+ (1,0) [0|0] "" XXX - SG_ OBD_2_Lampe : 11|1@1+ (1,0) [0|0] "" XXX - SG_ E_Gas_Lampe : 10|1@1+ (1,0) [0|0] "" XXX - SG_ Vorgluehlampe__Motor_5_ : 9|1@1+ (1,0) [0|0] "" XXX - SG_ Ladekontroll_Lampe : 8|1@1+ (1,0) [0|0] "" XXX - SG_ Multiplex_Code M : 6|2@1+ (1,0) [0|0] "" XXX - SG_ Multiplex_Info_norm__Verbrauch m3 : 0|6@1+ (20,0) [0|1260] "l/Zyl" XXX - SG_ Multiplex_Info_Motortyp m2 : 0|6@1+ (1,0) [0|0] "" XXX - SG_ Multiplex_Info_Drehzahl_MD_Max m1 : 0|6@1+ (100,0) [0|6300] "U/min" XXX - SG_ Multiplex_Info_Max_Drehmoment m0 : 0|6@1+ (10,0) [0|630] "Nm" XXX +BO_ 1152 Motor_5: 8 Motor + SG_ MO5_Mp_Code M : 6|2@1+ (1,0) [0|3] "" Gateway + SG_ MO5_max_Moment m0 : 0|6@1+ (10,0) [0|630] "Nm" Gateway + SG_ MO5_Drehzahl m1 : 0|6@1+ (100,0) [0|6300] "U/min" Gateway + SG_ MO5_Motortyp m2 : 0|6@1+ (1,0) [0|63] "" Gateway + SG_ MO5_Abgastyp m3 : 0|1@1+ (1,0) [0|1] "" Gateway + SG_ MO5_Abgastyp2 m3 : 1|1@1+ (1,0) [0|1] "" Gateway + SG_ MO5_Abgastyp3 m3 : 2|1@1+ (1,0) [0|1] "" Gateway + SG_ OBD_Kaltstart_Denominator m3 : 3|1@1+ (1,0) [0|1] "" Gateway + SG_ OBD_Minimum_Trip m3 : 4|1@1+ (1,0) [0|1] "" Gateway + SG_ MO5_DPF_reg m3 : 5|1@1+ (1,0) [0|1] "" Gateway + SG_ MO5_Vorgluehen : 9|1@1+ (1,0) [0|1] "" KOMBI + SG_ MO5_E_Gas : 10|1@1+ (1,0) [0|1] "" KOMBI + SG_ MO5_OBD_2 : 11|1@1+ (1,0) [0|1] "" KOMBI + SG_ MO5_Heissl : 12|1@1+ (1,0) [0|1] "" KOMBI + SG_ MO5_KlimaKompr : 13|1@1+ (1,0) [0|1] "" Gateway + SG_ MO5_Feld_kuehl : 14|1@1+ (1,0) [0|1] "" Gateway + SG_ MO5_KliKo_Red : 15|1@1+ (1,0) [0|1] "" Gateway + SG_ MO5_Verbrauch : 16|15@1+ (1,0) [0|32767] "µl" KOMBI + SG_ MO5_UeberlVerb : 31|1@1+ (1,0) [0|1] "" KOMBI + SG_ MO5_Luefter : 32|8@1+ (0.4,0) [0|101.6] "%" Gateway + SG_ MO5_HLeuchte : 40|1@1+ (1,0) [0|1] "" KOMBI + SG_ MO5_PartikelLamp : 41|1@1+ (1,0) [0|1] "" KOMBI + SG_ MO5_Sta_BKU : 42|1@1+ (1,0) [0|1] "" Gateway + SG_ MO5_TypStartSteu : 43|1@1+ (1,0) [0|1] "" Gateway + SG_ MO5_TDE_Lampe : 44|1@1+ (1,0) [0|1] "" KOMBI + SG_ MO5_TDE_Text : 45|1@1+ (1,0) [0|1] "" KOMBI + SG_ MO5_DZM_Daempf : 46|1@1+ (1,0) [0|1] "" KOMBI + SG_ MO5_Interlock : 47|1@1+ (1,0) [0|1] "" Gateway + SG_ MO5_Start : 48|1@1+ (1,0) [0|1] "" Gateway + SG_ MO5_Anlasser : 49|1@1+ (1,0) [0|1] "" Gateway + SG_ MO5_GRA_Hauptsch : 50|1@1+ (1,0) [0|1] "" Gateway + SG_ MO5_Momente : 51|1@1+ (1,0) [0|1] "" Gateway + SG_ MO5_Motortext1 : 52|1@1+ (1,0) [0|1] "" KOMBI + SG_ MO5_Motortext2 : 53|1@1+ (1,0) [0|1] "" KOMBI + SG_ MO5_Motortext3 : 54|1@1+ (1,0) [0|1] "" KOMBI + SG_ MO5_Motortext4 : 55|1@1+ (1,0) [0|1] "" KOMBI + SG_ CHECKSUM : 56|8@1+ (1,0) [0|255] "" Gateway -BO_ 896 Motor_3: 8 XXX - SG_ Drosselklappenpoti : 56|8@1+ (0.4,0) [0|101.6] "%" XXX - SG_ Motor_Wunschdrehzahl : 48|8@1+ (25,0) [0|6350] "U/min" XXX - SG_ Motordrehzahlbeeinflussung : 40|8@1+ (0.392,0) [0|100] "%" XXX - SG_ Kein_Start_Stop : 39|1@1+ (1,0) [0|0] "" XXX - SG_ Kein_E_Gas : 38|1@1+ (1,0) [0|0] "" XXX - SG_ Reserviert_Motor_3_1 : 37|1@1+ (1,0) [0|0] "" XXX - SG_ Vorzeichen_Rad_Wunschmoment : 36|1@1+ (1,0) [0|0] "" XXX - SG_ Rad_Wunschmoment : 24|12@1+ (0.39,0) [0|1597] "MDI" XXX - SG_ Fahrpedal_Rohsignal : 16|8@1+ (0.4,0) [0|101.6] "%" XXX - SG_ Ansauglufttemperatur : 8|8@1+ (0.75,-48) [-48|142.5] "" XXX - SG_ Fehlerstatus_Ansauglufttemperat : 7|1@1+ (1,0) [0|0] "" XXX - SG_ Motorsteuerger_t_gesperrt : 6|1@1+ (1,0) [0|0] "" XXX - SG_ Drosselklappenwinkel_ungenau : 5|1@1+ (1,0) [0|0] "" XXX - SG_ Fahrpedalwert_ungenau__Motor_3_ : 4|1@1+ (1,0) [0|0] "" XXX - SG_ Frei_Motor_3_1 : 3|1@1+ (1,0) [0|0] "" XXX - SG_ Motor_Wunschdrehzahl_Priorit_t : 2|1@1+ (1,0) [0|0] "" XXX - SG_ Uebertemperaturschutz__Motor_3_ : 1|1@1+ (1,0) [0|0] "" XXX - SG_ Vorgluehmeldung : 0|1@1+ (1,0) [0|0] "" XXX +BO_ 896 Motor_3: 8 Motor + SG_ MO3_Vorgluehen : 0|1@1+ (1,0) [0|1] "" Gateway + SG_ MO3_Prio_Dz : 1|1@1+ (1,0) [0|1] "" Transmission + SG_ MO_Schalter_StartStopp : 2|1@1+ (1,0) [0|1] "" Gateway + SG_ MO3_Winterprg : 3|1@1+ (1,0) [0|1] "" Transmission + SG_ MO3_Sta_Pedal : 4|1@1+ (1,0) [0|1] "" Gateway + SG_ MO3_Sta_FPG M : 5|1@1+ (1,0) [0|1] "" ESP + SG_ MO3_Sign_FPG m1 : 6|1@1+ (1,0) [0|1] "" ESP + SG_ MO3_Sta_Temp : 7|1@1+ (1,0) [0|1] "" Gateway + SG_ MO3_Offsentemp : 8|8@1+ (0.75,-48) [-48|142.5] "°C" Gateway + SG_ MO3_Pedalwert : 16|8@1+ (0.4,0) [0|101.6] "%" Gateway + SG_ MO3_Rad_Wu_Mo : 24|12@1+ (0.39,0) [0|1596.66] "%" Transmission + SG_ MO3_Vorz_RadWu : 36|1@1+ (1,0) [0|1] "" Transmission + SG_ MO3_Freigabe_Segeln : 37|1@1+ (1,0) [0|1] "" Transmission + SG_ MO_StartStopp_StoppVorbereitung : 38|1@1+ (1,0) [0|1] "" Gateway + SG_ MO3_Dz_Beeinfl : 40|8@1+ (0.39,0) [0|99.45] "%" Transmission + SG_ MO3_WunschDz : 48|8@1+ (25,0) [0|6350] "U/min" Transmission + SG_ MO3_DKW m0 : 56|8@1+ (0.4,0) [0|101.6] "%" Gateway + SG_ MO3_FPGradient m1 : 56|8@1+ (25,0) [0|6350] "%/s" ESP BO_ 648 Motor_2: 8 Motor SG_ MO2_Mp_Code m : 6|2@1+ (1,0) [0|3] "" Gateway @@ -705,28 +720,27 @@ BO_ 1344 Getriebe_2: 8 XXX SG_ Schubabschaltunterstuetzung : 1|1@1+ (1,0) [0|0] "" XXX SG_ LFR_Adaption_Freigabeflag : 0|1@1+ (1,0) [0|0] "" XXX -BO_ 1088 Getriebe_1: 8 XXX - SG_ Wandlerverlustmoment : 56|8@1+ (0.39,0) [0|99.06] "MDI" XXX - SG_ Fehlerspeichereintrag__Getriebe : 55|1@1+ (1,0) [0|0] "" XXX - SG_ COUNTER : 51|4@1+ (1,0) [0|15] "" XXX - SG_ Gang_eingelegt : 50|1@1+ (1,0) [0|0] "" XXX - SG_ Schaltabsicht : 49|1@1+ (1,0) [0|0] "" XXX - SG_ Motor_aus : 48|1@1+ (1,0) [0|0] "" XXX - SG_ OBD_Status__Getriebe_1___4_1_ : 46|2@1+ (1,0) [0|0] "" XXX - SG_ Kuehlleistung : 44|2@1+ (1,0) [0|0] "" XXX - SG_ Getriebe_Notlauf : 40|4@1+ (1,0) [0|0] "" XXX - SG_ Fahrwiderstandsindex : 32|8@1+ (0.249,-31.6) [-31.6|31.6] "" XXX - SG_ inneres_Soll_Motormoment : 24|8@1+ (0.39,0) [0|99.06] "MDI" XXX - SG_ Uebertragungsfunktion : 16|8@1+ (0.1,0) [0|25.4] "" XXX - SG_ Waehlhebelposition__Getriebe_1_ : 12|4@1+ (1,0) [0|0] "" XXX - SG_ Zielgang_oder_eingelegter_Gang : 8|4@1+ (1,0) [0|0] "" XXX - SG_ EGS_Anforderung : 7|1@1+ (1,0) [0|0] "" XXX - SG_ Kodierung_im_MSG : 6|1@1+ (1,0) [0|0] "" XXX - SG_ Leerlaufsolldrehzahlanhebung : 5|1@1+ (1,0) [0|0] "" XXX - SG_ Wandlerkupplung : 3|2@1+ (1,0) [0|0] "" XXX - SG_ Klimakompressor_aus__Getriebe_1 : 2|1@1+ (1,0) [0|0] "" XXX - SG_ Status_Getriebe_und_Wandlerschu : 1|1@1+ (1,0) [0|0] "" XXX - SG_ Schaltung_aktiv__Getriebe_1_ : 0|1@1+ (1,0) [0|0] "" XXX +BO_ 1088 Getriebe_1: 8 Transmission + SG_ GE1_Schaltung : 0|1@1+ (1,0) [0|1] "" Gateway + SG_ GE1_Sta_Schutz : 1|1@1+ (1,0) [0|1] "" Motor + SG_ GE1_Klimakompr : 2|1@1+ (1,0) [0|1] "" Motor + SG_ GE1_WK : 3|2@1+ (1,0) [0|3] "" Gateway + SG_ GE1_StSt_Info : 5|2@1+ (1,0) [0|3] "" Gateway + SG_ GE1_EGS_Anf : 7|1@1+ (1,0) [0|1] "" Motor + SG_ GE1_Zielgang : 8|4@1+ (1,0) [0|15] "" Gateway + SG_ GE1_Wahl_Pos : 12|4@1+ (1,0) [0|15] "" Gateway + SG_ GE1_Mrad_Mkurb : 16|8@1+ (0.1,0) [0|25.4] "" Gateway + SG_ GE1_Soll_Mo : 24|8@1+ (0.39,0) [0|99.06] "%" Motor + SG_ GE1_Fahrwistd : 32|8@1+ (0.249,-31.623) [-31.623|31.623] "" Gateway + SG_ GE1_Notlauf : 40|4@1+ (1,0) [0|15] "" Gateway + SG_ GE1_Kuehlung : 44|2@1+ (1,0) [0|3] "" Gateway + SG_ GE1_Sta_OBD : 47|1@1+ (1,0) [0|1] "" Motor + SG_ GE1_LaunchControl : 48|1@1+ (1,0) [0|1] "" ESP + SG_ GE1_Infobit : 49|1@1+ (1,0) [0|1] "" Gateway + SG_ GE1_SleepInd : 50|1@1+ (1,0) [0|1] "" Gateway + SG_ COUNTER : 51|4@1+ (1,0) [0|15] "" Gateway + SG_ GE1_Fehlereintr : 55|1@1+ (1,0) [0|1] "" Gateway + SG_ GE1_WaVerl_Mo : 56|8@1+ (0.39,0) [0|99.06] "%" Motor BO_ 912 Gate_Komf_1: 8 XXX SG_ GK1_Sta_RDK_Warn : 0|1@1+ (1,0) [0|1] "" XXX @@ -1406,6 +1420,8 @@ BO_ 1175 Parkhilfe_01: 8 XXX SG_ PH_KD_Fehler : 63|1@1+ (1,0) [0|1] "" XXX BO_ 1463 Bremse_11: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 8|4@1+ (1,0) [0|15] "" XXX SG_ B11_HydHalten : 13|1@1+ (1,0) [0|1] "" XXX SG_ B11_Br_StSt_Info : 14|2@1+ (1,0) [0|3] "" XXX SG_ B11_OBD_Nib_VL : 16|4@1+ (1,0) [0|15] "" XXX @@ -1600,14 +1616,24 @@ CM_ SG_ 648 MO2_LL_Solldz "Idle target speed"; CM_ SG_ 648 MO2_Begr_Mo "Limiting torque - max possible at speed"; CM_ SG_ 648 MO2_Mo_ZWR "Minimum engine torque with ignition angle retardation"; -CM_ SG_ 896 Drosselklappenpoti "Throttle Position"; -CM_ SG_ 896 Motor_Wunschdrehzahl "Desired engine speed"; -CM_ SG_ 896 Motordrehzahlbeeinflussung "Shift Target Influence"; -CM_ SG_ 896 Fahrpedal_Rohsignal "Accelerator Pedal Position"; -CM_ SG_ 896 Ansauglufttemperatur "Intake Air Temperature"; -CM_ SG_ 896 Kein_E_Gas "ETB flag"; -CM_ SG_ 896 Kein_Start_Stop "Start/stop flag"; -CM_ SG_ 896 Rad_Wunschmoment "Desired wheel torque"; +CM_ SG_ 896 MO3_Vorgluehen "Pre-glow active (diesel engines)"; +CM_ SG_ 896 MO3_Prio_Dz "Engine speed priority: 0=request, 1=mandatory"; +CM_ SG_ 896 MO_Schalter_StartStopp "Start/stop deactivated by driver (LED on when 0)"; +CM_ SG_ 896 MO3_Winterprg "Winter driving program active"; +CM_ SG_ 896 MO3_Sta_Pedal "Accelerator pedal status: 0=OK, 1=substitute value"; +CM_ SG_ 896 MO3_Sta_FPG "Accelerator pedal gradient control bit (multiplexer for byte 8)"; +CM_ SG_ 896 MO3_Sign_FPG "Accelerator pedal gradient sign (only when MO3_Sta_FPG=1)"; +CM_ SG_ 896 MO3_Sta_Temp "Intake air temperature status: 0=OK, 1=substitute value"; +CM_ SG_ 896 MO3_Offsentemp "Intake air temperature"; +CM_ SG_ 896 MO3_Pedalwert "Accelerator pedal raw signal (0-101.6%)"; +CM_ SG_ 896 MO3_Rad_Wu_Mo "Wheel torque request (12-bit value, 0-1596.66% MDI)"; +CM_ SG_ 896 MO3_Vorz_RadWu "Wheel torque sign: 0=positive, 1=negative"; +CM_ SG_ 896 MO3_Freigabe_Segeln "Sailing operation enable for transmission"; +CM_ SG_ 896 MO_StartStopp_StoppVorbereitung "Engine stop in preparation"; +CM_ SG_ 896 MO3_Dz_Beeinfl "Engine speed influence factor (0-100% interpolation)"; +CM_ SG_ 896 MO3_WunschDz "Desired engine speed (when MO3_Prio_Dz=1)"; +CM_ SG_ 896 MO3_DKW "Throttle valve position when MO3_Sta_FPG=0 (0-101.6%)"; +CM_ SG_ 896 MO3_FPGradient "Accelerator pedal gradient when MO3_Sta_FPG=1 (0-6350%/s)"; CM_ SG_ 912 GK1_Fa_Tuerkont "Status of the driver's door rotary latch"; CM_ SG_ 912 BSK_HL_geoeffnet "Status of the rear left door rotary latch"; @@ -1615,18 +1641,28 @@ CM_ SG_ 912 BSK_HR_geoeffnet "Status of the rear right door rotary latch"; CM_ SG_ 912 BSK_BT_geoeffnet "Status of the passenger door rotary latch"; CM_ SG_ 912 BSK_HD_Hauptraste "Status of trunk lid main detent"; -CM_ SG_ 1088 Zaehler_Getriebe_1 "Counter Getriebe_1"; -CM_ SG_ 1088 Waehlhebelposition__Getriebe_1_ "Gear Selector Position"; -CM_ SG_ 1088 inneres_Soll_Motormoment "Desired Inner Torque"; -CM_ SG_ 1088 Gang_eingelegt "Gear Engaged"; -CM_ SG_ 1088 Schaltabsicht "Shift Intent"; -CM_ SG_ 1088 Kuehlleistung "Cooling Power"; -CM_ SG_ 1088 Wandlerverlustmoment "Converter Torque Loss"; -CM_ SG_ 1088 Getriebe_Notlauf "Transmission_Notlauf"; -CM_ SG_ 1088 Zielgang_oder_eingelegter_Gang "target_gear_or_gear_in_engagement"; -CM_ SG_ 1088 Uebertragungsfunktion "transfer function"; -CM_ SG_ 1088 EGS_Anforderung "EGS Requirement"; -CM_ SG_ 1088 Schaltung_aktiv__Getriebe_1_ "Shift Activity"; +CM_ BO_ 1088 "Getriebe 1 - Contains gear status, torque requests, and control signals"; + +CM_ SG_ 1088 GE1_Schaltung "Gear shift active: 0=no shift, 1=shift in progress"; +CM_ SG_ 1088 GE1_Sta_Schutz "Transmission/converter protection request (power reduction or ignition angle)"; +CM_ SG_ 1088 GE1_Klimakompr "AC compressor off request"; +CM_ SG_ 1088 GE1_WK "Torque converter clutch status"; +CM_ SG_ 1088 GE1_StSt_Info "Start/stop coordinator info"; +CM_ SG_ 1088 GE1_EGS_Anf "EGS request - byte 4 becomes valid when set"; +CM_ SG_ 1088 GE1_Zielgang "Target gear when shifting or current gear"; +CM_ SG_ 1088 GE1_Wahl_Pos "Selector lever position / driving program"; +CM_ SG_ 1088 GE1_Mrad_Mkurb "Wheel torque to crankshaft torque ratio (Mrad/Mcrank)"; +CM_ SG_ 1088 GE1_Soll_Mo "Internal target engine torque request (0-99.06%)"; +CM_ SG_ 1088 GE1_Fahrwistd "Driving resistance index (normalized % slope)"; +CM_ SG_ 1088 GE1_Notlauf "Emergency mode status"; +CM_ SG_ 1088 GE1_Kuehlung "Cooling request level"; +CM_ SG_ 1088 GE1_Sta_OBD "OBD status - MIL lamp control"; +CM_ SG_ 1088 GE1_LaunchControl "Launch control active"; +CM_ SG_ 1088 GE1_Infobit "Transmission type: 0=stepped automatic, 1=CVT"; +CM_ SG_ 1088 GE1_SleepInd "Sleep readiness after terminal 15 off"; +CM_ SG_ 1088 GE1_Zaehler "Message counter (synchronized with Getriebe_2)"; +CM_ SG_ 1088 GE1_Fehlereintr "Fault memory entry present"; +CM_ SG_ 1088 GE1_WaVerl_Mo "Transmission torque loss / clutch torque (0-99.06%)"; CM_ SG_ 1056 Fehlerstatus_Aussentemp__4_1 "ambient temp error"; CM_ SG_ 1056 Fehlerstatus_Oeltemperatur_4_1 "oil temp error"; @@ -1637,19 +1673,45 @@ CM_ SG_ 1056 Kuehlmitteltemp__4_1__Kombi_2_ "kombi coolant temperature"; CM_ SG_ 1096 Zaehler_Waehlhebel_1 "Counter Waehlhebel_1"; -CM_ SG_ 1152 CHECKSUM "Checksum Motor_5"; -CM_ SG_ 1152 Anlasser_Ausspuren "Starter Disable"; -CM_ SG_ 1152 Anlasser_Freigabe "Starter Release"; -CM_ SG_ 1152 Klimadrucksignal__Motor_5_ "Air conditioning pressure signal"; -CM_ SG_ 1152 Kraftstoffverbrauchssignal "Fuel consumption signal"; -CM_ SG_ 1152 K_hlerluefteransteuerung "Cooling fan control signal"; -CM_ SG_ 1152 Klimakompressor_Leistungsreduzi "Air conditioning compressor power reduction flag"; -CM_ SG_ 1152 Klimakompressor_aus__Motor_5_ "Air conditioning compressor"; -CM_ SG_ 1152 Anlasser_Freigabe "Starter release"; -CM_ SG_ 1152 OBD_2_Lampe "OBD light"; -CM_ SG_ 1152 E_Gas_Lampe "ETB light"; -CM_ SG_ 1152 Ladekontroll_Lampe "Charge light"; -CM_ SG_ 1152 Vorgluehlampe__Motor_5_ "Glow light"; +CM_ BO_ 1152 "Motor message 5 - Contains engine type, consumption, lamps, and diagnostic info"; + +CM_ SG_ 1152 MO5_Mp_Code "Multiplex selector - switches every 4 transmissions"; +CM_ SG_ 1152 MO5_max_Moment "Maximum torque when Mp_Code=0 (0-630 Nm)"; +CM_ SG_ 1152 MO5_Drehzahl "Engine speed at max torque when Mp_Code=1 (0-6300 RPM)"; +CM_ SG_ 1152 MO5_Motortyp "Engine type info when Mp_Code=2 (cylinder count, turbo, fuel type)"; +CM_ SG_ 1152 MO5_Abgastyp "Exhaust type EOBD when Mp_Code=3"; +CM_ SG_ 1152 MO5_Abgastyp2 "Exhaust type OBD when Mp_Code=3"; +CM_ SG_ 1152 MO5_Abgastyp3 "DPF installed when Mp_Code=3"; +CM_ SG_ 1152 OBD_Kaltstart_Denominator "Cold start denominator increment when Mp_Code=3"; +CM_ SG_ 1152 OBD_Minimum_Trip "Minimum normalized trip when Mp_Code=3"; +CM_ SG_ 1152 MO5_DPF_reg "DPF regenerating when Mp_Code=3"; +CM_ SG_ 1152 MO5_Vorgluehen "Diesel pre-glow lamp"; +CM_ SG_ 1152 MO5_E_Gas "E-Gas system lamp (petrol only)"; +CM_ SG_ 1152 MO5_OBD_2 "OBD/MIL lamp control"; +CM_ SG_ 1152 MO5_Heissl "Coolant overheat warning lamp"; +CM_ SG_ 1152 MO5_KlimaKompr "AC compressor off request"; +CM_ SG_ 1152 MO5_Feld_kuehl "Map cooling installed and OK"; +CM_ SG_ 1152 MO5_KliKo_Red "AC compressor power reduction"; +CM_ SG_ 1152 MO5_Verbrauch "Fuel consumption counter (15-bit, µl)"; +CM_ SG_ 1152 MO5_UeberlVerb "Consumption counter overflow"; +CM_ SG_ 1152 MO5_Luefter "Cooling fan PWM control (0-101.6%)"; +CM_ SG_ 1152 MO5_HLeuchte "Overheat pre-warning"; +CM_ SG_ 1152 MO5_PartikelLamp "Particle filter lamp"; +CM_ SG_ 1152 MO5_Sta_BKU "Brake vacuum pump status (Porsche only)"; +CM_ SG_ 1152 MO5_TypStartSteu "Starter control type: 0=BSG/BCM, 1=MSG"; +CM_ SG_ 1152 MO5_TDE_Lampe "Fuel cap warning lamp (petrol only)"; +CM_ SG_ 1152 MO5_TDE_Text "Fuel cap text display (petrol only)"; +CM_ SG_ 1152 MO5_DZM_Daempf "RPM gauge damping control"; +CM_ SG_ 1152 MO5_Interlock "Interlock switch for manual transmission start"; +CM_ SG_ 1152 MO5_Start "Automatic start permission"; +CM_ SG_ 1152 MO5_Anlasser "Starter control permission"; +CM_ SG_ 1152 MO5_GRA_Hauptsch "GRA main switch / readiness"; +CM_ SG_ 1152 MO5_Momente "MDI torque values doubled"; +CM_ SG_ 1152 MO5_Motortext1 "Text: Engine workshop"; +CM_ SG_ 1152 MO5_Motortext2 "Text: Exhaust workshop (deprecated)"; +CM_ SG_ 1152 MO5_Motortext3 "Text: Fuel system fault"; +CM_ SG_ 1152 MO5_Motortext4 "Text: Particle filter needs regeneration"; +CM_ SG_ 1152 CHECKSUM "Checksum with final value 0x0"; CM_ SG_ 1160 Zaehler_Motor_6 "Counter Motor_6"; CM_ SG_ 1160 Hoeheninfo__Motor_6_ "Altitude Correction"; @@ -1688,6 +1750,10 @@ CM_ SG_ 1550 MFA_v_Signal_02 "0=km/h, 1=mph"; SG_MUL_VAL_ 416 BR1_ASRMo_fa BR1_MSR_Anf 0-0; SG_MUL_VAL_ 416 BR1_MSR_Mo_inv BR1_MSR_Anf 1-1; +SG_MUL_VAL_ 896 MO3_DKW MO3_Sta_FPG 0-0; +SG_MUL_VAL_ 896 MO3_FPGradient MO3_Sta_FPG 1-1; +SG_MUL_VAL_ 896 MO3_Sign_FPG MO3_Sta_FPG 1-1; + VAL_ 194 LW1_LRW_Sign 0 "positives_Vorzeichen" 1 "negatives_Vorzeichen"; VAL_ 194 LW1_Gesch_Sign 0 "positives_Vorzeichen" 1 "negatives_Vorzeichen"; VAL_ 194 LW1_ID 0 "noch_not_kalibriert" 128 "kalibriert_nur_bei_PQ35_46_VW32x_VW411"; @@ -1721,6 +1787,16 @@ SG_MUL_VAL_ 648 MO2_max_Mo MO2_Mp_Code 3-3; SG_MUL_VAL_ 648 MO2_CAN_Vers MO2_Mp_Code 0-0; SG_MUL_VAL_ 648 MO2_Motor_Code MO2_Mp_Code 1-1; +SG_MUL_VAL_ 1152 MO5_max_Moment MO5_Mp_Code 0-0; +SG_MUL_VAL_ 1152 MO5_Drehzahl MO5_Mp_Code 1-1; +SG_MUL_VAL_ 1152 MO5_Motortyp MO5_Mp_Code 2-2; +SG_MUL_VAL_ 1152 MO5_Abgastyp MO5_Mp_Code 3-3; +SG_MUL_VAL_ 1152 MO5_Abgastyp2 MO5_Mp_Code 3-3; +SG_MUL_VAL_ 1152 MO5_Abgastyp3 MO5_Mp_Code 3-3; +SG_MUL_VAL_ 1152 OBD_Kaltstart_Denominator MO5_Mp_Code 3-3; +SG_MUL_VAL_ 1152 OBD_Minimum_Trip MO5_Mp_Code 3-3; +SG_MUL_VAL_ 1152 MO5_DPF_reg MO5_Mp_Code 3-3; + VAL_ 648 MO2_Mp_Code 0 "CAN_Stand" 1 "Motor_Kod" 2 "Getriebe_Kod" 3 "MDI_Max"; VAL_ 648 MO2_Getr_Code 0 "_5HP19" 1 "_5HP24" 2 "AG4" 3 "VL300" 4 "VQ250" 5 "VQ35" 6 "AG4_yestco" 7 "AG5_yestco" 8 "autom_Kupplung" 9 "autom_Kupplung_mit_ASG" 10 "AG6_yestco_ZF_6HP_AISIN" 11 "DQ500_DQ250_DQ200" 12 "SQ100_SQ200" 14 "AL1000_AL551_AL951_ZF8HPx" 15 "Handschalter_konv" 16 "DL800" 17 "E_Fahrzeug__Single_Gear"; @@ -1779,8 +1855,68 @@ VAL_ 872 ACS_Fehler 1 "Fehlerspeichereintrag" 0 "kein_Fehlerspeichereintrag" ; VAL_ 872 ACS_zul_Regelabw 254 "ADR_nicht_aktiv" 255 "Fehler" ; VAL_ 872 ACS_max_AendGrad 254 "Neutralwert" 0 "Neutralwert" 255 "Fehler" ; +VAL_ 896 MO3_Vorgluehen 0 "no_Vorgluehen" 1 "Vorgluehen_active"; +VAL_ 896 MO3_Prio_Dz 0 "Wunsch" 1 "Zwang"; +VAL_ 896 MO_Schalter_StartStopp 0 "StartStopp_ueber_Hauptschalter_deactivated_LED_an" 1 "StartStopp_ueber_Hauptschalter_activated_LED_aus"; +VAL_ 896 MO3_Winterprg 0 "not_active" 1 "active"; +VAL_ 896 MO3_Sta_Pedal 0 "Fahrpedal_iO" 1 "Ersatzwert"; +VAL_ 896 MO3_Sta_FPG 0 "Gradient_not_bed" 1 "Gradient_bed"; +VAL_ 896 MO3_Sign_FPG 0 "positives_Vorzeichen" 1 "negatives_Vorzeichen"; +VAL_ 896 MO3_Sta_Temp 0 "Geber_iO" 1 "Ersatzwert"; +VAL_ 896 MO3_Vorz_RadWu 0 "positives_Vorzeichen" 1 "negatives_Vorzeichen"; +VAL_ 896 MO3_Freigabe_Segeln 0 "Segelbetrieb_not_freigegeben" 1 "Segelbetrieb_freigegeben"; +VAL_ 896 MO_StartStopp_StoppVorbereitung 0 "Motorstopp_not_in_Vorbereitung" 1 "Motorstopp_in_Vorbereitung"; +CM_ BO_ 896 "Motor message 3 - Contains accelerator pedal, temperatures, and control signals"; + VAL_ 978 LH2_Sta_HCA 0 "disabled" 1 "initializing" 2 "fault" 3 "ready" 4 "rejected" 5 "active" 7 "active"; -VAL_ 1088 Waehlhebelposition__Getriebe_1_ 8 "P" 7 "R" 6 "N" 5 "D" 9 "U" 12 "S" 14 "T" 10 "T" 11 "T"; + +VAL_ 1088 GE1_Schaltung 0 "no_circuit" 1 "circuit_is_running"; +VAL_ 1088 GE1_Sta_Schutz 0 "no_protection" 1 "protection_requested"; +VAL_ 1088 GE1_Klimakompr 0 "no_Anforderung" 1 "Kompressor_aus"; +VAL_ 1088 GE1_WK 0 "WK_open" 1 "WK_regulated" 2 "WK_closed" 3 "Failure"; +VAL_ 1088 GE1_StSt_Info 0 "Engine_running_not_necessary_stop_release" 1 "Motor_start_not_mandatory_necessary_stop_prohibition" 2 "Motor_start_absolute_necessary_start_request" 3 "System_error"; +VAL_ 1088 GE1_EGS_Anf 0 "no_requirement" 1 "EGS_requirement"; +VAL_ 1088 GE1_Zielgang 0 "P (Park) | Disengaged" 1 "Gear 1 | Engaged" 2 "Gear 2 | Engaged" 3 "Gear 3 | Engaged" 4 "Gear 4 | Engaged" 5 "Gear 5 | Engaged" 6 "1m Gear" 7 "Gang_R" 8 "Gear 6 | Engaged" 9 "Gear 7 | Engaged" 10 "Gear 8 | Engaged" 14 "Speed Not Defined" 15 "Failure"; +VAL_ 1088 GE1_Wahl_Pos 0 "Intermediate Position" 1 "Pos_1" 2 "Pos_2" 3 "Pos_3" 4 "Pos_4" 5 "D (Drive)" 6 "Pos_N" 7 "R (Reverse)" 8 "P (Park)" 9 "Tiptronic Override" 10 "Pos_Z1" 11 "Pos_Z2" 12 "S (Sport)" 13 "Pos_L" 14 "Gas Pedal Force Downshift" 15 "Failure"; +VAL_ 1088 GE1_Notlauf 0 "No Emergency" 1 "No Switching" 2 "Switch to Neutral" 3 "50% Shifting Capacity" 4 "Driving Without UK" 5 "No Emeregency" 6 "No Emergency" 7 "No Emergency, Target Shifting Reached" 15 "Failure"; +VAL_ 1088 GE1_Kuehlung 0 "No Additional Cooling Requested" 1 "20% Additional Fan Cooling Requested" 2 "40% Additional Fan Cooling Requested" 3 "Maximum Additional Fan Cooling Requested"; +VAL_ 1088 GE1_Sta_OBD 0 "MIL Off" 1 "MIL On"; +VAL_ 1088 GE1_LaunchControl 0 "Launch Control Not Active" 1 "Launch Control Program Active"; +VAL_ 1088 GE1_Infobit 0 "Standard Automatic" 1 "CVT"; +VAL_ 1088 GE1_SleepInd 0 "CAN is Required" 1 "Sleep Ready"; +VAL_ 1088 GE1_Fehlereintr 0 "No Failure Memory Entry" 1 "Failure Memory Entry"; + +VAL_ 1152 MO5_Mp_Code 0 "Max_Moment" 1 "Drehzahl" 2 "Motor_Typ" 3 "Abgastyp_od_norm_Verbrauch"; +VAL_ 1152 MO5_Abgastyp 0 "no_EOBD" 1 "EOBD"; +VAL_ 1152 MO5_Abgastyp2 0 "no_OBD" 1 "OBD"; +VAL_ 1152 MO5_Abgastyp3 0 "no_DPF_verbaut" 1 "DPF_verbaut"; +VAL_ 1152 OBD_Kaltstart_Denominator 0 "Denominator_not_hochzaehlen" 1 "Bedingungen_zum_Inkr_des_Kaltstart_Denom_erf"; +VAL_ 1152 OBD_Minimum_Trip 0 "no_Min_Normed_Trip" 1 "Min_Normed_Trip"; +VAL_ 1152 MO5_DPF_reg 0 "DPF_regeneriert_nicht" 1 "DPF_regeneriert"; +VAL_ 1152 MO5_Vorgluehen 0 "Lamp_off" 1 "Lamp_on"; +VAL_ 1152 MO5_E_Gas 0 "Lamp_off" 1 "Lamp_on"; +VAL_ 1152 MO5_OBD_2 0 "Lamp_off" 1 "Lamp_on"; +VAL_ 1152 MO5_Heissl 0 "Lamp_off" 1 "Lamp_on"; +VAL_ 1152 MO5_KlimaKompr 0 "no_Anforderung" 1 "Klimakompr_aus"; +VAL_ 1152 MO5_Feld_kuehl 0 "no" 1 "yes"; +VAL_ 1152 MO5_KliKo_Red 0 "no" 1 "yes"; +VAL_ 1152 MO5_UeberlVerb 0 "no_Ueberlauf" 1 "mindestens_einmal_uebergelaufen"; +VAL_ 1152 MO5_HLeuchte 0 "no_Warnung" 1 "Vorwarnung"; +VAL_ 1152 MO5_PartikelLamp 0 "Lamp_off" 1 "Lamp_on"; +VAL_ 1152 MO5_Sta_BKU 0 "iO_oder_not_verbaut" 1 "n_iO"; +VAL_ 1152 MO5_TypStartSteu 0 "Startersteuerung_BSG_BCM_KessyD1_ZAS" 1 "Startersteuerung_durch_MSG"; +VAL_ 1152 MO5_TDE_Lampe 0 "Lamp_off" 1 "Lamp_on"; +VAL_ 1152 MO5_TDE_Text 0 "no_Text" 1 "Textanzeige_nach_ISO"; +VAL_ 1152 MO5_DZM_Daempf 0 "normale_Daempfung" 1 "dynamische_Daempfung"; +VAL_ 1152 MO5_Interlock 0 "Interlock_not_betaetigt" 1 "Interlock_betaetigt"; +VAL_ 1152 MO5_Start 0 "Start_not_zulaessig" 1 "Startfreigabe"; +VAL_ 1152 MO5_Anlasser 0 "Anlasser_darf_angesteuert_werden" 1 "Anlasser_ausspuren_Ansteuerung_not_moeglich"; +VAL_ 1152 MO5_GRA_Hauptsch 0 "Off" 1 "On"; +VAL_ 1152 MO5_Momente 0 "Einfach" 1 "Doppelt"; +VAL_ 1152 MO5_Motortext1 0 "no_Text" 1 "Text_1"; +VAL_ 1152 MO5_Motortext2 0 "no_Text" 1 "Text_2"; +VAL_ 1152 MO5_Motortext3 0 "no_Text" 1 "Text_3"; +VAL_ 1152 MO5_Motortext4 0 "no_Text" 1 "Text_4"; VAL_ 1386 ACA_StaACC 6 "ACC_rev_aus" 0 "Hauptschalter_aus" 4 "ACC_im_Hintergrund" 3 "ACC_aktiv" 1 "Reserve" 2 "ACC_passiv" 7 "ACC_irrev_aus" 5 "frei" ; VAL_ 1386 ACA_ID_StaACC 0 "keine_Anzeige" ; diff --git a/opendbc/safety/__init__.py b/opendbc/safety/__init__.py index e23e17ac..aa14cb00 100644 --- a/opendbc/safety/__init__.py +++ b/opendbc/safety/__init__.py @@ -1,4 +1,4 @@ -# constants from panda/python/__init__.py +# constants from can.h DLC_TO_LEN = [0, 1, 2, 3, 4, 5, 6, 7, 8, 12, 16, 20, 24, 32, 48, 64] LEN_TO_DLC = {length: dlc for (dlc, length) in enumerate(DLC_TO_LEN)} diff --git a/opendbc/safety/board/can.h b/opendbc/safety/board/can.h deleted file mode 100644 index c2b8dfd1..00000000 --- a/opendbc/safety/board/can.h +++ /dev/null @@ -1,10 +0,0 @@ -#pragma once - -// TODO: clean this up. it's for interop with the panda version -#ifndef CANPACKET_HEAD_SIZE - -#include "opendbc/safety/board/can_declarations.h" - -static const unsigned char dlc_to_len[] = {0U, 1U, 2U, 3U, 4U, 5U, 6U, 7U, 8U, 12U, 16U, 20U, 24U, 32U, 48U, 64U}; - -#endif diff --git a/opendbc/safety/board/drivers/can_common.h b/opendbc/safety/board/drivers/can_common.h deleted file mode 100644 index 523cca73..00000000 --- a/opendbc/safety/board/drivers/can_common.h +++ /dev/null @@ -1,19 +0,0 @@ -#pragma once -#include "opendbc/safety/board/drivers/can_common_declarations.h" - -uint8_t calculate_checksum(const uint8_t *dat, uint32_t len) { - uint8_t checksum = 0U; - for (uint32_t i = 0U; i < len; i++) { - checksum ^= dat[i]; - } - return checksum; -} - -void can_set_checksum(CANPacket_t *packet) { - packet->checksum = 0U; - packet->checksum = calculate_checksum((uint8_t *) packet, CANPACKET_HEAD_SIZE + GET_LEN(packet)); -} - -bool can_check_checksum(CANPacket_t *packet) { - return (calculate_checksum((uint8_t *) packet, CANPACKET_HEAD_SIZE + GET_LEN(packet)) == 0U); -} diff --git a/opendbc/safety/board/drivers/can_common_declarations.h b/opendbc/safety/board/drivers/can_common_declarations.h deleted file mode 100644 index c05df042..00000000 --- a/opendbc/safety/board/drivers/can_common_declarations.h +++ /dev/null @@ -1,4 +0,0 @@ -#pragma once - -uint8_t calculate_checksum(const uint8_t *dat, uint32_t len); -void can_set_checksum(CANPacket_t *packet); diff --git a/opendbc/safety/board/fake_stm.h b/opendbc/safety/board/fake_stm.h deleted file mode 100644 index 2d94bdb0..00000000 --- a/opendbc/safety/board/fake_stm.h +++ /dev/null @@ -1,28 +0,0 @@ -// minimal code to fake a panda for tests -#include -#include -#include - -#include "opendbc/safety/board/utils.h" - -#define ALLOW_DEBUG - -void print(const char *a) { - printf("%s", a); -} - -void puth(unsigned int i) { - printf("%u", i); -} - -typedef struct { - uint32_t CNT; -} TIM_TypeDef; - -TIM_TypeDef timer; -TIM_TypeDef *MICROSECOND_TIMER = &timer; -uint32_t microsecond_timer_get(void); - -uint32_t microsecond_timer_get(void) { - return MICROSECOND_TIMER->CNT; -} diff --git a/opendbc/safety/board/faults.h b/opendbc/safety/board/faults.h deleted file mode 100644 index b1281955..00000000 --- a/opendbc/safety/board/faults.h +++ /dev/null @@ -1,25 +0,0 @@ -#include "opendbc/safety/board/faults_declarations.h" - -uint8_t fault_status = FAULT_STATUS_NONE; -uint32_t faults = 0U; - -void fault_occurred(uint32_t fault) { - if ((faults & fault) == 0U) { - if ((PERMANENT_FAULTS & fault) != 0U) { - print("Permanent fault occurred: 0x"); puth(fault); print("\n"); - fault_status = FAULT_STATUS_PERMANENT; - } else { - print("Temporary fault occurred: 0x"); puth(fault); print("\n"); - fault_status = FAULT_STATUS_TEMPORARY; - } - } - faults |= fault; -} - -void fault_recovered(uint32_t fault) { - if ((PERMANENT_FAULTS & fault) == 0U) { - faults &= ~fault; - } else { - print("Cannot recover from a permanent fault!\n"); - } -} diff --git a/opendbc/safety/board/faults_declarations.h b/opendbc/safety/board/faults_declarations.h deleted file mode 100644 index a023d7e7..00000000 --- a/opendbc/safety/board/faults_declarations.h +++ /dev/null @@ -1,18 +0,0 @@ -#pragma once - -#define FAULT_STATUS_NONE 0U -#define FAULT_STATUS_TEMPORARY 1U -#define FAULT_STATUS_PERMANENT 2U - -// Fault types, excerpt from cereal.log.PandaState.FaultType for safety tests -#define FAULT_RELAY_MALFUNCTION (1UL << 0) -// ... - -// Permanent faults -#define PERMANENT_FAULTS 0U - -extern uint8_t fault_status; -extern uint32_t faults; - -void fault_occurred(uint32_t fault); -void fault_recovered(uint32_t fault); diff --git a/opendbc/safety/board/utils.h b/opendbc/safety/board/utils.h deleted file mode 100644 index db011ddb..00000000 --- a/opendbc/safety/board/utils.h +++ /dev/null @@ -1,47 +0,0 @@ -// cppcheck-suppress-macro misra-c2012-1.2; allow __typeof__ extension -#define MIN(a, b) ({ \ - __typeof__(a) _a = (a); \ - __typeof__(b) _b = (b); \ - (_a < _b) ? _a : _b; \ -}) - -// cppcheck-suppress-macro misra-c2012-1.2; allow __typeof__ extension -#define MAX(a, b) ({ \ - __typeof__(a) _a = (a); \ - __typeof__(b) _b = (b); \ - (_a > _b) ? _a : _b; \ -}) - -// cppcheck-suppress-macro misra-c2012-1.2; allow __typeof__ extension -#define CLAMP(x, low, high) ({ \ - __typeof__(x) __x = (x); \ - __typeof__(low) __low = (low);\ - __typeof__(high) __high = (high);\ - (__x > __high) ? __high : ((__x < __low) ? __low : __x); \ -}) - -// cppcheck-suppress-macro misra-c2012-1.2; allow __typeof__ extension -#define ABS(a) ({ \ - __typeof__(a) _a = (a); \ - (_a > 0) ? _a : (-_a); \ -}) - -#ifndef NULL -// this just provides a standard implementation of NULL -// in lieu of including libc in the panda build -// cppcheck-suppress [misra-c2012-21.1] -#define NULL ((void*)0) -#endif - -// STM32 HAL defines this -#ifndef UNUSED -#define UNUSED(x) ((void)(x)) -#endif - -#define COMPILE_TIME_ASSERT(pred) ((void)sizeof(char[1 - (2 * (!(pred) ? 1 : 0))])) - -// compute the time elapsed (in microseconds) from 2 counter samples -// case where ts < ts_last is ok: overflow is properly re-casted into uint32_t -static inline uint32_t get_ts_elapsed(uint32_t ts, uint32_t ts_last) { - return ts - ts_last; -} diff --git a/opendbc/safety/board/can_declarations.h b/opendbc/safety/can.h similarity index 65% rename from opendbc/safety/board/can_declarations.h rename to opendbc/safety/can.h index be2ef5c4..205ee3a2 100644 --- a/opendbc/safety/board/can_declarations.h +++ b/opendbc/safety/can.h @@ -1,8 +1,12 @@ #pragma once -#define CANPACKET_HEAD_SIZE 6U +static const unsigned char dlc_to_len[] = {0U, 1U, 2U, 3U, 4U, 5U, 6U, 7U, 8U, 12U, 16U, 20U, 24U, 32U, 48U, 64U}; + +#define CANPACKET_HEAD_SIZE 6U // non-data portion of CANPacket_t #define CANPACKET_DATA_SIZE_MAX 64U +// bump this when changing the CAN packet +#define CAN_PACKET_VERSION 4 typedef struct { unsigned char fd : 1; unsigned char bus : 3; diff --git a/opendbc/safety/safety_declarations.h b/opendbc/safety/declarations.h similarity index 99% rename from opendbc/safety/safety_declarations.h rename to opendbc/safety/declarations.h index 40a41a02..866b0d75 100644 --- a/opendbc/safety/safety_declarations.h +++ b/opendbc/safety/declarations.h @@ -26,7 +26,7 @@ #define SAFETY_SUBARU_PREGLOBAL 22U #define SAFETY_HYUNDAI_LEGACY 23U #define SAFETY_HYUNDAI_COMMUNITY 24U -#define SAFETY_STELLANTIS 25U +#define SAFETY_VOLKSWAGEN_MLB 25U #define SAFETY_FAW 26U #define SAFETY_BODY 27U #define SAFETY_HYUNDAI_CANFD 28U @@ -340,6 +340,7 @@ extern const safety_hooks subaru_hooks; extern const safety_hooks subaru_preglobal_hooks; extern const safety_hooks tesla_hooks; extern const safety_hooks toyota_hooks; +extern const safety_hooks volkswagen_mlb_hooks; extern const safety_hooks volkswagen_mqb_hooks; extern const safety_hooks volkswagen_pq_hooks; extern const safety_hooks rivian_hooks; diff --git a/opendbc/safety/helpers.h b/opendbc/safety/helpers.h index 3ce9021f..9701028c 100644 --- a/opendbc/safety/helpers.h +++ b/opendbc/safety/helpers.h @@ -1,12 +1,47 @@ -#include "opendbc/safety/safety_declarations.h" +#include "opendbc/safety/declarations.h" -static bool max_limit_check(int val, const int MAX_VAL, const int MIN_VAL) { +// cppcheck-suppress-macro misra-c2012-1.2; allow __typeof__ extension +#define SAFETY_MIN(a, b) ({ \ + __typeof__(a) _a = (a); \ + __typeof__(b) _b = (b); \ + (_a < _b) ? _a : _b; \ +}) + +// cppcheck-suppress-macro misra-c2012-1.2; allow __typeof__ extension +#define SAFETY_MAX(a, b) ({ \ + __typeof__(a) _a = (a); \ + __typeof__(b) _b = (b); \ + (_a > _b) ? _a : _b; \ +}) + +// cppcheck-suppress-macro misra-c2012-1.2; allow __typeof__ extension +#define SAFETY_CLAMP(x, low, high) ({ \ + __typeof__(x) __x = (x); \ + __typeof__(low) __low = (low);\ + __typeof__(high) __high = (high);\ + (__x > __high) ? __high : ((__x < __low) ? __low : __x); \ +}) + +// cppcheck-suppress-macro misra-c2012-1.2; allow __typeof__ extension +#define SAFETY_ABS(a) ({ \ + __typeof__(a) _a = (a); \ + (_a > 0) ? _a : (-_a); \ +}) + +#define SAFETY_UNUSED(x) ((void)(x)) + +// compute the time elapsed (in microseconds) from 2 counter samples +// case where ts < ts_last is ok: overflow is properly re-casted into uint32_t +static inline uint32_t safety_get_ts_elapsed(uint32_t ts, uint32_t ts_last) { + return ts - ts_last; +} + +static bool safety_max_limit_check(int val, const int MAX_VAL, const int MIN_VAL) { return (val > MAX_VAL) || (val < MIN_VAL); } // interp function that holds extreme values -static float interpolate(struct lookup_t xy, float x) { - +static float safety_interpolate(struct lookup_t xy, float x) { int size = sizeof(xy.x) / sizeof(xy.x[0]); float ret = xy.y[size - 1]; // default output is last point @@ -23,7 +58,7 @@ static float interpolate(struct lookup_t xy, float x) { float dx = xy.x[i+1] - x0; float dy = xy.y[i+1] - y0; // dx should not be zero as xy.x is supposed to be monotonic - dx = MAX(dx, 0.0001); + dx = SAFETY_MAX(dx, 0.0001); ret = (dy * (x - x0) / dx) + y0; break; } diff --git a/opendbc/safety/lateral.h b/opendbc/safety/lateral.h index 1e191f8d..ca815cef 100644 --- a/opendbc/safety/lateral.h +++ b/opendbc/safety/lateral.h @@ -1,5 +1,5 @@ -#include "opendbc/safety/sunnypilot/safety_mads.h" -#include "opendbc/safety/safety_declarations.h" +#include "opendbc/safety/sunnypilot/mads.h" +#include "opendbc/safety/declarations.h" // ISO 11270 static const float ISO_LATERAL_ACCEL = 3.0; // m/s^2 @@ -16,15 +16,15 @@ static bool dist_to_meas_check(int val, int val_last, struct sample_t *val_meas, const int MAX_RATE_UP, const int MAX_RATE_DOWN, const int MAX_ERROR) { // *** val rate limit check *** - int highest_allowed_rl = MAX(val_last, 0) + MAX_RATE_UP; - int lowest_allowed_rl = MIN(val_last, 0) - MAX_RATE_UP; + int highest_allowed_rl = SAFETY_MAX(val_last, 0) + MAX_RATE_UP; + int lowest_allowed_rl = SAFETY_MIN(val_last, 0) - MAX_RATE_UP; // if we've exceeded the meas val, we must start moving toward 0 - int highest_allowed = MIN(highest_allowed_rl, MAX(val_last - MAX_RATE_DOWN, MAX(val_meas->max, 0) + MAX_ERROR)); - int lowest_allowed = MAX(lowest_allowed_rl, MIN(val_last + MAX_RATE_DOWN, MIN(val_meas->min, 0) - MAX_ERROR)); + int highest_allowed = SAFETY_MIN(highest_allowed_rl, SAFETY_MAX(val_last - MAX_RATE_DOWN, SAFETY_MAX(val_meas->max, 0) + MAX_ERROR)); + int lowest_allowed = SAFETY_MAX(lowest_allowed_rl, SAFETY_MIN(val_last + MAX_RATE_DOWN, SAFETY_MIN(val_meas->min, 0) - MAX_ERROR)); // check for violation - return max_limit_check(val, highest_allowed, lowest_allowed); + return safety_max_limit_check(val, highest_allowed, lowest_allowed); } // check that commanded value isn't fighting against driver @@ -33,32 +33,32 @@ static bool driver_limit_check(int val, int val_last, const struct sample_t *val const int MAX_ALLOWANCE, const int DRIVER_FACTOR) { // torque delta/rate limits - int highest_allowed_rl = MAX(val_last, 0) + MAX_RATE_UP; - int lowest_allowed_rl = MIN(val_last, 0) - MAX_RATE_UP; + int highest_allowed_rl = SAFETY_MAX(val_last, 0) + MAX_RATE_UP; + int lowest_allowed_rl = SAFETY_MIN(val_last, 0) - MAX_RATE_UP; // driver int driver_max_limit = MAX_VAL + (MAX_ALLOWANCE + val_driver->max) * DRIVER_FACTOR; int driver_min_limit = -MAX_VAL + (-MAX_ALLOWANCE + val_driver->min) * DRIVER_FACTOR; // if we've exceeded the applied torque, we must start moving toward 0 - int highest_allowed = MIN(highest_allowed_rl, MAX(val_last - MAX_RATE_DOWN, - MAX(driver_max_limit, 0))); - int lowest_allowed = MAX(lowest_allowed_rl, MIN(val_last + MAX_RATE_DOWN, - MIN(driver_min_limit, 0))); + int highest_allowed = SAFETY_MIN(highest_allowed_rl, SAFETY_MAX(val_last - MAX_RATE_DOWN, + SAFETY_MAX(driver_max_limit, 0))); + int lowest_allowed = SAFETY_MAX(lowest_allowed_rl, SAFETY_MIN(val_last + MAX_RATE_DOWN, + SAFETY_MIN(driver_min_limit, 0))); // check for violation - return max_limit_check(val, highest_allowed, lowest_allowed); + return safety_max_limit_check(val, highest_allowed, lowest_allowed); } // real time check, mainly used for steer torque rate limiter static bool rt_torque_rate_limit_check(int val, int val_last, const int MAX_RT_DELTA) { // *** torque real time rate limit check *** - int highest_val = MAX(val_last, 0) + MAX_RT_DELTA; - int lowest_val = MIN(val_last, 0) - MAX_RT_DELTA; + int highest_val = SAFETY_MAX(val_last, 0) + MAX_RT_DELTA; + int lowest_val = SAFETY_MIN(val_last, 0) - MAX_RT_DELTA; // check for violation - return max_limit_check(val, highest_val, lowest_val); + return safety_max_limit_check(val, highest_val, lowest_val); } // Safety checks for torque-based steering commands @@ -71,12 +71,12 @@ bool steer_torque_cmd_checks(int desired_torque, int steer_req, const TorqueStee int max_torque = limits.max_torque; if (limits.dynamic_max_torque) { const float fudged_speed = (vehicle_speed.min / VEHICLE_SPEED_FACTOR) - 1.; - max_torque = interpolate(limits.max_torque_lookup, fudged_speed) + 1; - max_torque = CLAMP(max_torque, -limits.max_torque, limits.max_torque); + max_torque = safety_interpolate(limits.max_torque_lookup, fudged_speed) + 1; + max_torque = SAFETY_CLAMP(max_torque, -limits.max_torque, limits.max_torque); } // *** global torque limit check *** - violation |= max_limit_check(desired_torque, max_torque, -max_torque); + violation |= safety_max_limit_check(desired_torque, max_torque, -max_torque); // *** torque rate limit check *** if (limits.type == TorqueDriverLimited) { @@ -93,7 +93,7 @@ bool steer_torque_cmd_checks(int desired_torque, int steer_req, const TorqueStee violation |= rt_torque_rate_limit_check(desired_torque, rt_torque_last, limits.max_rt_delta); // every RT_INTERVAL set the new limits - uint32_t ts_elapsed = get_ts_elapsed(ts, ts_torque_check_last); + uint32_t ts_elapsed = safety_get_ts_elapsed(ts, ts_torque_check_last); if (ts_elapsed > MAX_RT_INTERVAL) { rt_torque_last = desired_torque; ts_torque_check_last = ts; @@ -122,7 +122,7 @@ bool steer_torque_cmd_checks(int desired_torque, int steer_req, const TorqueStee } // or we've cut torque too recently in time - uint32_t ts_elapsed = get_ts_elapsed(ts, ts_steer_req_mismatch_last); + uint32_t ts_elapsed = safety_get_ts_elapsed(ts, ts_steer_req_mismatch_last); if (ts_elapsed < limits.min_valid_request_rt_interval) { violation = true; } @@ -135,9 +135,9 @@ bool steer_torque_cmd_checks(int desired_torque, int steer_req, const TorqueStee valid_steer_req_count = 0; ts_steer_req_mismatch_last = ts; - invalid_steer_req_count = MIN(invalid_steer_req_count + 1, limits.max_invalid_request_frames); + invalid_steer_req_count = SAFETY_MIN(invalid_steer_req_count + 1, limits.max_invalid_request_frames); } else { - valid_steer_req_count = MIN(valid_steer_req_count + 1, limits.min_valid_request_frames); + valid_steer_req_count = SAFETY_MIN(valid_steer_req_count + 1, limits.min_valid_request_frames); invalid_steer_req_count = 0; } } @@ -168,7 +168,7 @@ static bool rt_angle_rate_limit_check(AngleSteeringLimits limits) { rt_angle_msgs += 1U; // every RT_INTERVAL reset message counter - uint32_t ts_elapsed = get_ts_elapsed(ts, ts_angle_check_last); + uint32_t ts_elapsed = safety_get_ts_elapsed(ts, ts_angle_check_last); if (ts_elapsed >= MAX_RT_INTERVAL) { rt_angle_msgs = 0; ts_angle_check_last = ts; @@ -187,8 +187,8 @@ bool steer_angle_cmd_checks(int desired_angle, bool steer_control_enabled, const // always slightly above openpilot's in case we read an updated speed in between angle commands // TODO: this speed fudge can be much lower, look at data to determine the lowest reasonable offset const float fudged_speed = (vehicle_speed.min / VEHICLE_SPEED_FACTOR) - 1.; - int delta_angle_up = (interpolate(limits.angle_rate_up_lookup, fudged_speed) * limits.angle_deg_to_can) + 1.; - int delta_angle_down = (interpolate(limits.angle_rate_down_lookup, fudged_speed) * limits.angle_deg_to_can) + 1.; + int delta_angle_up = (safety_interpolate(limits.angle_rate_up_lookup, fudged_speed) * limits.angle_deg_to_can) + 1.; + int delta_angle_down = (safety_interpolate(limits.angle_rate_down_lookup, fudged_speed) * limits.angle_deg_to_can) + 1.; // allow down limits at zero since small floats from openpilot will be rounded to 0 // TODO: openpilot should be cognizant of this and not send small floats @@ -200,8 +200,8 @@ bool steer_angle_cmd_checks(int desired_angle, bool steer_control_enabled, const if (limits.enforce_angle_error && ((vehicle_speed.values[0] / VEHICLE_SPEED_FACTOR) > limits.angle_error_min_speed)) { // flipped fudge to avoid false positives const float fudged_speed_error = (vehicle_speed.max / VEHICLE_SPEED_FACTOR) + 1.; - const int delta_angle_up_relaxed = (interpolate(limits.angle_rate_up_lookup, fudged_speed_error) * limits.angle_deg_to_can) - 1.; - const int delta_angle_down_relaxed = (interpolate(limits.angle_rate_down_lookup, fudged_speed_error) * limits.angle_deg_to_can) - 1.; + const int delta_angle_up_relaxed = (safety_interpolate(limits.angle_rate_up_lookup, fudged_speed_error) * limits.angle_deg_to_can) - 1.; + const int delta_angle_down_relaxed = (safety_interpolate(limits.angle_rate_down_lookup, fudged_speed_error) * limits.angle_deg_to_can) - 1.; // the minimum and maximum angle allowed based on the measured angle const int lowest_desired_angle_error = angle_meas.min - limits.max_angle_error - 1; @@ -210,22 +210,22 @@ bool steer_angle_cmd_checks(int desired_angle, bool steer_control_enabled, const // the MAX is to allow the desired angle to hit the edge of the bounds and not require going under it if (desired_angle_last > highest_desired_angle_error) { const int delta = (desired_angle_last >= 0) ? delta_angle_down_relaxed : delta_angle_up_relaxed; - highest_desired_angle = MAX(desired_angle_last - delta, highest_desired_angle_error); + highest_desired_angle = SAFETY_MAX(desired_angle_last - delta, highest_desired_angle_error); } else if (desired_angle_last < lowest_desired_angle_error) { const int delta = (desired_angle_last <= 0) ? delta_angle_down_relaxed : delta_angle_up_relaxed; - lowest_desired_angle = MIN(desired_angle_last + delta, lowest_desired_angle_error); + lowest_desired_angle = SAFETY_MIN(desired_angle_last + delta, lowest_desired_angle_error); } else { // already inside error boundary, don't allow commanding outside it - highest_desired_angle = MIN(highest_desired_angle, highest_desired_angle_error); - lowest_desired_angle = MAX(lowest_desired_angle, lowest_desired_angle_error); + highest_desired_angle = SAFETY_MIN(highest_desired_angle, highest_desired_angle_error); + lowest_desired_angle = SAFETY_MAX(lowest_desired_angle, lowest_desired_angle_error); } // don't enforce above the max steer // TODO: this should always be done - lowest_desired_angle = CLAMP(lowest_desired_angle, -limits.max_angle, limits.max_angle); - highest_desired_angle = CLAMP(highest_desired_angle, -limits.max_angle, limits.max_angle); + lowest_desired_angle = SAFETY_CLAMP(lowest_desired_angle, -limits.max_angle, limits.max_angle); + highest_desired_angle = SAFETY_CLAMP(highest_desired_angle, -limits.max_angle, limits.max_angle); } // check not above ISO 11270 lateral accel assuming worst case road roll @@ -235,23 +235,23 @@ bool steer_angle_cmd_checks(int desired_angle, bool steer_control_enabled, const static const float MAX_LATERAL_ACCEL = ISO_LATERAL_ACCEL - (EARTH_G * AVERAGE_ROAD_ROLL); // ~2.4 m/s^2 // Allow small tolerance by using minimum speed and rounding curvature up - const float speed_lower = MAX(vehicle_speed.min / VEHICLE_SPEED_FACTOR, 1.0); - const float speed_upper = MAX(vehicle_speed.max / VEHICLE_SPEED_FACTOR, 1.0); + const float speed_lower = SAFETY_MAX(vehicle_speed.min / VEHICLE_SPEED_FACTOR, 1.0); + const float speed_upper = SAFETY_MAX(vehicle_speed.max / VEHICLE_SPEED_FACTOR, 1.0); const int max_curvature_upper = (MAX_LATERAL_ACCEL / (speed_lower * speed_lower) * limits.angle_deg_to_can) + 1.; const int max_curvature_lower = (MAX_LATERAL_ACCEL / (speed_upper * speed_upper) * limits.angle_deg_to_can) - 1.; // ensure that the curvature error doesn't try to enforce above this limit if (desired_angle_last > 0) { - lowest_desired_angle = CLAMP(lowest_desired_angle, -max_curvature_lower, max_curvature_lower); - highest_desired_angle = CLAMP(highest_desired_angle, -max_curvature_upper, max_curvature_upper); + lowest_desired_angle = SAFETY_CLAMP(lowest_desired_angle, -max_curvature_lower, max_curvature_lower); + highest_desired_angle = SAFETY_CLAMP(highest_desired_angle, -max_curvature_upper, max_curvature_upper); } else { - lowest_desired_angle = CLAMP(lowest_desired_angle, -max_curvature_upper, max_curvature_upper); - highest_desired_angle = CLAMP(highest_desired_angle, -max_curvature_lower, max_curvature_lower); + lowest_desired_angle = SAFETY_CLAMP(lowest_desired_angle, -max_curvature_upper, max_curvature_upper); + highest_desired_angle = SAFETY_CLAMP(highest_desired_angle, -max_curvature_lower, max_curvature_lower); } } // check for violation; - violation |= max_limit_check(desired_angle, highest_desired_angle, lowest_desired_angle); + violation |= safety_max_limit_check(desired_angle, highest_desired_angle, lowest_desired_angle); } desired_angle_last = desired_angle; @@ -260,9 +260,9 @@ bool steer_angle_cmd_checks(int desired_angle, bool steer_control_enabled, const if (limits.inactive_angle_is_zero) { violation |= desired_angle != 0; } else { - const int max_inactive_angle = CLAMP(angle_meas.max, -limits.max_angle, limits.max_angle) + 1; - const int min_inactive_angle = CLAMP(angle_meas.min, -limits.max_angle, limits.max_angle) - 1; - violation |= max_limit_check(desired_angle, max_inactive_angle, min_inactive_angle); + const int max_inactive_angle = SAFETY_CLAMP(angle_meas.max, -limits.max_angle, limits.max_angle) + 1; + const int min_inactive_angle = SAFETY_CLAMP(angle_meas.min, -limits.max_angle, limits.max_angle) - 1; + violation |= safety_max_limit_check(desired_angle, max_inactive_angle, min_inactive_angle); } } @@ -276,7 +276,7 @@ bool steer_angle_cmd_checks(int desired_angle, bool steer_control_enabled, const if (limits.inactive_angle_is_zero) { desired_angle_last = 0; } else { - desired_angle_last = CLAMP(angle_meas.values[0], -limits.max_angle, limits.max_angle); + desired_angle_last = SAFETY_CLAMP(angle_meas.values[0], -limits.max_angle, limits.max_angle); } } @@ -304,7 +304,7 @@ bool steer_angle_cmd_checks_vm(int desired_angle, bool steer_control_enabled, co // Lower than ISO 11270 lateral jerk limit, which is 5.0 m/s^3 static const float MAX_LATERAL_JERK = 3.0 + (EARTH_G * AVERAGE_ROAD_ROLL); // ~3.6 m/s^3 - const float fudged_speed = MAX((vehicle_speed.min / VEHICLE_SPEED_FACTOR) - 1.0, 1.0); + const float fudged_speed = SAFETY_MAX((vehicle_speed.min / VEHICLE_SPEED_FACTOR) - 1.0, 1.0); const float curvature_factor = get_curvature_factor(fudged_speed, params); bool violation = false; @@ -323,14 +323,14 @@ bool steer_angle_cmd_checks_vm(int desired_angle, bool steer_control_enabled, co const int highest_desired_angle = desired_angle_last + max_angle_delta_can; const int lowest_desired_angle = desired_angle_last - max_angle_delta_can; - violation |= max_limit_check(desired_angle, highest_desired_angle, lowest_desired_angle); + violation |= safety_max_limit_check(desired_angle, highest_desired_angle, lowest_desired_angle); // *** ISO lateral accel limit *** const float max_curvature = MAX_LATERAL_ACCEL / (fudged_speed * fudged_speed); const float max_angle = get_angle_from_curvature(max_curvature, curvature_factor, params); const int max_angle_can = (max_angle * limits.angle_deg_to_can) + 1.; - violation |= max_limit_check(desired_angle, max_angle_can, -max_angle_can); + violation |= safety_max_limit_check(desired_angle, max_angle_can, -max_angle_can); // *** angle real time rate limit check *** violation |= rt_angle_rate_limit_check(limits); @@ -339,9 +339,9 @@ bool steer_angle_cmd_checks_vm(int desired_angle, bool steer_control_enabled, co // Angle should either be 0 or same as current angle while not steering if (!steer_control_enabled) { - const int max_inactive_angle = CLAMP(angle_meas.max, -limits.max_angle, limits.max_angle) + 1; - const int min_inactive_angle = CLAMP(angle_meas.min, -limits.max_angle, limits.max_angle) - 1; - violation |= max_limit_check(desired_angle, max_inactive_angle, min_inactive_angle); + const int max_inactive_angle = SAFETY_CLAMP(angle_meas.max, -limits.max_angle, limits.max_angle) + 1; + const int min_inactive_angle = SAFETY_CLAMP(angle_meas.min, -limits.max_angle, limits.max_angle) - 1; + violation |= safety_max_limit_check(desired_angle, max_inactive_angle, min_inactive_angle); } // No angle control allowed when controls are not allowed @@ -351,7 +351,7 @@ bool steer_angle_cmd_checks_vm(int desired_angle, bool steer_control_enabled, co // reset to current angle if either controls is not allowed or there's a violation if (violation || !is_lat_active()) { - desired_angle_last = CLAMP(angle_meas.values[0], -limits.max_angle, limits.max_angle); + desired_angle_last = SAFETY_CLAMP(angle_meas.values[0], -limits.max_angle, limits.max_angle); } return violation; diff --git a/opendbc/safety/longitudinal.h b/opendbc/safety/longitudinal.h index 186559d6..8f516df8 100644 --- a/opendbc/safety/longitudinal.h +++ b/opendbc/safety/longitudinal.h @@ -1,4 +1,4 @@ -#include "opendbc/safety/safety_declarations.h" +#include "opendbc/safety/declarations.h" bool get_longitudinal_allowed(void) { return controls_allowed && !gas_pressed_prev; @@ -6,7 +6,7 @@ bool get_longitudinal_allowed(void) { // Safety checks for longitudinal actuation bool longitudinal_accel_checks(int desired_accel, const LongitudinalLimits limits) { - bool accel_valid = get_longitudinal_allowed() && !max_limit_check(desired_accel, limits.max_accel, limits.min_accel); + bool accel_valid = get_longitudinal_allowed() && !safety_max_limit_check(desired_accel, limits.max_accel, limits.min_accel); bool accel_inactive = desired_accel == limits.inactive_accel; return !(accel_valid || accel_inactive); } @@ -16,13 +16,13 @@ bool longitudinal_speed_checks(int desired_speed, const LongitudinalLimits limit } bool longitudinal_transmission_rpm_checks(int desired_transmission_rpm, const LongitudinalLimits limits) { - bool transmission_rpm_valid = get_longitudinal_allowed() && !max_limit_check(desired_transmission_rpm, limits.max_transmission_rpm, limits.min_transmission_rpm); + bool transmission_rpm_valid = get_longitudinal_allowed() && !safety_max_limit_check(desired_transmission_rpm, limits.max_transmission_rpm, limits.min_transmission_rpm); bool transmission_rpm_inactive = desired_transmission_rpm == limits.inactive_transmission_rpm; return !(transmission_rpm_valid || transmission_rpm_inactive); } bool longitudinal_gas_checks(int desired_gas, const LongitudinalLimits limits) { - bool gas_valid = get_longitudinal_allowed() && !max_limit_check(desired_gas, limits.max_gas, limits.min_gas); + bool gas_valid = get_longitudinal_allowed() && !safety_max_limit_check(desired_gas, limits.max_gas, limits.min_gas); bool gas_inactive = desired_gas == limits.inactive_gas; return !(gas_valid || gas_inactive); } diff --git a/opendbc/safety/modes/body.h b/opendbc/safety/modes/body.h index a3093b26..e3d5c212 100644 --- a/opendbc/safety/modes/body.h +++ b/opendbc/safety/modes/body.h @@ -1,6 +1,6 @@ #pragma once -#include "opendbc/safety/safety_declarations.h" +#include "opendbc/safety/declarations.h" static void body_rx_hook(const CANPacket_t *msg) { if (msg->addr == 0x201U) { @@ -32,7 +32,7 @@ static safety_config body_init(uint16_t param) { static const CanMsg BODY_TX_MSGS[] = {{0x250, 0, 8, .check_relay = false}, {0x250, 0, 6, .check_relay = false}, {0x251, 0, 5, .check_relay = false}, // body {0x1, 0, 8, .check_relay = false}}; // CAN flasher - UNUSED(param); + SAFETY_UNUSED(param); safety_config ret = BUILD_SAFETY_CFG(body_rx_checks, BODY_TX_MSGS); ret.disable_forwarding = true; return ret; diff --git a/opendbc/safety/modes/chrysler.h b/opendbc/safety/modes/chrysler.h index f4f62986..009cfe19 100644 --- a/opendbc/safety/modes/chrysler.h +++ b/opendbc/safety/modes/chrysler.h @@ -1,6 +1,6 @@ #pragma once -#include "opendbc/safety/safety_declarations.h" +#include "opendbc/safety/declarations.h" typedef struct { const unsigned int EPS_2; diff --git a/opendbc/safety/modes/defaults.h b/opendbc/safety/modes/defaults.h index 03551c91..5f9d9376 100644 --- a/opendbc/safety/modes/defaults.h +++ b/opendbc/safety/modes/defaults.h @@ -1,25 +1,25 @@ #pragma once -#include "opendbc/safety/safety_declarations.h" +#include "opendbc/safety/declarations.h" // GCOV_EXCL_START // Unreachable by design (doesn't define any rx msgs) void default_rx_hook(const CANPacket_t *msg) { - UNUSED(msg); + SAFETY_UNUSED(msg); } // GCOV_EXCL_STOP // *** no output safety mode *** static safety_config nooutput_init(uint16_t param) { - UNUSED(param); + SAFETY_UNUSED(param); return (safety_config){NULL, 0, NULL, 0, true}; // NOLINT(readability/braces) } // GCOV_EXCL_START // Unreachable by design (doesn't define any tx msgs) static bool nooutput_tx_hook(const CANPacket_t *msg) { - UNUSED(msg); + SAFETY_UNUSED(msg); return false; } // GCOV_EXCL_STOP @@ -40,7 +40,7 @@ static safety_config alloutput_init(uint16_t param) { } static bool alloutput_tx_hook(const CANPacket_t *msg) { - UNUSED(msg); + SAFETY_UNUSED(msg); return true; } diff --git a/opendbc/safety/modes/elm327.h b/opendbc/safety/modes/elm327.h index 8abb938e..dbcc0601 100644 --- a/opendbc/safety/modes/elm327.h +++ b/opendbc/safety/modes/elm327.h @@ -1,6 +1,6 @@ #pragma once -#include "opendbc/safety/safety_declarations.h" +#include "opendbc/safety/declarations.h" #include "opendbc/safety/modes/defaults.h" static bool elm327_tx_hook(const CANPacket_t *msg) { diff --git a/opendbc/safety/modes/ford.h b/opendbc/safety/modes/ford.h index 4dd18e20..69115be9 100644 --- a/opendbc/safety/modes/ford.h +++ b/opendbc/safety/modes/ford.h @@ -1,6 +1,6 @@ #pragma once -#include "opendbc/safety/safety_declarations.h" +#include "opendbc/safety/declarations.h" // Safety-relevant CAN messages for Ford vehicles. #define FORD_EngBrakeData 0x165U // RX from PCM, for driver brake pedal and cruise state @@ -137,7 +137,7 @@ static void ford_rx_hook(const CANPacket_t *msg) { // Signal: VehYaw_W_Actl // TODO: we should use the speed which results in the closest angle measurement to the desired angle float ford_yaw_rate = (((msg->data[2] << 8U) | msg->data[3]) * 0.0002) - 6.5; - float current_curvature = ford_yaw_rate / MAX(vehicle_speed.values[0] / VEHICLE_SPEED_FACTOR, 0.1); + float current_curvature = ford_yaw_rate / SAFETY_MAX(vehicle_speed.values[0] / VEHICLE_SPEED_FACTOR, 0.1); // convert current curvature into units on CAN for comparison with desired curvature update_sample(&angle_meas, ROUND(current_curvature * FORD_STEERING_LIMITS.angle_deg_to_can)); } diff --git a/opendbc/safety/modes/gm.h b/opendbc/safety/modes/gm.h index 4c774f06..ffc9ae01 100644 --- a/opendbc/safety/modes/gm.h +++ b/opendbc/safety/modes/gm.h @@ -1,6 +1,6 @@ #pragma once -#include "opendbc/safety/safety_declarations.h" +#include "opendbc/safety/declarations.h" // TODO: do checksum and counter checks. Add correct timestep, 0.1s for now. #define GM_COMMON_RX_CHECKS \ diff --git a/opendbc/safety/modes/honda.h b/opendbc/safety/modes/honda.h index 0db40551..46daddf9 100644 --- a/opendbc/safety/modes/honda.h +++ b/opendbc/safety/modes/honda.h @@ -1,6 +1,6 @@ #pragma once -#include "opendbc/safety/safety_declarations.h" +#include "opendbc/safety/declarations.h" // All common address checks except SCM_BUTTONS which isn't on one Nidec safety configuration #define HONDA_COMMON_NO_SCM_FEEDBACK_RX_CHECKS(pt_bus) \ diff --git a/opendbc/safety/modes/hyundai.h b/opendbc/safety/modes/hyundai.h index 95ab8337..b4a1fe54 100644 --- a/opendbc/safety/modes/hyundai.h +++ b/opendbc/safety/modes/hyundai.h @@ -1,6 +1,6 @@ #pragma once -#include "opendbc/safety/safety_declarations.h" +#include "opendbc/safety/declarations.h" #include "opendbc/safety/modes/hyundai_common.h" #define HYUNDAI_LIMITS(steer, rate_up, rate_down) { \ diff --git a/opendbc/safety/modes/hyundai_canfd.h b/opendbc/safety/modes/hyundai_canfd.h index ce505937..f9cf5557 100644 --- a/opendbc/safety/modes/hyundai_canfd.h +++ b/opendbc/safety/modes/hyundai_canfd.h @@ -1,6 +1,6 @@ #pragma once -#include "opendbc/safety/safety_declarations.h" +#include "opendbc/safety/declarations.h" #include "opendbc/safety/modes/hyundai_common.h" #define HYUNDAI_CANFD_CRUISE_BUTTON_TX_MSGS(bus) \ diff --git a/opendbc/safety/modes/hyundai_common.h b/opendbc/safety/modes/hyundai_common.h index 2d159371..79dce7fd 100644 --- a/opendbc/safety/modes/hyundai_common.h +++ b/opendbc/safety/modes/hyundai_common.h @@ -1,6 +1,6 @@ #pragma once -#include "opendbc/safety/safety_declarations.h" +#include "opendbc/safety/declarations.h" extern uint16_t hyundai_canfd_crc_lut[256]; uint16_t hyundai_canfd_crc_lut[256]; @@ -127,7 +127,7 @@ void hyundai_common_cruise_buttons_check(const int cruise_button, const bool mai if ((cruise_button == HYUNDAI_BTN_RESUME) || (cruise_button == HYUNDAI_BTN_SET) || (cruise_button == HYUNDAI_BTN_CANCEL) || main_button) { hyundai_last_button_interaction = 0U; } else { - hyundai_last_button_interaction = MIN(hyundai_last_button_interaction + 1U, HYUNDAI_PREV_BUTTON_SAMPLES); + hyundai_last_button_interaction = SAFETY_MIN(hyundai_last_button_interaction + 1U, HYUNDAI_PREV_BUTTON_SAMPLES); } if (hyundai_longitudinal) { diff --git a/opendbc/safety/modes/mazda.h b/opendbc/safety/modes/mazda.h index 0895f903..9838fecc 100644 --- a/opendbc/safety/modes/mazda.h +++ b/opendbc/safety/modes/mazda.h @@ -1,6 +1,6 @@ #pragma once -#include "opendbc/safety/safety_declarations.h" +#include "opendbc/safety/declarations.h" // CAN msgs we care about #define MAZDA_LKAS 0x243U @@ -95,7 +95,7 @@ static safety_config mazda_init(uint16_t param) { {.msg = {{MAZDA_PEDALS, 0, 8, 50U, .ignore_checksum = true, .ignore_counter = true, .ignore_quality_flag = true}, { 0 }, { 0 }}}, }; - UNUSED(param); + SAFETY_UNUSED(param); return BUILD_SAFETY_CFG(mazda_rx_checks, MAZDA_TX_MSGS); } diff --git a/opendbc/safety/modes/nissan.h b/opendbc/safety/modes/nissan.h index af996547..1742a5e9 100644 --- a/opendbc/safety/modes/nissan.h +++ b/opendbc/safety/modes/nissan.h @@ -1,6 +1,6 @@ #pragma once -#include "opendbc/safety/safety_declarations.h" +#include "opendbc/safety/declarations.h" #define NISSAN_COMMON_RX_CHECKS \ {.msg = {{0x2, 0, 5, 100U, .ignore_checksum = true, .ignore_counter = true, .ignore_quality_flag = true}, \ diff --git a/opendbc/safety/modes/psa.h b/opendbc/safety/modes/psa.h index 115bcdd7..6bbd7b9c 100644 --- a/opendbc/safety/modes/psa.h +++ b/opendbc/safety/modes/psa.h @@ -1,6 +1,6 @@ #pragma once -#include "opendbc/safety/safety_declarations.h" +#include "opendbc/safety/declarations.h" #define PSA_STEERING 757U // RX from XXX, driver torque #define PSA_STEERING_ALT 773U // RX from EPS, steering angle @@ -124,7 +124,7 @@ static bool psa_tx_hook(const CANPacket_t *msg) { } static safety_config psa_init(uint16_t param) { - UNUSED(param); + SAFETY_UNUSED(param); static const CanMsg PSA_TX_MSGS[] = { {PSA_LANE_KEEP_ASSIST, PSA_MAIN_BUS, 8, .check_relay = true}, // EPS steering }; diff --git a/opendbc/safety/modes/rivian.h b/opendbc/safety/modes/rivian.h index f6990f71..35645b7c 100644 --- a/opendbc/safety/modes/rivian.h +++ b/opendbc/safety/modes/rivian.h @@ -1,6 +1,6 @@ #pragma once -#include "opendbc/safety/safety_declarations.h" +#include "opendbc/safety/declarations.h" static uint8_t rivian_get_counter(const CANPacket_t *msg) { uint8_t cnt = 0; @@ -167,7 +167,7 @@ static safety_config rivian_init(uint16_t param) { bool rivian_longitudinal = false; - UNUSED(param); + SAFETY_UNUSED(param); #ifdef ALLOW_DEBUG const int FLAG_RIVIAN_LONG_CONTROL = 1; rivian_longitudinal = GET_FLAG(param, FLAG_RIVIAN_LONG_CONTROL); diff --git a/opendbc/safety/modes/subaru.h b/opendbc/safety/modes/subaru.h index 46f302a0..0d214e25 100644 --- a/opendbc/safety/modes/subaru.h +++ b/opendbc/safety/modes/subaru.h @@ -1,6 +1,6 @@ #pragma once -#include "opendbc/safety/safety_declarations.h" +#include "opendbc/safety/declarations.h" #include "opendbc/safety/modes/subaru_common.h" #define SUBARU_STEERING_LIMITS_GENERATOR(steer_max, rate_up, rate_down) \ diff --git a/opendbc/safety/modes/subaru_preglobal.h b/opendbc/safety/modes/subaru_preglobal.h index 34edaa66..38dffa05 100644 --- a/opendbc/safety/modes/subaru_preglobal.h +++ b/opendbc/safety/modes/subaru_preglobal.h @@ -1,6 +1,6 @@ #pragma once -#include "opendbc/safety/safety_declarations.h" +#include "opendbc/safety/declarations.h" #include "opendbc/safety/modes/subaru_common.h" // Preglobal platform diff --git a/opendbc/safety/modes/tesla.h b/opendbc/safety/modes/tesla.h index 15a9c0a4..0a530856 100644 --- a/opendbc/safety/modes/tesla.h +++ b/opendbc/safety/modes/tesla.h @@ -1,6 +1,6 @@ #pragma once -#include "opendbc/safety/safety_declarations.h" +#include "opendbc/safety/declarations.h" #define TESLA_COMMON_RX_CHECKS \ {.msg = {{0x2b9, 2, 8, 25U, .max_counter = 7U, .ignore_quality_flag = true}, { 0 }, { 0 }}}, /* DAS_control */ \ @@ -354,7 +354,7 @@ static safety_config tesla_init(uint16_t param) { {0x27D, 0, 3, .check_relay = true, .disable_static_blocking = true}, // APS_eacMonitor }; - UNUSED(param); + SAFETY_UNUSED(param); #ifdef ALLOW_DEBUG const int TESLA_FLAG_LONGITUDINAL_CONTROL = 1; tesla_longitudinal = GET_FLAG(param, TESLA_FLAG_LONGITUDINAL_CONTROL); diff --git a/opendbc/safety/modes/toyota.h b/opendbc/safety/modes/toyota.h index d8a49fba..08002937 100644 --- a/opendbc/safety/modes/toyota.h +++ b/opendbc/safety/modes/toyota.h @@ -1,6 +1,6 @@ #pragma once -#include "opendbc/safety/safety_declarations.h" +#include "opendbc/safety/declarations.h" // Stock longitudinal #define TOYOTA_BASE_TX_MSGS \ @@ -14,7 +14,7 @@ #define TOYOTA_COMMON_SECOC_TX_MSGS \ TOYOTA_BASE_TX_MSGS \ {0x2E4, 0, 8, .check_relay = true}, {0x131, 0, 8, .check_relay = true}, \ - {0x343, 0, 8, .check_relay = false}, /* ACC cancel cmd */ \ + {0x343, 0, 8, .check_relay = false}, /* ACC cancel cmd */ \ #define TOYOTA_COMMON_LONG_TX_MSGS \ TOYOTA_COMMON_TX_MSGS \ @@ -31,6 +31,11 @@ /* ACC */ \ {0x343, 0, 8, .check_relay = true}, \ +#define TOYOTA_COMMON_SECOC_LONG_TX_MSGS \ + TOYOTA_COMMON_SECOC_TX_MSGS \ + {0x343, 0, 8, .check_relay = true}, \ + {0x183, 0, 8, .check_relay = true}, /* ACC_CONTROL_2 */ \ + #define TOYOTA_COMMON_SECOC_LONG_TX_MSGS \ TOYOTA_COMMON_SECOC_TX_MSGS \ {0x343, 0, 8, .check_relay = true}, /* ACC */ \ @@ -260,6 +265,10 @@ static bool toyota_tx_hook(const CANPacket_t *msg) { int desired_accel = toyota_get_longitudinal_desired_accel_tx(msg); bool violation = false; + if (toyota_secoc) { + // SecOC cars move accel to 0x183. Only allow inactive accel on 0x343 to match stock behavior + violation = desired_accel != TOYOTA_LONG_LIMITS.inactive_accel; + } violation |= longitudinal_accel_checks(desired_accel, TOYOTA_LONG_LIMITS); // only ACC messages that cancel are allowed when openpilot is not controlling longitudinal @@ -294,6 +303,13 @@ static bool toyota_tx_hook(const CANPacket_t *msg) { } } + if (msg->addr == 0x183U) { + int desired_accel = (msg->data[0] << 8) | msg->data[1]; + desired_accel = to_signed(desired_accel, 16); + + tx = !longitudinal_accel_checks(desired_accel, TOYOTA_LONG_LIMITS); + } + // AEB: block all actuation. only used when DSU is unplugged if (msg->addr == 0x283U) { // only allow the checksum, which is the last byte @@ -339,12 +355,12 @@ static bool toyota_tx_hook(const CANPacket_t *msg) { } // check if we should wind down torque - int driver_torque = MIN(ABS(torque_driver.min), ABS(torque_driver.max)); + int driver_torque = SAFETY_MIN(SAFETY_ABS(torque_driver.min), SAFETY_ABS(torque_driver.max)); if ((driver_torque > TOYOTA_LTA_MAX_DRIVER_TORQUE) && (torque_wind_down != 0)) { tx = false; } - int eps_torque = MIN(ABS(torque_meas.min), ABS(torque_meas.max)); + int eps_torque = SAFETY_MIN(SAFETY_ABS(torque_meas.min), SAFETY_ABS(torque_meas.max)); if ((eps_torque > TOYOTA_LTA_MAX_MEAS_TORQUE) && (torque_wind_down != 0)) { tx = false; } @@ -424,6 +440,10 @@ static safety_config toyota_init(uint16_t param) { {0x200, 0, 6, .check_relay = false}, // gas interceptor }; + static const CanMsg TOYOTA_SECOC_LONG_TX_MSGS[] = { + TOYOTA_COMMON_SECOC_LONG_TX_MSGS + }; + // safety param flags // first byte is for EPS factor, second is for flags const uint32_t TOYOTA_PARAM_OFFSET = 8U; diff --git a/opendbc/safety/modes/volkswagen_common.h b/opendbc/safety/modes/volkswagen_common.h index 7792c1eb..484f4851 100644 --- a/opendbc/safety/modes/volkswagen_common.h +++ b/opendbc/safety/modes/volkswagen_common.h @@ -14,6 +14,10 @@ bool volkswagen_set_button_prev = false; extern bool volkswagen_resume_button_prev; bool volkswagen_resume_button_prev = false; +extern bool volkswagen_brake_pedal_switch; +extern bool volkswagen_brake_pressure_detected; +bool volkswagen_brake_pedal_switch = false; +bool volkswagen_brake_pressure_detected = false; #define MSG_LH_EPS_03 0x09FU // RX from EPS, for driver steering torque #define MSG_ESP_19 0x0B2U // RX from ABS, for wheel speeds @@ -28,6 +32,21 @@ bool volkswagen_resume_button_prev = false; #define MSG_LDW_02 0x397U // TX by OP, Lane line recognition and text alerts #define MSG_MOTOR_14 0x3BEU // RX from ECU, for brake switch status +// MLB only messages +#define MSG_ESP_03 0x103U // RX from ABS, for wheel speeds +#define MSG_LS_01 0x10BU // TX by OP, ACC control buttons for cancel/resume +#define MSG_MOTOR_03 0x105U // RX from ECU, for driver throttle input and brake switch status +#define MSG_TSK_02 0x10CU // RX from ECU, for ACC status from drivetrain coordinator +#define MSG_ACC_05 0x10DU // RX from radar, for ACC status + +static void volkswagen_common_init(void) { + volkswagen_set_button_prev = false; + volkswagen_resume_button_prev = false; + volkswagen_brake_pedal_switch = false; + volkswagen_brake_pressure_detected = false; + gen_crc_lookup_table_8(0x2F, volkswagen_crc8_lut_8h2f); + return; +} static uint32_t volkswagen_mqb_meb_get_checksum(const CANPacket_t *msg) { return (uint8_t)msg->data[0]; @@ -68,3 +87,25 @@ static uint32_t volkswagen_mqb_meb_compute_crc(const CANPacket_t *msg) { return (uint8_t)(crc ^ 0xFFU); } + +static int volkswagen_mlb_mqb_driver_input_torque(const CANPacket_t *msg) { + // Signal: LH_EPS_03.EPS_Lenkmoment (absolute torque) + // Signal: LH_EPS_03.EPS_VZ_Lenkmoment (direction) + int torque_driver_new = msg->data[5] | ((msg->data[6] & 0x1FU) << 8); + bool sign = GET_BIT(msg, 55U); + if (sign) { + torque_driver_new *= -1; + } + return torque_driver_new; +} + +static int volkswagen_mlb_mqb_steering_control_torque(const CANPacket_t *msg) { + // Signal: HCA_01.HCA_01_LM_Offset (absolute torque) + // Signal: HCA_01.HCA_01_LM_OffSign (direction) + int desired_torque = msg->data[2] | ((msg->data[3] & 0x1U) << 8); + bool sign = GET_BIT(msg, 31U); + if (sign) { + desired_torque *= -1; + } + return desired_torque; +} diff --git a/opendbc/safety/modes/volkswagen_mlb.h b/opendbc/safety/modes/volkswagen_mlb.h new file mode 100644 index 00000000..6469da6d --- /dev/null +++ b/opendbc/safety/modes/volkswagen_mlb.h @@ -0,0 +1,134 @@ +#pragma once + +#include "opendbc/safety/declarations.h" +#include "opendbc/safety/modes/volkswagen_common.h" + + +static safety_config volkswagen_mlb_init(uint16_t param) { + // Transmit of LS_01 is allowed on bus 0 and 2 to keep compatibility with gateway and camera integration + static const CanMsg VOLKSWAGEN_MLB_STOCK_TX_MSGS[] = {{MSG_HCA_01, 0, 8, .check_relay = true}, {MSG_LDW_02, 0, 8, .check_relay = true}, + {MSG_LS_01, 0, 4, .check_relay = false}, {MSG_LS_01, 2, 4, .check_relay = false}}; + + static RxCheck volkswagen_mlb_rx_checks[] = { + // TODO: implement checksum validation + {.msg = {{MSG_ESP_03, 0, 8, 50U, .ignore_checksum = true, .max_counter = 15U, .ignore_quality_flag = true}, { 0 }, { 0 }}}, + {.msg = {{MSG_LH_EPS_03, 0, 8, 100U, .ignore_checksum = true, .max_counter = 15U, .ignore_quality_flag = true}, { 0 }, { 0 }}}, + {.msg = {{MSG_ESP_05, 0, 8, 50U, .ignore_checksum = true, .max_counter = 15U, .ignore_quality_flag = true}, { 0 }, { 0 }}}, + {.msg = {{MSG_ACC_05, 2, 8, 50U, .ignore_checksum = true, .max_counter = 15U, .ignore_quality_flag = true}, { 0 }, { 0 }}}, + {.msg = {{MSG_MOTOR_03, 0, 8, 100U, .ignore_checksum = true, .max_counter = 15U, .ignore_quality_flag = true}, { 0 }, { 0 }}}, + {.msg = {{MSG_LS_01, 0, 4, 10U, .ignore_checksum = true, .max_counter = 15U, .ignore_quality_flag = true}, { 0 }, { 0 }}}, + }; + + SAFETY_UNUSED(param); + volkswagen_common_init(); + + return BUILD_SAFETY_CFG(volkswagen_mlb_rx_checks, VOLKSWAGEN_MLB_STOCK_TX_MSGS); +} + +static void volkswagen_mlb_rx_hook(const CANPacket_t *msg) { + if (msg->bus == 0U) { + // Check all wheel speeds for any movement + // Signals: ESP_03.ESP_[VL|VR|HL|HR]_Radgeschw + if (msg->addr == MSG_ESP_03) { + uint32_t speed = 0; + speed += ((msg->data[3] & 0xFU) << 8) | msg->data[2]; // FL + speed += (msg->data[4] << 4) | (msg->data[3] >> 4); // FR + speed += ((msg->data[6] & 0xFU) << 8) | msg->data[5]; // RL + speed += (msg->data[7] << 4) | (msg->data[6] >> 4); // RR + vehicle_moving = speed > 0U; + } + + // Update driver input torque + if (msg->addr == MSG_LH_EPS_03) { + update_sample(&torque_driver, volkswagen_mlb_mqb_driver_input_torque(msg)); + } + + if (msg->addr == MSG_LS_01) { + // Always exit controls on rising edge of Cancel + // Signal: LS_01.LS_Abbrechen + if (GET_BIT(msg, 13U)) { + controls_allowed = false; + } + } + + // Signal: Motor_03.MO_Fahrpedalrohwert_01 + // Signal: Motor_03.MO_Fahrer_bremst + if (msg->addr == MSG_MOTOR_03) { + gas_pressed = msg->data[6] != 0U; + volkswagen_brake_pedal_switch = GET_BIT(msg, 35U); + } + + if (msg->addr == MSG_ESP_05) { + volkswagen_brake_pressure_detected = GET_BIT(msg, 26U); + } + + brake_pressed = volkswagen_brake_pedal_switch || volkswagen_brake_pressure_detected; + + } + + if (msg->bus == 2U) { + // TODO: See if there's a bus-agnostic TSK message we can use instead + if (msg->addr == MSG_ACC_05) { + // When using stock ACC, enter controls on rising edge of stock ACC engage, exit on disengage + // Always exit controls on main switch off + // Signal: ACC_05.ACC_Status_ACC + int acc_status = (msg->data[7] & 0xEU) >> 1; + bool cruise_engaged = (acc_status == 3) || (acc_status == 4) || (acc_status == 5); + acc_main_on = cruise_engaged || (acc_status == 2); + + pcm_cruise_check(cruise_engaged); + + if (!acc_main_on) { + controls_allowed = false; + } + } + } +} + +static bool volkswagen_mlb_tx_hook(const CANPacket_t *msg) { + // lateral limits + const TorqueSteeringLimits VOLKSWAGEN_MLB_STEERING_LIMITS = { + .max_torque = 300, // 3.0 Nm (EPS side max of 3.0Nm with fault if violated) + .max_rt_delta = 169, // 10 max rate up * 50Hz send rate * 250000 RT interval / 1000000 = 112.5 ; 112.5 * 1.5 for safety pad = 168.75 + .max_rate_up = 9, // 5.0 Nm/s RoC limit (EPS rack has own soft-limit of 5.0 Nm/s) + .max_rate_down = 10, // 5.0 Nm/s RoC limit (EPS rack has own soft-limit of 5.0 Nm/s) + .driver_torque_allowance = 60, + .driver_torque_multiplier = 3, + .type = TorqueDriverLimited, + }; + + bool tx = true; + + // Safety check for HCA_01 Heading Control Assist torque + if (msg->addr == MSG_HCA_01) { + int desired_torque = volkswagen_mlb_mqb_steering_control_torque(msg); + + int steer_status = msg->data[4] & 0xFU; + bool steer_req = (steer_status == 5) || (steer_status == 7); + + if (steer_torque_cmd_checks(desired_torque, steer_req, VOLKSWAGEN_MLB_STEERING_LIMITS)) { + tx = false; + } + } + + // FORCE CANCEL: ensuring that only the cancel button press is sent when controls are off. + // This avoids unintended engagements while still allowing resume spam + if ((msg->addr == MSG_LS_01) && !controls_allowed) { + // disallow resume and set: bits 16 and 19 + if (GET_BIT(msg, 16U) || GET_BIT(msg, 19U)) { + tx = false; + } + } + + return tx; +} + +// TODO: rename these functions to MXB or something +const safety_hooks volkswagen_mlb_hooks = { + .init = volkswagen_mlb_init, + .rx = volkswagen_mlb_rx_hook, + .tx = volkswagen_mlb_tx_hook, + .get_counter = volkswagen_mqb_meb_get_counter, + .get_checksum = volkswagen_mqb_meb_get_checksum, + .compute_checksum = volkswagen_mqb_meb_compute_crc, +}; diff --git a/opendbc/safety/modes/volkswagen_mqb.h b/opendbc/safety/modes/volkswagen_mqb.h index 8b34503a..bf727464 100644 --- a/opendbc/safety/modes/volkswagen_mqb.h +++ b/opendbc/safety/modes/volkswagen_mqb.h @@ -1,12 +1,8 @@ #pragma once -#include "opendbc/safety/safety_declarations.h" +#include "opendbc/safety/declarations.h" #include "opendbc/safety/modes/volkswagen_common.h" -static bool volkswagen_mqb_brake_pedal_switch = false; -static bool volkswagen_mqb_brake_pressure_detected = false; - - static safety_config volkswagen_mqb_init(uint16_t param) { // Transmit of GRA_ACC_01 is allowed on bus 0 and 2 to keep compatibility with gateway and camera integration // MSG_LH_EPS_03: openpilot needs to replace apparent driver steering input torque to pacify VW Emergency Assist @@ -26,17 +22,14 @@ static safety_config volkswagen_mqb_init(uint16_t param) { {.msg = {{MSG_GRA_ACC_01, 0, 8, 33U, .max_counter = 15U, .ignore_quality_flag = true}, { 0 }, { 0 }}}, }; - UNUSED(param); - - volkswagen_set_button_prev = false; - volkswagen_resume_button_prev = false; - volkswagen_mqb_brake_pedal_switch = false; - volkswagen_mqb_brake_pressure_detected = false; + volkswagen_common_init(); #ifdef ALLOW_DEBUG volkswagen_longitudinal = GET_FLAG(param, FLAG_VOLKSWAGEN_LONG_CONTROL); +#else + SAFETY_UNUSED(param); #endif - gen_crc_lookup_table_8(0x2F, volkswagen_crc8_lut_8h2f); + return volkswagen_longitudinal ? BUILD_SAFETY_CFG(volkswagen_mqb_rx_checks, VOLKSWAGEN_MQB_LONG_TX_MSGS) : \ BUILD_SAFETY_CFG(volkswagen_mqb_rx_checks, VOLKSWAGEN_MQB_STOCK_TX_MSGS); } @@ -59,12 +52,7 @@ static void volkswagen_mqb_rx_hook(const CANPacket_t *msg) { // Signal: LH_EPS_03.EPS_Lenkmoment (absolute torque) // Signal: LH_EPS_03.EPS_VZ_Lenkmoment (direction) if (msg->addr == MSG_LH_EPS_03) { - int torque_driver_new = msg->data[5] | ((msg->data[6] & 0x1FU) << 8); - int sign = (msg->data[6] & 0x80U) >> 7; - if (sign == 1) { - torque_driver_new *= -1; - } - update_sample(&torque_driver, torque_driver_new); + update_sample(&torque_driver, volkswagen_mlb_mqb_driver_input_torque(msg)); } if (msg->addr == MSG_TSK_06) { @@ -111,15 +99,15 @@ static void volkswagen_mqb_rx_hook(const CANPacket_t *msg) { // Signal: Motor_14.MO_Fahrer_bremst (ECU detected brake pedal switch F63) if (msg->addr == MSG_MOTOR_14) { - volkswagen_mqb_brake_pedal_switch = (msg->data[3] & 0x10U) >> 4; + volkswagen_brake_pedal_switch = GET_BIT(msg, 28U); } // Signal: ESP_05.ESP_Fahrer_bremst (ESP detected driver brake pressure above platform specified threshold) if (msg->addr == MSG_ESP_05) { - volkswagen_mqb_brake_pressure_detected = (msg->data[3] & 0x4U) >> 2; + volkswagen_brake_pressure_detected = GET_BIT(msg, 26U); } - brake_pressed = volkswagen_mqb_brake_pedal_switch || volkswagen_mqb_brake_pressure_detected; + brake_pressed = volkswagen_brake_pedal_switch || volkswagen_brake_pressure_detected; } } @@ -146,15 +134,8 @@ static bool volkswagen_mqb_tx_hook(const CANPacket_t *msg) { bool tx = true; // Safety check for HCA_01 Heading Control Assist torque - // Signal: HCA_01.HCA_01_LM_Offset (absolute torque) - // Signal: HCA_01.HCA_01_LM_OffSign (direction) if (msg->addr == MSG_HCA_01) { - int desired_torque = msg->data[2] | ((msg->data[3] & 0x1U) << 8); - bool sign = GET_BIT(msg, 31U); - if (sign) { - desired_torque *= -1; - } - + int desired_torque = volkswagen_mlb_mqb_steering_control_torque(msg); bool steer_req = GET_BIT(msg, 30U); if (steer_torque_cmd_checks(desired_torque, steer_req, VOLKSWAGEN_MQB_STEERING_LIMITS)) { diff --git a/opendbc/safety/modes/volkswagen_pq.h b/opendbc/safety/modes/volkswagen_pq.h index 6cdb6426..c3b2184b 100644 --- a/opendbc/safety/modes/volkswagen_pq.h +++ b/opendbc/safety/modes/volkswagen_pq.h @@ -1,6 +1,6 @@ #pragma once -#include "opendbc/safety/safety_declarations.h" +#include "opendbc/safety/declarations.h" #include "opendbc/safety/modes/volkswagen_common.h" #define MSG_LENKHILFE_3 0x0D0U // RX from EPS, for steering angle and driver steering torque @@ -63,13 +63,12 @@ static safety_config volkswagen_pq_init(uint16_t param) { {.msg = {{MSG_GRA_NEU, 0, 4, 30U, .max_counter = 15U, .ignore_quality_flag = true}, { 0 }, { 0 }}}, }; - UNUSED(param); - - volkswagen_set_button_prev = false; - volkswagen_resume_button_prev = false; + volkswagen_common_init(); #ifdef ALLOW_DEBUG volkswagen_longitudinal = GET_FLAG(param, FLAG_VOLKSWAGEN_LONG_CONTROL); +#else + SAFETY_UNUSED(param); #endif return volkswagen_longitudinal ? BUILD_SAFETY_CFG(volkswagen_pq_rx_checks, VOLKSWAGEN_PQ_LONG_TX_MSGS) : \ BUILD_SAFETY_CFG(volkswagen_pq_rx_checks, VOLKSWAGEN_PQ_STOCK_TX_MSGS); @@ -78,7 +77,7 @@ static safety_config volkswagen_pq_init(uint16_t param) { static void volkswagen_pq_rx_hook(const CANPacket_t *msg) { if (msg->bus == 0U) { // Update in-motion state from speed value. - // Signal: Bremse_1.Geschwindigkeit_neu__Bremse_1_ + // Signal: Bremse_1.BR1_Rad_kmh if (msg->addr == MSG_BREMSE_1) { int speed = ((msg->data[2] & 0xFEU) >> 1) | (msg->data[3] << 7); vehicle_moving = speed > 0; @@ -99,7 +98,7 @@ static void volkswagen_pq_rx_hook(const CANPacket_t *msg) { if (volkswagen_longitudinal) { if (msg->addr == MSG_MOTOR_5) { // ACC main switch on is a prerequisite to enter controls, exit controls immediately on main switch off - // Signal: Motor_5.GRA_Hauptschalter + // Signal: Motor_5.MO5_GRA_Hauptsch acc_main_on = GET_BIT(msg, 50U); if (!acc_main_on) { controls_allowed = false; @@ -126,19 +125,19 @@ static void volkswagen_pq_rx_hook(const CANPacket_t *msg) { } else { if (msg->addr == MSG_MOTOR_2) { // Enter controls on rising edge of stock ACC, exit controls if stock ACC disengages - // Signal: Motor_2.GRA_Status + // Signal: Motor_2.MO2_Sta_GRA int acc_status = (msg->data[2] & 0xC0U) >> 6; bool cruise_engaged = (acc_status == 1) || (acc_status == 2); pcm_cruise_check(cruise_engaged); } } - // Signal: Motor_3.Fahrpedal_Rohsignal + // Signal: Motor_3.MO3_Pedalwert if (msg->addr == MSG_MOTOR_3) { gas_pressed = (msg->data[2]); } - // Signal: Motor_2.Bremslichtschalter + // Signal: Motor_2.MO2_BLS if (msg->addr == MSG_MOTOR_2) { brake_pressed = (msg->data[2] & 0x1U); } diff --git a/opendbc/safety/safety.h b/opendbc/safety/safety.h index 8fae5fe0..fee40d4d 100644 --- a/opendbc/safety/safety.h +++ b/opendbc/safety/safety.h @@ -3,8 +3,8 @@ #include "opendbc/safety/helpers.h" #include "opendbc/safety/lateral.h" #include "opendbc/safety/longitudinal.h" -#include "opendbc/safety/safety_declarations.h" -#include "opendbc/safety/board/can.h" +#include "opendbc/safety/declarations.h" +#include "opendbc/safety/can.h" // all the safety modes #include "opendbc/safety/modes/defaults.h" @@ -20,6 +20,7 @@ #include "opendbc/safety/modes/subaru_preglobal.h" #include "opendbc/safety/modes/mazda.h" #include "opendbc/safety/modes/nissan.h" +#include "opendbc/safety/modes/volkswagen_mlb.h" #include "opendbc/safety/modes/volkswagen_mqb.h" #include "opendbc/safety/modes/volkswagen_pq.h" #include "opendbc/safety/modes/elm327.h" @@ -145,7 +146,7 @@ static void update_counter(RxCheck addr_list[], int index, uint8_t counter) { if (index != -1) { uint8_t expected_counter = (addr_list[index].status.last_counter + 1U) % (addr_list[index].msg[addr_list[index].status.index].max_counter + 1U); addr_list[index].status.wrong_counters += (expected_counter == counter) ? -1 : 1; - addr_list[index].status.wrong_counters = CLAMP(addr_list[index].status.wrong_counters, 0, MAX_WRONG_COUNTERS); + addr_list[index].status.wrong_counters = SAFETY_CLAMP(addr_list[index].status.wrong_counters, 0, MAX_WRONG_COUNTERS); addr_list[index].status.last_counter = counter; } } @@ -316,12 +317,12 @@ void safety_tick(const safety_config *cfg) { uint32_t ts = microsecond_timer_get(); if (cfg != NULL) { for (int i=0; i < cfg->rx_checks_len; i++) { - uint32_t elapsed_time = get_ts_elapsed(ts, cfg->rx_checks[i].status.last_timestamp); + uint32_t elapsed_time = safety_get_ts_elapsed(ts, cfg->rx_checks[i].status.last_timestamp); // lag threshold is max of: 1s and MAX_MISSED_MSGS * expected timestep. // Quite conservative to not risk false triggers. // 2s of lag is worse case, since the function is called at 1Hz uint32_t timestep = 1e6 / cfg->rx_checks[i].msg[cfg->rx_checks[i].status.index].frequency; - bool lagging = elapsed_time > MAX(timestep * MAX_MISSED_MSGS, 1e6); + bool lagging = elapsed_time > SAFETY_MAX(timestep * MAX_MISSED_MSGS, 1e6); cfg->rx_checks[i].status.lagging = lagging; if (lagging) { controls_allowed = false; @@ -339,7 +340,6 @@ void safety_tick(const safety_config *cfg) { static void relay_malfunction_set(void) { relay_malfunction = true; - fault_occurred(FAULT_RELAY_MALFUNCTION); } static void generic_rx_checks(void) { @@ -377,7 +377,6 @@ static void stock_ecu_check(bool stock_ecu_detected) { static void relay_malfunction_reset(void) { relay_malfunction = false; - fault_recovered(FAULT_RELAY_MALFUNCTION); } // resets values and min/max for sample_t struct @@ -412,6 +411,7 @@ int set_safety_hooks(uint16_t mode, uint16_t param) { #ifdef ALLOW_DEBUG {SAFETY_PSA, &psa_hooks}, {SAFETY_SUBARU_PREGLOBAL, &subaru_preglobal_hooks}, + {SAFETY_VOLKSWAGEN_MLB, &volkswagen_mlb_hooks}, {SAFETY_VOLKSWAGEN_PQ, &volkswagen_pq_hooks}, {SAFETY_ALLOUTPUT, &alloutput_hooks}, #endif @@ -490,9 +490,9 @@ int set_safety_hooks(uint16_t mode, uint16_t param) { // convert a trimmed integer to signed 32 bit int int to_signed(int d, int bits) { int d_signed = d; - int max_value = (1 << MAX((bits - 1), 0)); + int max_value = (1 << SAFETY_MAX((bits - 1), 0)); if (d >= max_value) { - d_signed = d - (1 << MAX(bits, 0)); + d_signed = d - (1 << SAFETY_MAX(bits, 0)); } return d_signed; } @@ -536,7 +536,7 @@ void speed_mismatch_check(const float speed_2) { // Disable controls if speeds from two sources are too far apart. // For safety modes that use speed to adjust torque or angle limits const float MAX_SPEED_DELTA = 2.0; // m/s - bool is_invalid_speed = ABS(speed_2 - ((float)vehicle_speed.values[0] / VEHICLE_SPEED_FACTOR)) > MAX_SPEED_DELTA; + bool is_invalid_speed = SAFETY_ABS(speed_2 - ((float)vehicle_speed.values[0] / VEHICLE_SPEED_FACTOR)) > MAX_SPEED_DELTA; if (is_invalid_speed) { controls_allowed = false; } diff --git a/opendbc/safety/sunnypilot/safety_mads.h b/opendbc/safety/sunnypilot/mads.h similarity index 99% rename from opendbc/safety/sunnypilot/safety_mads.h rename to opendbc/safety/sunnypilot/mads.h index 6dd93cde..e5667bed 100644 --- a/opendbc/safety/sunnypilot/safety_mads.h +++ b/opendbc/safety/sunnypilot/mads.h @@ -7,7 +7,7 @@ #pragma once -#include "opendbc/safety/sunnypilot/safety_mads_declarations.h" +#include "opendbc/safety/sunnypilot/mads_declarations.h" // =============================== // Global Variables diff --git a/opendbc/safety/sunnypilot/safety_mads_declarations.h b/opendbc/safety/sunnypilot/mads_declarations.h similarity index 100% rename from opendbc/safety/sunnypilot/safety_mads_declarations.h rename to opendbc/safety/sunnypilot/mads_declarations.h diff --git a/opendbc/safety/tests/common.py b/opendbc/safety/tests/common.py index 56d375b3..ba7de0ce 100644 --- a/opendbc/safety/tests/common.py +++ b/opendbc/safety/tests/common.py @@ -42,8 +42,8 @@ def make_msg(bus, addr, length=8, dat=None): return libsafety_py.make_CANPacket(addr, bus, dat) -class CANPackerPanda(CANPacker): - def make_can_msg_panda(self, name_or_addr, bus, values, fix_checksum=None): +class CANPackerSafety(CANPacker): + def make_can_msg_safety(self, name_or_addr, bus, values, fix_checksum=None): msg = self.make_can_msg(name_or_addr, bus, values) if fix_checksum is not None: msg = fix_checksum(msg) @@ -73,12 +73,12 @@ def add_regen_tests(cls): return cls -class PandaSafetyTestBase(unittest.TestCase): - safety: libsafety_py.Panda +class SafetyTestBase(unittest.TestCase): + safety: libsafety_py.LibSafety @classmethod def setUpClass(cls): - if cls.__name__ == "PandaSafetyTestBase": + if cls.__name__ == "SafetyTestBase": cls.safety = None raise unittest.SkipTest @@ -135,7 +135,7 @@ class PandaSafetyTestBase(unittest.TestCase): self.assertEqual(meas_max_func(), 0) -class LongitudinalAccelSafetyTest(PandaSafetyTestBase, abc.ABC): +class LongitudinalAccelSafetyTest(SafetyTestBase, abc.ABC): LONGITUDINAL = True MAX_ACCEL: float = 2.0 @@ -175,7 +175,7 @@ class LongitudinalAccelSafetyTest(PandaSafetyTestBase, abc.ABC): self.assertEqual(should_tx, self._tx(self._accel_msg(accel))) -class LongitudinalGasBrakeSafetyTest(PandaSafetyTestBase, abc.ABC): +class LongitudinalGasBrakeSafetyTest(SafetyTestBase, abc.ABC): MIN_BRAKE: int = 0 MAX_BRAKE: int | None = None @@ -209,7 +209,7 @@ class LongitudinalGasBrakeSafetyTest(PandaSafetyTestBase, abc.ABC): self._generic_limit_safety_check(self._send_gas_msg, self.MIN_GAS, self.MAX_GAS, self.MIN_POSSIBLE_GAS, self.MAX_POSSIBLE_GAS, 1, self.INACTIVE_GAS) -class TorqueSteeringSafetyTestBase(PandaSafetyTestBase, abc.ABC): +class TorqueSteeringSafetyTestBase(SafetyTestBase, abc.ABC): MAX_RATE_UP = 0 MAX_RATE_DOWN = 0 @@ -642,7 +642,7 @@ class MotorTorqueSteeringSafetyTest(TorqueSteeringSafetyTestBase, abc.ABC): self.assertEqual(self.safety.get_torque_meas_max(), 0) -class VehicleSpeedSafetyTest(PandaSafetyTestBase): +class VehicleSpeedSafetyTest(SafetyTestBase): @classmethod def setUpClass(cls): if cls.__name__ == "VehicleSpeedSafetyTest": @@ -809,7 +809,7 @@ class AngleSteeringSafetyTest(VehicleSpeedSafetyTest): self.assertTrue(self._tx(self._angle_cmd_msg(0, True, increment_timer=False))) -class PandaSafetyTest(PandaSafetyTestBase): +class SafetyTest(SafetyTestBase): TX_MSGS: list[list[int]] | None = None SCANNED_ADDRS = [*range(0x800), # Entire 11-bit CAN address space *range(0x18DA00F1, 0x18DB00F1, 0x100), # 29-bit UDS physical addressing @@ -820,7 +820,7 @@ class PandaSafetyTest(PandaSafetyTestBase): @classmethod def setUpClass(cls): - if cls.__name__ == "PandaSafetyTest" or cls.__name__.endswith('Base'): + if cls.__name__ == "SafetyTest" or cls.__name__.endswith('Base'): cls.safety = None raise unittest.SkipTest @@ -897,13 +897,12 @@ class PandaSafetyTest(PandaSafetyTestBase): continue if {attr, current_test}.issubset({'TestHyundaiLongitudinalSafety', 'TestHyundaiLongitudinalSafetyCameraSCC', 'TestHyundaiSafetyFCEVLong'}): continue - base_tests = {'TestHyundaiLongitudinalSafety', 'TestHyundaiLongitudinalSafetyCameraSCC', 'TestHyundaiSafetyFCEVLong', 'TestHyundaiLongitudinalESCCSafety'} if any(attr.startswith(test) for test in base_tests) and any(current_test.startswith(test) for test in base_tests): continue - - if {attr, current_test}.issubset({'TestVolkswagenMqbSafety', 'TestVolkswagenMqbStockSafety', 'TestVolkswagenMqbLongSafety'}): + volkswagen_shared = ('TestVolkswagenMqb', 'TestVolkswagenMlb') + if attr.startswith(volkswagen_shared) and current_test.startswith(volkswagen_shared): continue # overlapping TX addrs, but they're not actuating messages for either car @@ -946,14 +945,14 @@ class PandaSafetyTest(PandaSafetyTestBase): @add_regen_tests -class PandaCarSafetyTest(PandaSafetyTest, MadsSafetyTestBase): +class CarSafetyTest(SafetyTest, MadsSafetyTestBase): STANDSTILL_THRESHOLD: float = 0.0 GAS_PRESSED_THRESHOLD = 0 RELAY_MALFUNCTION_ADDRS: dict[int, tuple[int, ...]] | None = None @classmethod def setUpClass(cls): - if cls.__name__ == "PandaCarSafetyTest" or cls.__name__.endswith('Base'): + if cls.__name__ == "CarSafetyTest" or cls.__name__.endswith('Base'): cls.safety = None raise unittest.SkipTest diff --git a/opendbc/safety/tests/gas_interceptor_common.py b/opendbc/safety/tests/gas_interceptor_common.py index 811d3e06..16ed465c 100644 --- a/opendbc/safety/tests/gas_interceptor_common.py +++ b/opendbc/safety/tests/gas_interceptor_common.py @@ -8,17 +8,17 @@ See the LICENSE.md file in the root directory for more details. import numpy as np import unittest -from opendbc.safety.tests.common import CANPackerPanda, PandaSafetyTestBase +from opendbc.safety.tests.common import CANPackerSafety, CarSafetyTest -class GasInterceptorSafetyTest(PandaSafetyTestBase): +class GasInterceptorSafetyTest(CarSafetyTest): INTERCEPTOR_THRESHOLD = 0 cnt_gas_cmd = 0 cnt_user_gas = 0 - packer: CANPackerPanda + packer: CANPackerSafety @classmethod def setUpClass(cls): @@ -32,13 +32,13 @@ class GasInterceptorSafetyTest(PandaSafetyTestBase): values["GAS_COMMAND"] = gas * 255. values["GAS_COMMAND2"] = gas * 255. self.__class__.cnt_gas_cmd += 1 - return self.packer.make_can_msg_panda("GAS_COMMAND", 0, values) + return self.packer.make_can_msg_safety("GAS_COMMAND", 0, values) def _interceptor_user_gas(self, gas: int): values = {"INTERCEPTOR_GAS": gas, "INTERCEPTOR_GAS2": gas, "PEDAL_COUNTER": self.__class__.cnt_user_gas} self.__class__.cnt_user_gas += 1 - return self.packer.make_can_msg_panda("GAS_SENSOR", 0, values) + return self.packer.make_can_msg_safety("GAS_SENSOR", 0, values) # Skip non-interceptor user gas tests def test_prev_gas(self): diff --git a/opendbc/safety/tests/hyundai_common.py b/opendbc/safety/tests/hyundai_common.py index cbce8c3e..a7724b6c 100644 --- a/opendbc/safety/tests/hyundai_common.py +++ b/opendbc/safety/tests/hyundai_common.py @@ -84,7 +84,7 @@ class HyundaiLongitudinalBase(common.LongitudinalAccelSafetyTest): cls.safety = None raise unittest.SkipTest - # override these tests from PandaCarSafetyTest, hyundai longitudinal uses button enable + # override these tests from CarSafetyTest, hyundai longitudinal uses button enable def test_disable_control_allowed_from_cruise(self): pass diff --git a/opendbc/safety/tests/install_mull.sh b/opendbc/safety/tests/install_mull.sh deleted file mode 100755 index 75b1042e..00000000 --- a/opendbc/safety/tests/install_mull.sh +++ /dev/null @@ -1,11 +0,0 @@ -#!/usr/bin/env bash -set -e - -DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" -cd $DIR - -if ! command -v "mull-runner-17" > /dev/null 2>&1; then - sudo apt-get update && sudo apt-get install -y curl clang-17 - curl -1sLf 'https://dl.cloudsmith.io/public/mull-project/mull-stable/setup.deb.sh' | sudo -E bash - sudo apt-get update && sudo apt-get install -y mull-17 -fi diff --git a/opendbc/safety/tests/libsafety/SConscript b/opendbc/safety/tests/libsafety/SConscript index c02a703a..7cab268a 100644 --- a/opendbc/safety/tests/libsafety/SConscript +++ b/opendbc/safety/tests/libsafety/SConscript @@ -11,6 +11,7 @@ mac_ver = platform.mac_ver() if system == 'Darwin' and mac_ver[0] and mac_ver[0] < '15': CC += '-13' +# standard env env = Environment( CC=CC, CFLAGS=[ @@ -24,46 +25,45 @@ env = Environment( '-Wno-pointer-to-int-cast', '-g', '-O0', - "-fno-omit-frame-pointer" + '-fno-omit-frame-pointer', + '-fprofile-arcs', + '-ftest-coverage', + '-DALLOW_DEBUG', + ], + LINKFLAGS=[ + '-fprofile-arcs', + '-ftest-coverage', ], CPPPATH=["#", "../../board/"], tools=["default", "compilation_db"], ) if system == "Darwin": env.PrependENVPath('PATH', '/opt/homebrew/bin') - -if GetOption('mutation'): - env['CC'] = 'clang-17' - flags = [ - '-fprofile-instr-generate', - '-fcoverage-mapping', - '-fpass-plugin=/usr/lib/mull-ir-frontend-17', - '-g', - '-grecord-command-line', - ] - env['CFLAGS'] += flags - env['LINKFLAGS'] += flags - if GetOption('ubsan'): - flags = [ + env.Prepend(LINKFLAGS=[ "-fsanitize=undefined", "-fno-sanitize-recover=undefined", - ] - env['CFLAGS'] += flags - env['LINKFLAGS'] += flags + ]) -safety = env.SharedObject("safety.os", "safety.c") -libsafety = env.SharedLibrary("libsafety.so", [safety]) - -coverage_flags = [ - # GCC coverage flags - '-fprofile-arcs', - '-ftest-coverage', +# mutation env +menv = env.Clone() +menv['CC'] = 'clang-17' +flags = [ + '-fprofile-instr-generate', + '-fcoverage-mapping', + '-fpass-plugin=/usr/lib/mull-ir-frontend-17', + '-g', + '-grecord-command-line', ] -env.Append( - CFLAGS=coverage_flags, - LINKFLAGS=coverage_flags, -) +menv['CFLAGS'] += flags +menv['LINKFLAGS'] += flags -# GCC note file is generated by compiler, allow scons to clean it up -env.SideEffect("safety.gcno", safety) +for build_env, suffix in ((env, ""), (menv, "_mutation")): + # TODO: add macOS support + if (build_env == menv) and (system == "Darwin"): + continue + safety = env.SharedObject(f"safety{suffix}.os", "safety.c") + libsafety = env.SharedLibrary(f"libsafety{suffix}.so", [safety]) + + # GCC note file is generated by compiler, allow scons to clean it up + env.SideEffect("safety.gcno", safety) diff --git a/opendbc/safety/tests/libsafety/fake_stm.h b/opendbc/safety/tests/libsafety/fake_stm.h new file mode 100644 index 00000000..11948430 --- /dev/null +++ b/opendbc/safety/tests/libsafety/fake_stm.h @@ -0,0 +1,12 @@ +#include +#include +#include + +#define ALLOW_DEBUG + +// TODO: time should just be passed into the hooks we expose +uint32_t timer_cnt = 0; +uint32_t microsecond_timer_get(void); +uint32_t microsecond_timer_get(void) { + return timer_cnt; +} diff --git a/opendbc/safety/tests/libsafety/libsafety_py.py b/opendbc/safety/tests/libsafety/libsafety_py.py index bae99fc0..eef29c45 100644 --- a/opendbc/safety/tests/libsafety/libsafety_py.py +++ b/opendbc/safety/tests/libsafety/libsafety_py.py @@ -1,12 +1,10 @@ import os from cffi import FFI -from typing import Protocol from opendbc.safety import LEN_TO_DLC -from opendbc.safety.tests.libsafety.safety_helpers import PandaSafety, setup_safety_helpers libsafety_dir = os.path.dirname(os.path.abspath(__file__)) -libsafety_fn = os.path.join(libsafety_dir, "libsafety.so") +libsafety_fn = os.path.join(libsafety_dir, "libsafety_mutation.so" if "MUTATION" in os.environ else "libsafety.so") ffi = FFI() @@ -23,47 +21,91 @@ typedef struct { unsigned char data[64]; } CANPacket_t; """, packed=True) +class CANPacket: + pass ffi.cdef(""" bool safety_rx_hook(CANPacket_t *msg); bool safety_tx_hook(CANPacket_t *msg); int safety_fwd_hook(int bus_num, int addr); int set_safety_hooks(uint16_t mode, uint16_t param); + +void set_controls_allowed(bool c); +bool get_controls_allowed(void); +bool get_longitudinal_allowed(void); +void set_alternative_experience(int mode); +int get_alternative_experience(void); +void set_relay_malfunction(bool c); +bool get_relay_malfunction(void); +bool get_gas_pressed_prev(void); +void set_gas_pressed_prev(bool); +bool get_brake_pressed_prev(void); +bool get_regen_braking_prev(void); +bool get_steering_disengage_prev(void); +bool get_acc_main_on(void); +float get_vehicle_speed_min(void); +float get_vehicle_speed_max(void); +int get_current_safety_mode(void); +int get_current_safety_param(void); + +void set_torque_meas(int min, int max); +int get_torque_meas_min(void); +int get_torque_meas_max(void); +void set_torque_driver(int min, int max); +int get_torque_driver_min(void); +int get_torque_driver_max(void); +void set_desired_torque_last(int t); +void set_rt_torque_last(int t); +void set_desired_angle_last(int t); +int get_desired_angle_last(); +void set_angle_meas(int min, int max); +int get_angle_meas_min(void); +int get_angle_meas_max(void); + +bool get_cruise_engaged_prev(void); +void set_cruise_engaged_prev(bool engaged); +bool get_vehicle_moving(void); +void set_timer(uint32_t t); + +void safety_tick_current_safety_config(); +bool safety_config_valid(); + +void init_tests(void); + +void set_honda_fwd_brake(bool c); +bool get_honda_fwd_brake(void); +void set_honda_alt_brake_msg(bool c); +void set_honda_bosch_long(bool c); +int get_honda_hw(void); + +bool get_lat_active(void); +bool get_controls_allowed_lat(void); +bool get_controls_requested_lat(void); +void set_current_safety_param_sp(int param); +int get_current_safety_param_sp(void); +bool get_enable_mads(void); +bool get_disengage_lateral_on_brake(void); +bool get_pause_lateral_on_brake(void); +void set_mads_button_press(int mads_button_press); +void set_controls_allowed_lat(bool c); +void set_controls_requested_lat(bool c); +bool get_mads_acc_main(void); +void set_acc_main_on(bool c); +int get_mads_button_press(void); +void mads_set_current_disengage_reason(int reason); +int mads_get_current_disengage_reason(void); +int get_temp_debug(void); +uint32_t get_acc_main_on_mismatches(void); +void set_mads_params(bool enable_mads, bool disengage_lateral_on_brake, bool pause_lateral_on_brake); +void set_heartbeat_engaged_mads(bool c); +void mads_heartbeat_engaged_check(void); +void set_steering_disengage(bool c); +int get_gas_interceptor_prev(void); """) -ffi.cdef(""" -void can_set_checksum(CANPacket_t *packet); -""") - -setup_safety_helpers(ffi) - - -class CANPacket: - reserved: int - bus: int - data_len_code: int - rejected: int - returned: int - extended: int - addr: int - data: list[int] - - -class Panda(PandaSafety, Protocol): - # CAN - def can_set_checksum(self, p: CANPacket) -> None: ... - - # safety - def safety_rx_hook(self, msg: CANPacket) -> int: ... - def safety_tx_hook(self, msg: CANPacket) -> int: ... - def safety_fwd_hook(self, bus_num: int, addr: int) -> int: ... - def set_safety_hooks(self, mode: int, param: int) -> int: ... - - -libsafety: Panda = ffi.dlopen(libsafety_fn) - - -# helpers +class LibSafety: + pass +libsafety: LibSafety = ffi.dlopen(libsafety_fn) def make_CANPacket(addr: int, bus: int, dat): ret = ffi.new('CANPacket_t *') @@ -72,6 +114,4 @@ def make_CANPacket(addr: int, bus: int, dat): ret[0].data_len_code = LEN_TO_DLC[len(dat)] ret[0].bus = bus ret[0].data = bytes(dat) - libsafety.can_set_checksum(ret) - return ret diff --git a/opendbc/safety/tests/libsafety/safety.c b/opendbc/safety/tests/libsafety/safety.c index c7501bf6..9183e4a6 100644 --- a/opendbc/safety/tests/libsafety/safety.c +++ b/opendbc/safety/tests/libsafety/safety.c @@ -1,13 +1,301 @@ -#include +#include +#include +#include -#include "opendbc/safety/board/fake_stm.h" -#include "opendbc/safety/board/can.h" +// TODO: time should just be passed into the hooks we expose +uint32_t timer_cnt = 0; +uint32_t microsecond_timer_get(void); +uint32_t microsecond_timer_get(void) { + return timer_cnt; +} -//int safety_tx_hook(CANPacket_t *msg) { return 1; } - -#include "opendbc/safety/board/faults.h" +#include "opendbc/safety/can.h" #include "opendbc/safety/safety.h" -#include "opendbc/safety/board/drivers/can_common.h" -// libsafety stuff -#include "opendbc/safety/tests/libsafety/safety_helpers.h" +void safety_tick_current_safety_config() { + safety_tick(¤t_safety_config); +} + +bool safety_config_valid() { + if (current_safety_config.rx_checks_len <= 0) { + printf("missing RX checks\n"); + return false; + } + + for (int i = 0; i < current_safety_config.rx_checks_len; i++) { + const RxCheck addr = current_safety_config.rx_checks[i]; + bool valid = addr.status.msg_seen && !addr.status.lagging && addr.status.valid_checksum && (addr.status.wrong_counters < MAX_WRONG_COUNTERS) && addr.status.valid_quality_flag; + if (!valid) { + // printf("i %d seen %d lagging %d valid checksum %d wrong counters %d valid quality flag %d\n", i, addr.status.msg_seen, addr.status.lagging, addr.status.valid_checksum, addr.status.wrong_counters, addr.status.valid_quality_flag); + return false; + } + } + return true; +} + +void set_controls_allowed(bool c){ + controls_allowed = c; +} + +void set_alternative_experience(int mode){ + alternative_experience = mode; +} + +void set_relay_malfunction(bool c){ + relay_malfunction = c; +} + +bool get_controls_allowed(void){ + return controls_allowed; +} + +int get_alternative_experience(void){ + return alternative_experience; +} + +bool get_relay_malfunction(void){ + return relay_malfunction; +} + +bool get_gas_pressed_prev(void){ + return gas_pressed_prev; +} + +void set_gas_pressed_prev(bool c){ + gas_pressed_prev = c; +} + +bool get_brake_pressed_prev(void){ + return brake_pressed_prev; +} + +bool get_regen_braking_prev(void){ + return regen_braking_prev; +} + +bool get_steering_disengage_prev(void){ + return steering_disengage_prev; +} + +bool get_cruise_engaged_prev(void){ + return cruise_engaged_prev; +} + +void set_cruise_engaged_prev(bool engaged){ + cruise_engaged_prev = engaged; +} + +bool get_vehicle_moving(void){ + return vehicle_moving; +} + +bool get_acc_main_on(void){ + return acc_main_on; +} + +float get_vehicle_speed_min(void){ + return vehicle_speed.min / VEHICLE_SPEED_FACTOR; +} + +float get_vehicle_speed_max(void){ + return vehicle_speed.max / VEHICLE_SPEED_FACTOR; +} + +int get_current_safety_mode(void){ + return current_safety_mode; +} + +int get_current_safety_param(void){ + return current_safety_param; +} + +void set_timer(uint32_t t){ + timer_cnt = t; +} + +void set_torque_meas(int min, int max){ + torque_meas.min = min; + torque_meas.max = max; +} + +int get_torque_meas_min(void){ + return torque_meas.min; +} + +int get_torque_meas_max(void){ + return torque_meas.max; +} + +void set_torque_driver(int min, int max){ + torque_driver.min = min; + torque_driver.max = max; +} + +int get_torque_driver_min(void){ + return torque_driver.min; +} + +int get_torque_driver_max(void){ + return torque_driver.max; +} + +void set_rt_torque_last(int t){ + rt_torque_last = t; +} + +void set_desired_torque_last(int t){ + desired_torque_last = t; +} + +void set_desired_angle_last(int t){ + desired_angle_last = t; +} + +int get_desired_angle_last(void){ + return desired_angle_last; +} + +void set_angle_meas(int min, int max){ + angle_meas.min = min; + angle_meas.max = max; +} + +int get_angle_meas_min(void){ + return angle_meas.min; +} + +int get_angle_meas_max(void){ + return angle_meas.max; +} + + +// ***** car specific helpers ***** + +void set_honda_alt_brake_msg(bool c){ + honda_alt_brake_msg = c; +} + +void set_honda_bosch_long(bool c){ + honda_bosch_long = c; +} + +int get_honda_hw(void) { + return honda_hw; +} + +void set_honda_fwd_brake(bool c){ + honda_fwd_brake = c; +} + +bool get_honda_fwd_brake(void){ + return honda_fwd_brake; +} + +static MADSState *get_mads_state(void) { + return &m_mads_state; +} + +bool get_lat_active(void){ + return is_lat_active(); +} + +bool get_controls_allowed_lat(void){ + return mads_is_lateral_control_allowed_by_mads(); +} + +bool get_controls_requested_lat(void){ + return get_mads_state()->controls_requested_lat; +} + +bool get_enable_mads(void){ + return get_mads_state()->system_enabled; +} + +bool get_disengage_lateral_on_brake(void){ + return get_mads_state()->disengage_lateral_on_brake; +} + +bool get_pause_lateral_on_brake(void){ + return get_mads_state()->pause_lateral_on_brake; +} + +void set_acc_main_on(bool c){ + acc_main_on = c; +} + +void set_current_safety_param_sp(int param){ + current_safety_param_sp = param; +} + +int get_current_safety_param_sp(void){ + return current_safety_param_sp; +} + +void set_mads_button_press(int c){ + mads_button_press = c; +} + +int get_mads_button_press(void){ + return mads_button_press; +} + +void set_controls_allowed_lat(bool c){ + m_mads_state.controls_allowed_lat = c; +} + +bool get_mads_acc_main(void){ + return m_mads_state.acc_main.current; +} + +int mads_get_current_disengage_reason(void) { + return get_mads_state()->current_disengage.active_reason; +} + +void mads_set_current_disengage_reason(int reason) { + m_mads_state.current_disengage.active_reason = reason; +} + +void set_controls_requested_lat(bool c){ + m_mads_state.controls_requested_lat = c; +} + +void set_mads_params(bool enable_mads, bool disengage_lateral_on_brake, bool pause_lateral_on_brake){ + alternative_experience = 0; + if (enable_mads) { + alternative_experience |= ALT_EXP_ENABLE_MADS; + + if (disengage_lateral_on_brake) { + alternative_experience |= ALT_EXP_MADS_DISENGAGE_LATERAL_ON_BRAKE; + } else if (pause_lateral_on_brake) { + alternative_experience |= ALT_EXP_MADS_PAUSE_LATERAL_ON_BRAKE; + } else { + } + } + + mads_set_alternative_experience(&alternative_experience); +} + +void set_heartbeat_engaged_mads(bool c){ + heartbeat_engaged_mads = c; +} + +void set_steering_disengage(bool c){ + steering_disengage = c; +} + +int get_gas_interceptor_prev(void){ + return gas_interceptor_prev; +} + +void init_tests(void){ + safety_mode_cnt = 2U; // avoid ignoring relay_malfunction logic + alternative_experience = 0; + current_safety_param_sp = 0; + set_timer(0); + ts_steer_req_mismatch_last = 0; + valid_steer_req_count = 0; + invalid_steer_req_count = 0; + + // assumes autopark on safety mode init to avoid a fault. get rid of that for testing + tesla_autopark = false; +} diff --git a/opendbc/safety/tests/libsafety/safety_helpers.h b/opendbc/safety/tests/libsafety/safety_helpers.h deleted file mode 100644 index 06366756..00000000 --- a/opendbc/safety/tests/libsafety/safety_helpers.h +++ /dev/null @@ -1,294 +0,0 @@ -#include - -void safety_tick_current_safety_config() { - safety_tick(¤t_safety_config); -} - -bool safety_config_valid() { - if (current_safety_config.rx_checks_len <= 0) { - printf("missing RX checks\n"); - return false; - } - - for (int i = 0; i < current_safety_config.rx_checks_len; i++) { - const RxCheck addr = current_safety_config.rx_checks[i]; - bool valid = addr.status.msg_seen && !addr.status.lagging && addr.status.valid_checksum && (addr.status.wrong_counters < MAX_WRONG_COUNTERS) && addr.status.valid_quality_flag; - if (!valid) { - // printf("i %d seen %d lagging %d valid checksum %d wrong counters %d valid quality flag %d\n", i, addr.status.msg_seen, addr.status.lagging, addr.status.valid_checksum, addr.status.wrong_counters, addr.status.valid_quality_flag); - return false; - } - } - return true; -} - - -static MADSState *get_mads_state(void) { - return &m_mads_state; -} - -void set_controls_allowed(bool c){ - controls_allowed = c; -} - -void set_alternative_experience(int mode){ - alternative_experience = mode; -} - -void set_relay_malfunction(bool c){ - relay_malfunction = c; -} - -bool get_controls_allowed(void){ - return controls_allowed; -} - -bool get_lat_active(void){ - return is_lat_active(); -} - -bool get_controls_allowed_lat(void){ - return mads_is_lateral_control_allowed_by_mads(); -} - -bool get_controls_requested_lat(void){ - return get_mads_state()->controls_requested_lat; -} - -bool get_enable_mads(void){ - return get_mads_state()->system_enabled; -} - -bool get_disengage_lateral_on_brake(void){ - return get_mads_state()->disengage_lateral_on_brake; -} - -bool get_pause_lateral_on_brake(void){ - return get_mads_state()->pause_lateral_on_brake; -} - -int get_alternative_experience(void){ - return alternative_experience; -} - -bool get_relay_malfunction(void){ - return relay_malfunction; -} - -bool get_gas_pressed_prev(void){ - return gas_pressed_prev; -} - -void set_gas_pressed_prev(bool c){ - gas_pressed_prev = c; -} - -bool get_brake_pressed_prev(void){ - return brake_pressed_prev; -} - -bool get_regen_braking_prev(void){ - return regen_braking_prev; -} - -bool get_steering_disengage_prev(void){ - return steering_disengage_prev; -} - -bool get_cruise_engaged_prev(void){ - return cruise_engaged_prev; -} - -void set_cruise_engaged_prev(bool engaged){ - cruise_engaged_prev = engaged; -} - -bool get_vehicle_moving(void){ - return vehicle_moving; -} - -bool get_acc_main_on(void){ - return acc_main_on; -} - -float get_vehicle_speed_min(void){ - return vehicle_speed.min / VEHICLE_SPEED_FACTOR; -} - -float get_vehicle_speed_max(void){ - return vehicle_speed.max / VEHICLE_SPEED_FACTOR; -} - -void set_acc_main_on(bool c){ - acc_main_on = c; -} - -int get_current_safety_mode(void){ - return current_safety_mode; -} - -int get_current_safety_param(void){ - return current_safety_param; -} - -void set_current_safety_param_sp(int param){ - current_safety_param_sp = param; -} - -int get_current_safety_param_sp(void){ - return current_safety_param_sp; -} - -void set_timer(uint32_t t){ - timer.CNT = t; -} - -void set_torque_meas(int min, int max){ - torque_meas.min = min; - torque_meas.max = max; -} - -int get_torque_meas_min(void){ - return torque_meas.min; -} - -int get_torque_meas_max(void){ - return torque_meas.max; -} - -void set_torque_driver(int min, int max){ - torque_driver.min = min; - torque_driver.max = max; -} - -int get_torque_driver_min(void){ - return torque_driver.min; -} - -int get_torque_driver_max(void){ - return torque_driver.max; -} - -void set_rt_torque_last(int t){ - rt_torque_last = t; -} - -void set_desired_torque_last(int t){ - desired_torque_last = t; -} - -void set_desired_angle_last(int t){ - desired_angle_last = t; -} - -int get_desired_angle_last(void){ - return desired_angle_last; -} - -void set_angle_meas(int min, int max){ - angle_meas.min = min; - angle_meas.max = max; -} - -int get_angle_meas_min(void){ - return angle_meas.min; -} - -int get_angle_meas_max(void){ - return angle_meas.max; -} - - -// ***** car specific helpers ***** - -void set_honda_alt_brake_msg(bool c){ - honda_alt_brake_msg = c; -} - -void set_honda_bosch_long(bool c){ - honda_bosch_long = c; -} - -int get_honda_hw(void) { - return honda_hw; -} - -void set_honda_fwd_brake(bool c){ - honda_fwd_brake = c; -} - -bool get_honda_fwd_brake(void){ - return honda_fwd_brake; -} - -void set_mads_button_press(int c){ - mads_button_press = c; -} - -int get_mads_button_press(void){ - return mads_button_press; -} - -void set_controls_allowed_lat(bool c){ - m_mads_state.controls_allowed_lat = c; -} - -bool get_mads_acc_main(void){ - return m_mads_state.acc_main.current; -} - -int mads_get_current_disengage_reason(void) { - return get_mads_state()->current_disengage.active_reason; -} - -void mads_set_current_disengage_reason(int reason) { - m_mads_state.current_disengage.active_reason = reason; -} - -void set_controls_requested_lat(bool c){ - m_mads_state.controls_requested_lat = c; -} - -void set_mads_params(bool enable_mads, bool disengage_lateral_on_brake, bool pause_lateral_on_brake){ - alternative_experience = 0; - if (enable_mads) { - alternative_experience |= ALT_EXP_ENABLE_MADS; - - if (disengage_lateral_on_brake) { - alternative_experience |= ALT_EXP_MADS_DISENGAGE_LATERAL_ON_BRAKE; - } else if (pause_lateral_on_brake) { - alternative_experience |= ALT_EXP_MADS_PAUSE_LATERAL_ON_BRAKE; - } else { - } - } - - mads_set_alternative_experience(&alternative_experience); -} - -void set_heartbeat_engaged_mads(bool c){ - heartbeat_engaged_mads = c; -} - -void set_steering_disengage(bool c){ - steering_disengage = c; -} - -int get_gas_interceptor_prev(void){ - return gas_interceptor_prev; -} - -//int get_temp_debug(void){ -// return temp_debug; -//} - -void init_tests(void){ - safety_mode_cnt = 2U; // avoid ignoring relay_malfunction logic - alternative_experience = 0; - current_safety_param_sp = 0; - set_timer(0); - ts_steer_req_mismatch_last = 0; - valid_steer_req_count = 0; - invalid_steer_req_count = 0; - - // assumes autopark on safety mode init to avoid a fault. get rid of that for testing - tesla_autopark = false; -} diff --git a/opendbc/safety/tests/libsafety/safety_helpers.py b/opendbc/safety/tests/libsafety/safety_helpers.py deleted file mode 100644 index 899358e0..00000000 --- a/opendbc/safety/tests/libsafety/safety_helpers.py +++ /dev/null @@ -1,155 +0,0 @@ -# panda safety helpers, from safety_helpers.c -from typing import Protocol - - -def setup_safety_helpers(ffi): - ffi.cdef(""" - void set_controls_allowed(bool c); - bool get_controls_allowed(void); - bool get_lat_active(void); - bool get_controls_allowed_lat(void); - bool get_controls_requested_lat(void); - bool get_longitudinal_allowed(void); - void set_alternative_experience(int mode); - int get_alternative_experience(void); - void set_relay_malfunction(bool c); - bool get_relay_malfunction(void); - bool get_gas_pressed_prev(void); - void set_gas_pressed_prev(bool); - bool get_brake_pressed_prev(void); - bool get_regen_braking_prev(void); - bool get_steering_disengage_prev(void); - bool get_acc_main_on(void); - float get_vehicle_speed_min(void); - float get_vehicle_speed_max(void); - int get_current_safety_mode(void); - int get_current_safety_param(void); - void set_current_safety_param_sp(int param); - int get_current_safety_param_sp(void); - - void set_torque_meas(int min, int max); - int get_torque_meas_min(void); - int get_torque_meas_max(void); - void set_torque_driver(int min, int max); - int get_torque_driver_min(void); - int get_torque_driver_max(void); - void set_desired_torque_last(int t); - void set_rt_torque_last(int t); - void set_desired_angle_last(int t); - int get_desired_angle_last(); - void set_angle_meas(int min, int max); - int get_angle_meas_min(void); - int get_angle_meas_max(void); - - bool get_cruise_engaged_prev(void); - void set_cruise_engaged_prev(bool engaged); - bool get_vehicle_moving(void); - void set_timer(uint32_t t); - - void safety_tick_current_safety_config(); - bool safety_config_valid(); - - void init_tests(void); - - void set_honda_fwd_brake(bool c); - bool get_honda_fwd_brake(void); - void set_honda_alt_brake_msg(bool c); - void set_honda_bosch_long(bool c); - int get_honda_hw(void); - - bool get_enable_mads(void); - bool get_disengage_lateral_on_brake(void); - bool get_pause_lateral_on_brake(void); - void set_mads_button_press(int mads_button_press); - void set_controls_allowed_lat(bool c); - void set_controls_requested_lat(bool c); - - bool get_mads_acc_main(void); - void set_acc_main_on(bool c); - int get_mads_button_press(void); - void mads_set_current_disengage_reason(int reason); - int mads_get_current_disengage_reason(void); - int get_temp_debug(void); - uint32_t get_acc_main_on_mismatches(void); - void set_mads_params(bool enable_mads, bool disengage_lateral_on_brake, bool pause_lateral_on_brake); - void set_heartbeat_engaged_mads(bool c); - void mads_heartbeat_engaged_check(void); - void set_steering_disengage(bool c); - int get_gas_interceptor_prev(void); - """) - - -class PandaSafety(Protocol): - def set_controls_allowed(self, c: bool) -> None: ... - def get_controls_allowed(self) -> bool: ... - def set_controls_allowed_lat(self, c: bool) -> None: ... - def set_controls_requested_lat(self, c: bool) -> None: ... - def get_lat_active(self) -> bool: ... - def get_controls_allowed_lat(self) -> bool: ... - def get_controls_requested_lat(self) -> bool: ... - def get_mads_acc_main(self) -> bool: ... - def get_longitudinal_allowed(self) -> bool: ... - def set_alternative_experience(self, mode: int) -> None: ... - def get_alternative_experience(self) -> int: ... - def set_relay_malfunction(self, c: bool) -> None: ... - def get_relay_malfunction(self) -> bool: ... - def get_gas_pressed_prev(self) -> bool: ... - def set_gas_pressed_prev(self, c: bool) -> None: ... - def get_brake_pressed_prev(self) -> bool: ... - def get_regen_braking_prev(self) -> bool: ... - def get_steering_disengage_prev(self) -> bool: ... - def get_acc_main_on(self) -> bool: ... - def set_acc_main_on(self, c: bool) -> None: ... - def get_vehicle_speed_min(self) -> int: ... - def get_vehicle_speed_max(self) -> int: ... - def get_current_safety_mode(self) -> int: ... - def get_current_safety_param(self) -> int: ... - def set_current_safety_param_sp(self, param: int) -> int: ... - def get_current_safety_param_sp(self) -> int: ... - - def set_torque_meas(self, min: int, max: int) -> None: ... # noqa: A002 - def get_torque_meas_min(self) -> int: ... - def get_torque_meas_max(self) -> int: ... - def set_torque_driver(self, min: int, max: int) -> None: ... # noqa: A002 - def get_torque_driver_min(self) -> int: ... - def get_torque_driver_max(self) -> int: ... - def set_desired_torque_last(self, t: int) -> None: ... - def set_rt_torque_last(self, t: int) -> None: ... - def set_desired_angle_last(self, t: int) -> None: ... - def get_desired_angle_last(self) -> int: ... - def set_angle_meas(self, min: int, max: int) -> None: ... # noqa: A002 - def get_angle_meas_min(self) -> int: ... - def get_angle_meas_max(self) -> int: ... - - def get_cruise_engaged_prev(self) -> bool: ... - def set_cruise_engaged_prev(self, enabled: bool) -> None: ... - def get_vehicle_moving(self) -> bool: ... - def set_timer(self, t: int) -> None: ... - - def safety_tick_current_safety_config(self) -> None: ... - def safety_config_valid(self) -> bool: ... - - def init_tests(self) -> None: ... - - def set_honda_fwd_brake(self, c: bool) -> None: ... - def get_honda_fwd_brake(self) -> bool: ... - def set_honda_alt_brake_msg(self, c: bool) -> None: ... - def set_honda_bosch_long(self, c: bool) -> None: ... - def get_honda_hw(self) -> int: ... - - def set_mads_button_press(self, mads_button_press: int) -> None: ... - def get_enable_mads(self) -> bool: ... - def get_disengage_lateral_on_brake(self) -> bool: ... - def get_pause_lateral_on_brake(self) -> bool: ... - - def get_mads_button_press(self) -> int: ... - def mads_set_current_disengage_reason(self, reason: int) -> None: ... - def mads_get_current_disengage_reason(self) -> int: ... - def get_acc_main_on_mismatches(self) -> int: ... - - def set_mads_params(self, enable_mads: bool, disengage_lateral_on_brake: bool, pause_lateral_on_brake: bool) -> None: ... - def set_heartbeat_engaged_mads(self, c: bool) -> None: ... - def mads_heartbeat_engaged_check(self) -> None: ... - def set_steering_disengage(self, c: bool) -> None: ... - def get_gas_interceptor_prev(self) -> int: ... - # def get_temp_debug(self) -> int: ... diff --git a/opendbc/safety/tests/mads_common.py b/opendbc/safety/tests/mads_common.py index 51efef79..f33680bd 100644 --- a/opendbc/safety/tests/mads_common.py +++ b/opendbc/safety/tests/mads_common.py @@ -6,7 +6,7 @@ from opendbc.safety.tests.libsafety import libsafety_py class MadsSafetyTestBase(unittest.TestCase): - safety: libsafety_py.Panda + safety: libsafety_py.LibSafety @abc.abstractmethod def _lkas_button_msg(self, enabled): @@ -17,6 +17,7 @@ class MadsSafetyTestBase(unittest.TestCase): raise NotImplementedError def teardown_method(self, method): + self.safety = libsafety_py.libsafety self.safety.set_mads_button_press(-1) self.safety.set_controls_allowed_lat(False) self.safety.set_controls_requested_lat(False) diff --git a/opendbc/safety/tests/misra/main.c b/opendbc/safety/tests/misra/main.c index 701f2cd2..fe7eda92 100644 --- a/opendbc/safety/tests/misra/main.c +++ b/opendbc/safety/tests/misra/main.c @@ -2,14 +2,14 @@ // this file is checked by cppcheck -// Ignore misra-c2012-8.7 as these functions are only called from panda and libsafety -UNUSED(heartbeat_engaged); +// Ignore misra-c2012-8.7 as these functions are only called from libsafety +SAFETY_UNUSED(heartbeat_engaged); -UNUSED(safety_rx_hook); -UNUSED(safety_tx_hook); -UNUSED(safety_fwd_hook); -UNUSED(safety_tick); -UNUSED(set_safety_hooks); -UNUSED(mads_heartbeat_engaged_check); -UNUSED(mads_set_alternative_experience); -UNUSED(get_acc_main_on_mismatches); +SAFETY_UNUSED(safety_rx_hook); +SAFETY_UNUSED(safety_tx_hook); +SAFETY_UNUSED(safety_fwd_hook); +SAFETY_UNUSED(safety_tick); +SAFETY_UNUSED(set_safety_hooks); +SAFETY_UNUSED(mads_heartbeat_engaged_check); +SAFETY_UNUSED(mads_set_alternative_experience); +SAFETY_UNUSED(get_acc_main_on_mismatches); diff --git a/opendbc/safety/tests/misra/test_misra.sh b/opendbc/safety/tests/misra/test_misra.sh index 216278c4..a94d37d5 100755 --- a/opendbc/safety/tests/misra/test_misra.sh +++ b/opendbc/safety/tests/misra/test_misra.sh @@ -53,10 +53,10 @@ cppcheck() { fi } -PANDA_OPTS=" --enable=all --enable=unusedFunction --addon=misra" +OPTS=" --enable=all --enable=unusedFunction --addon=misra" printf "\n${GREEN}** Safety **${NC}\n" -cppcheck $PANDA_OPTS $BASEDIR/opendbc/safety/tests/misra/main.c +cppcheck $OPTS $BASEDIR/opendbc/safety/tests/misra/main.c printf "\n${GREEN}Success!${NC} took $SECONDS seconds\n" diff --git a/opendbc/safety/tests/mutation.sh b/opendbc/safety/tests/mutation.sh index 8b3b7c36..29bca601 100755 --- a/opendbc/safety/tests/mutation.sh +++ b/opendbc/safety/tests/mutation.sh @@ -5,13 +5,13 @@ DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" cd $DIR source $DIR/../../../setup.sh -$DIR/install_mull.sh GIT_REF="${GIT_REF:-origin/master}" GIT_ROOT=$(git rev-parse --show-toplevel) MULL_OPS="mutators: [cxx_increment, cxx_decrement, cxx_comparison, cxx_boundary, cxx_bitwise_assignment, cxx_bitwise, cxx_arithmetic_assignment, cxx_arithmetic, cxx_remove_negation]" echo -e "$MULL_OPS" > $GIT_ROOT/mull.yml -scons --mutation -j$(nproc) -D +scons -j$(nproc) -D echo -e "timeout: 1000000\ngitDiffRef: $GIT_REF\ngitProjectRoot: $GIT_ROOT" >> $GIT_ROOT/mull.yml -mull-runner-17 --ld-search-path /lib/x86_64-linux-gnu/ ./libsafety/libsafety.so -test-program=pytest -- -n8 --ignore-glob=misra/* +export MUTATION=1 +mull-runner-17 --ld-search-path /lib/x86_64-linux-gnu/ ./libsafety/libsafety_mutation.so -test-program=pytest -- -n8 --ignore-glob=misra/* diff --git a/opendbc/safety/tests/safety_replay/helpers.py b/opendbc/safety/tests/safety_replay/helpers.py index bc3baad5..a1c6611a 100644 --- a/opendbc/safety/tests/safety_replay/helpers.py +++ b/opendbc/safety/tests/safety_replay/helpers.py @@ -108,4 +108,4 @@ def init_segment(safety, msgs, mode, param): safety.set_controls_allowed_lat(1) safety.set_desired_angle_last(angle) safety.set_angle_meas(angle, angle) - assert safety.safety_tx_hook(msg), "failed to initialize panda safety for segment" + assert safety.safety_tx_hook(msg), "failed to initialize safety for segment" diff --git a/opendbc/safety/tests/test_body.py b/opendbc/safety/tests/test_body.py index e779bd69..ae98712c 100755 --- a/opendbc/safety/tests/test_body.py +++ b/opendbc/safety/tests/test_body.py @@ -4,31 +4,31 @@ import unittest from opendbc.car.structs import CarParams import opendbc.safety.tests.common as common from opendbc.safety.tests.libsafety import libsafety_py -from opendbc.safety.tests.common import CANPackerPanda +from opendbc.safety.tests.common import CANPackerSafety -class TestBody(common.PandaSafetyTest): +class TestBody(common.SafetyTest): TX_MSGS = [[0x250, 0], [0x251, 0], [0x1, 0], [0x1, 1], [0x1, 2], [0x1, 3]] FWD_BUS_LOOKUP = {} def setUp(self): - self.packer = CANPackerPanda("comma_body") + self.packer = CANPackerSafety("comma_body") self.safety = libsafety_py.libsafety self.safety.set_safety_hooks(CarParams.SafetyModel.body, 0) self.safety.init_tests() def _motors_data_msg(self, speed_l, speed_r): values = {"SPEED_L": speed_l, "SPEED_R": speed_r} - return self.packer.make_can_msg_panda("MOTORS_DATA", 0, values) + return self.packer.make_can_msg_safety("MOTORS_DATA", 0, values) def _torque_cmd_msg(self, torque_l, torque_r): values = {"TORQUE_L": torque_l, "TORQUE_R": torque_r} - return self.packer.make_can_msg_panda("TORQUE_CMD", 0, values) + return self.packer.make_can_msg_safety("TORQUE_CMD", 0, values) def _max_motor_rpm_cmd_msg(self, max_rpm_l, max_rpm_r): values = {"MAX_RPM_L": max_rpm_l, "MAX_RPM_R": max_rpm_r} - return self.packer.make_can_msg_panda("MAX_MOTOR_RPM_CMD", 0, values) + return self.packer.make_can_msg_safety("MAX_MOTOR_RPM_CMD", 0, values) def test_rx_hook(self): self.assertFalse(self.safety.get_controls_allowed()) diff --git a/opendbc/safety/tests/test_chrysler.py b/opendbc/safety/tests/test_chrysler.py index a31dd24a..4eb65335 100755 --- a/opendbc/safety/tests/test_chrysler.py +++ b/opendbc/safety/tests/test_chrysler.py @@ -5,10 +5,10 @@ from opendbc.car.chrysler.values import ChryslerSafetyFlags from opendbc.car.structs import CarParams from opendbc.safety.tests.libsafety import libsafety_py import opendbc.safety.tests.common as common -from opendbc.safety.tests.common import CANPackerPanda +from opendbc.safety.tests.common import CANPackerSafety -class TestChryslerSafety(common.PandaCarSafetyTest, common.MotorTorqueSteeringSafetyTest): +class TestChryslerSafety(common.CarSafetyTest, common.MotorTorqueSteeringSafetyTest): TX_MSGS = [[0x23B, 0], [0x292, 0], [0x2A6, 0], [0x2D9, 0]] RELAY_MALFUNCTION_ADDRS = {0: (0x292, 0x2A6, 0x2D9)} FWD_BLACKLISTED_ADDRS = {2: [0x292, 0x2A6, 0x2D9]} @@ -24,38 +24,38 @@ class TestChryslerSafety(common.PandaCarSafetyTest, common.MotorTorqueSteeringSa DAS_BUS = 0 def setUp(self): - self.packer = CANPackerPanda("chrysler_pacifica_2017_hybrid_generated") + self.packer = CANPackerSafety("chrysler_pacifica_2017_hybrid_generated") self.safety = libsafety_py.libsafety self.safety.set_safety_hooks(CarParams.SafetyModel.chrysler, 0) self.safety.init_tests() def _button_msg(self, cancel=False, resume=False, accel=False, decel=False): values = {"ACC_Cancel": cancel, "ACC_Resume": resume, "ACC_Accel": accel, "ACC_Decel": decel} - return self.packer.make_can_msg_panda("CRUISE_BUTTONS", self.DAS_BUS, values) + return self.packer.make_can_msg_safety("CRUISE_BUTTONS", self.DAS_BUS, values) def _pcm_status_msg(self, enable): values = {"ACC_ACTIVE": enable} - return self.packer.make_can_msg_panda("DAS_3", self.DAS_BUS, values) + return self.packer.make_can_msg_safety("DAS_3", self.DAS_BUS, values) def _speed_msg(self, speed): values = {"SPEED_LEFT": speed, "SPEED_RIGHT": speed} - return self.packer.make_can_msg_panda("SPEED_1", 0, values) + return self.packer.make_can_msg_safety("SPEED_1", 0, values) def _user_gas_msg(self, gas): values = {"Accelerator_Position": gas} - return self.packer.make_can_msg_panda("ECM_5", 0, values) + return self.packer.make_can_msg_safety("ECM_5", 0, values) def _user_brake_msg(self, brake): values = {"Brake_Pedal_State": 1 if brake else 0} - return self.packer.make_can_msg_panda("ESP_1", 0, values) + return self.packer.make_can_msg_safety("ESP_1", 0, values) def _torque_meas_msg(self, torque): values = {"EPS_TORQUE_MOTOR": torque} - return self.packer.make_can_msg_panda("EPS_2", 0, values) + return self.packer.make_can_msg_safety("EPS_2", 0, values) def _torque_cmd_msg(self, torque, steer_req=1): values = {"STEERING_TORQUE": torque, "LKAS_CONTROL_BIT": self.LKAS_ACTIVE_VALUE if steer_req else 0} - return self.packer.make_can_msg_panda("LKAS_COMMAND", 0, values) + return self.packer.make_can_msg_safety("LKAS_COMMAND", 0, values) def test_buttons(self): for controls_allowed in (True, False): @@ -95,7 +95,7 @@ class TestChryslerSafety(common.PandaCarSafetyTest, common.MotorTorqueSteeringSa def _lkas_button_msg(self, enabled): values = {"TOGGLE_LKAS": enabled} - return self.packer.make_can_msg_panda("TRACTION_BUTTON", 0, values) + return self.packer.make_can_msg_safety("TRACTION_BUTTON", 0, values) class TestChryslerRamDTSafety(TestChryslerSafety): @@ -112,18 +112,18 @@ class TestChryslerRamDTSafety(TestChryslerSafety): LKAS_ACTIVE_VALUE = 2 def setUp(self): - self.packer = CANPackerPanda("chrysler_ram_dt_generated") + self.packer = CANPackerSafety("chrysler_ram_dt_generated") self.safety = libsafety_py.libsafety self.safety.set_safety_hooks(CarParams.SafetyModel.chrysler, ChryslerSafetyFlags.RAM_DT) self.safety.init_tests() def _speed_msg(self, speed): values = {"Vehicle_Speed": speed} - return self.packer.make_can_msg_panda("ESP_8", 0, values) + return self.packer.make_can_msg_safety("ESP_8", 0, values) def _lkas_button_msg(self, enabled): values = {"LKAS_Button": enabled} - return self.packer.make_can_msg_panda("Center_Stack_2", 0, values) + return self.packer.make_can_msg_safety("Center_Stack_2", 0, values) class TestChryslerRamHDSafety(TestChryslerSafety): @@ -141,18 +141,18 @@ class TestChryslerRamHDSafety(TestChryslerSafety): LKAS_ACTIVE_VALUE = 2 def setUp(self): - self.packer = CANPackerPanda("chrysler_ram_hd_generated") + self.packer = CANPackerSafety("chrysler_ram_hd_generated") self.safety = libsafety_py.libsafety self.safety.set_safety_hooks(CarParams.SafetyModel.chrysler, ChryslerSafetyFlags.RAM_HD) self.safety.init_tests() def _speed_msg(self, speed): values = {"Vehicle_Speed": speed} - return self.packer.make_can_msg_panda("ESP_8", 0, values) + return self.packer.make_can_msg_safety("ESP_8", 0, values) def _lkas_button_msg(self, enabled): values = {"LKAS_Button": enabled} - return self.packer.make_can_msg_panda("Center_Stack_2", 0, values) + return self.packer.make_can_msg_safety("Center_Stack_2", 0, values) if __name__ == "__main__": diff --git a/opendbc/safety/tests/test_defaults.py b/opendbc/safety/tests/test_defaults.py index e44a1cd0..4e596154 100755 --- a/opendbc/safety/tests/test_defaults.py +++ b/opendbc/safety/tests/test_defaults.py @@ -6,7 +6,7 @@ from opendbc.car.structs import CarParams from opendbc.safety.tests.libsafety import libsafety_py -class TestDefaultRxHookBase(common.PandaSafetyTest): +class TestDefaultRxHookBase(common.SafetyTest): FWD_BUS_LOOKUP = {} def test_rx_hook(self): @@ -36,7 +36,7 @@ class TestSilent(TestNoOutput): class TestAllOutput(TestDefaultRxHookBase): # Allow all messages - TX_MSGS = [[addr, bus] for addr in common.PandaSafetyTest.SCANNED_ADDRS + TX_MSGS = [[addr, bus] for addr in common.SafetyTest.SCANNED_ADDRS for bus in range(4)] def setUp(self): diff --git a/opendbc/safety/tests/test_ford.py b/opendbc/safety/tests/test_ford.py index 9f719504..51816a37 100755 --- a/opendbc/safety/tests/test_ford.py +++ b/opendbc/safety/tests/test_ford.py @@ -8,7 +8,7 @@ from opendbc.car.ford.carcontroller import MAX_LATERAL_ACCEL from opendbc.car.ford.values import FordSafetyFlags from opendbc.car.structs import CarParams from opendbc.safety.tests.libsafety import libsafety_py -from opendbc.safety.tests.common import CANPackerPanda +from opendbc.safety.tests.common import CANPackerSafety MSG_EngBrakeData = 0x165 # RX from PCM, for driver brake pedal and cruise state MSG_EngVehicleSpThrottle = 0x204 # RX from PCM, for driver throttle input @@ -65,7 +65,7 @@ class Buttons: # * CAN FD with stock longitudinal # * CAN FD with openpilot longitudinal -class TestFordSafetyBase(common.PandaCarSafetyTest): +class TestFordSafetyBase(common.CarSafetyTest): STANDSTILL_THRESHOLD = 1 RELAY_MALFUNCTION_ADDRS = {0: (MSG_ACCDATA_3, MSG_Lane_Assist_Data1, MSG_LateralMotionControl, MSG_LateralMotionControl2, MSG_IPMA_Data)} @@ -89,8 +89,8 @@ class TestFordSafetyBase(common.PandaCarSafetyTest): cnt_speed_2 = 0 cnt_yaw_rate = 0 - packer: CANPackerPanda - safety: libsafety_py.Panda + packer: CANPackerSafety + safety: libsafety_py.LibSafety def get_canfd_curvature_limits(self, speed): # Round it in accordance with the safety @@ -117,37 +117,37 @@ class TestFordSafetyBase(common.PandaCarSafetyTest): "BpedDrvAppl_D_Actl": 2 if brake else 1, "CcStat_D_Actl": 5 if enable else 0, } - return self.packer.make_can_msg_panda("EngBrakeData", 0, values) + return self.packer.make_can_msg_safety("EngBrakeData", 0, values) # ABS vehicle speed def _speed_msg(self, speed: float, quality_flag=True): values = {"Veh_V_ActlBrk": speed * 3.6, "VehVActlBrk_D_Qf": 3 if quality_flag else 0, "VehVActlBrk_No_Cnt": self.cnt_speed % 16} self.__class__.cnt_speed += 1 - return self.packer.make_can_msg_panda("BrakeSysFeatures", 0, values, fix_checksum=checksum) + return self.packer.make_can_msg_safety("BrakeSysFeatures", 0, values, fix_checksum=checksum) # PCM vehicle speed def _speed_msg_2(self, speed: float, quality_flag=True): # Ford relies on speed for driver curvature limiting, so it checks two sources values = {"Veh_V_ActlEng": speed * 3.6, "VehVActlEng_D_Qf": 3 if quality_flag else 0, "VehVActlEng_No_Cnt": self.cnt_speed_2 % 16} self.__class__.cnt_speed_2 += 1 - return self.packer.make_can_msg_panda("EngVehicleSpThrottle2", 0, values, fix_checksum=checksum) + return self.packer.make_can_msg_safety("EngVehicleSpThrottle2", 0, values, fix_checksum=checksum) # Standstill state def _vehicle_moving_msg(self, speed: float): values = {"VehStop_D_Stat": 1 if speed <= self.STANDSTILL_THRESHOLD else random.choice((0, 2, 3))} - return self.packer.make_can_msg_panda("DesiredTorqBrk", 0, values) + return self.packer.make_can_msg_safety("DesiredTorqBrk", 0, values) # Current curvature def _yaw_rate_msg(self, curvature: float, speed: float, quality_flag=True): values = {"VehYaw_W_Actl": curvature * speed, "VehYawWActl_D_Qf": 3 if quality_flag else 0, "VehRollYaw_No_Cnt": self.cnt_yaw_rate % 256} self.__class__.cnt_yaw_rate += 1 - return self.packer.make_can_msg_panda("Yaw_Data_FD1", 0, values, fix_checksum=checksum) + return self.packer.make_can_msg_safety("Yaw_Data_FD1", 0, values, fix_checksum=checksum) # Drive throttle input def _user_gas_msg(self, gas: float): values = {"ApedPos_Pc_ActlArb": gas} - return self.packer.make_can_msg_panda("EngVehicleSpThrottle", 0, values) + return self.packer.make_can_msg_safety("EngVehicleSpThrottle", 0, values) # Cruise status def _pcm_status_msg(self, enable: bool): @@ -158,14 +158,14 @@ class TestFordSafetyBase(common.PandaCarSafetyTest): "BpedDrvAppl_D_Actl": 2 if brake else 1, "CcStat_D_Actl": 5 if enable else 0, } - return self.packer.make_can_msg_panda("EngBrakeData", 0, values) + return self.packer.make_can_msg_safety("EngBrakeData", 0, values) # LKAS command def _lkas_command_msg(self, action: int): values = { "LkaActvStats_D2_Req": action, } - return self.packer.make_can_msg_panda("Lane_Assist_Data1", 0, values) + return self.packer.make_can_msg_safety("Lane_Assist_Data1", 0, values) # LCA command def _lat_ctl_msg(self, enabled: bool, path_offset: float, path_angle: float, curvature: float, curvature_rate: float): @@ -177,7 +177,7 @@ class TestFordSafetyBase(common.PandaCarSafetyTest): "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 self.packer.make_can_msg_panda("LateralMotionControl", 0, values) + return self.packer.make_can_msg_safety("LateralMotionControl", 0, values) elif self.STEER_MESSAGE == MSG_LateralMotionControl2: values = { "LatCtl_D2_Rq": 1 if enabled else 0, @@ -186,7 +186,7 @@ class TestFordSafetyBase(common.PandaCarSafetyTest): "LatCtlCrv_NoRate2_Actl": curvature_rate, # Curvature rate [-0.001024|0.001023] 1/meter^2 "LatCtlCurv_No_Actl": curvature, # Curvature [-0.02|0.02094] 1/meter } - return self.packer.make_can_msg_panda("LateralMotionControl2", 0, values) + return self.packer.make_can_msg_safety("LateralMotionControl2", 0, values) # Cruise control buttons def _acc_button_msg(self, button: int, bus: int): @@ -195,7 +195,7 @@ class TestFordSafetyBase(common.PandaCarSafetyTest): "CcAsllButtnResPress": 1 if button == Buttons.RESUME else 0, "TjaButtnOnOffPress": 1 if button == Buttons.TJA_TOGGLE else 0, } - return self.packer.make_can_msg_panda("Steering_Data_FD1", bus, values) + return self.packer.make_can_msg_safety("Steering_Data_FD1", bus, values) def test_rx_hook(self): # checksum, counter, and quality flag checks @@ -294,7 +294,7 @@ class TestFordSafetyBase(common.PandaCarSafetyTest): def test_curvature_rate_limits(self): """ When the curvature error is exceeded, commanded curvature must start moving towards meas respecting rate limits. - Since panda allows higher rate limits to avoid false positives, we need to allow a lower rate to move towards meas. + Since safety allows higher rate limits to avoid false positives, we need to allow a lower rate to move towards meas. """ self.safety.set_controls_allowed(True) # safety fudges the speed (1 m/s) and rate limits (1 CAN unit) to avoid false positives @@ -402,7 +402,7 @@ class TestFordCANFDStockSafety(TestFordSafetyBase): MSG_IPMA_Data]} def setUp(self): - self.packer = CANPackerPanda("ford_lincoln_base_pt") + self.packer = CANPackerSafety("ford_lincoln_base_pt") self.safety = libsafety_py.libsafety self.safety.set_safety_hooks(CarParams.SafetyModel.ford, FordSafetyFlags.CANFD) self.safety.init_tests() @@ -427,7 +427,7 @@ class TestFordLongitudinalSafetyBase(TestFordSafetyBase): "AccBrkDecel_B_Rq": 1 if brake_actuation else 0, # Deceleration request: 0=Inactive, 1=Active "CmbbDeny_B_Actl": 1 if cmbb_deny else 0, # [0|1] deny AEB actuation } - return self.packer.make_can_msg_panda("ACCDATA", 0, values) + return self.packer.make_can_msg_safety("ACCDATA", 0, values) def test_stock_aeb(self): # Test that CmbbDeny_B_Actl is never 1, it prevents the ABS module from actuating AEB requests from ACCDATA_2 @@ -472,7 +472,7 @@ class TestFordLongitudinalSafety(TestFordLongitudinalSafetyBase): MSG_IPMA_Data]} def setUp(self): - self.packer = CANPackerPanda("ford_lincoln_base_pt") + self.packer = CANPackerSafety("ford_lincoln_base_pt") self.safety = libsafety_py.libsafety # Make sure we enforce long safety even without long flag for CAN self.safety.set_safety_hooks(CarParams.SafetyModel.ford, 0) @@ -497,7 +497,7 @@ class TestFordCANFDLongitudinalSafety(TestFordLongitudinalSafetyBase): MSG_IPMA_Data]} def setUp(self): - self.packer = CANPackerPanda("ford_lincoln_base_pt") + self.packer = CANPackerSafety("ford_lincoln_base_pt") self.safety = libsafety_py.libsafety self.safety.set_safety_hooks(CarParams.SafetyModel.ford, FordSafetyFlags.LONG_CONTROL | FordSafetyFlags.CANFD) self.safety.init_tests() diff --git a/opendbc/safety/tests/test_gm.py b/opendbc/safety/tests/test_gm.py index 4d8d1bad..7e67a469 100755 --- a/opendbc/safety/tests/test_gm.py +++ b/opendbc/safety/tests/test_gm.py @@ -5,7 +5,7 @@ from opendbc.car.gm.values import GMSafetyFlags from opendbc.car.structs import CarParams from opendbc.safety.tests.libsafety import libsafety_py import opendbc.safety.tests.common as common -from opendbc.safety.tests.common import CANPackerPanda +from opendbc.safety.tests.common import CANPackerSafety from opendbc.sunnypilot.car.gm.values_ext import GMSafetyFlagsSP @@ -17,7 +17,7 @@ class Buttons: CANCEL = 6 -class GmLongitudinalBase(common.PandaCarSafetyTest, common.LongitudinalGasBrakeSafetyTest): +class GmLongitudinalBase(common.CarSafetyTest, common.LongitudinalGasBrakeSafetyTest): RELAY_MALFUNCTION_ADDRS = {0: (0x180, 0x2CB), 2: (0x184,)} # ASCMLKASteeringCmd, ASCMGasRegenCmd, PSCMStatus @@ -31,13 +31,13 @@ class GmLongitudinalBase(common.PandaCarSafetyTest, common.LongitudinalGasBrakeS def _send_brake_msg(self, brake): values = {"FrictionBrakeCmd": -brake} - return self.packer_chassis.make_can_msg_panda("EBCMFrictionBrakeCmd", self.BRAKE_BUS, values) + return self.packer_chassis.make_can_msg_safety("EBCMFrictionBrakeCmd", self.BRAKE_BUS, values) def _send_gas_msg(self, gas): values = {"GasRegenCmd": gas} - return self.packer.make_can_msg_panda("ASCMGasRegenCmd", 0, values) + return self.packer.make_can_msg_safety("ASCMGasRegenCmd", 0, values) - # override these tests from PandaCarSafetyTest, GM longitudinal uses button enable + # override these tests from CarSafetyTest, GM longitudinal uses button enable def _pcm_status_msg(self, enable): raise NotImplementedError @@ -73,7 +73,7 @@ class GmLongitudinalBase(common.PandaCarSafetyTest, common.LongitudinalGasBrakeS self.assertFalse(self.safety.get_controls_allowed()) -class TestGmSafetyBase(common.PandaCarSafetyTest, common.DriverTorqueSteeringSafetyTest): +class TestGmSafetyBase(common.CarSafetyTest, common.DriverTorqueSteeringSafetyTest): STANDSTILL_THRESHOLD = 10 * 0.0311 # Ensures ASCM is off on ASCM cars, and relay is not malfunctioning for camera-ACC cars RELAY_MALFUNCTION_ADDRS = {0: (0x180,), 2: (0x184,)} # ASCMLKASteeringCmd, PSCMStatus @@ -92,8 +92,8 @@ class TestGmSafetyBase(common.PandaCarSafetyTest, common.DriverTorqueSteeringSaf EXTRA_SAFETY_PARAM = 0 def setUp(self): - self.packer = CANPackerPanda("gm_global_a_powertrain_generated") - self.packer_chassis = CANPackerPanda("gm_global_a_chassis") + self.packer = CANPackerSafety("gm_global_a_powertrain_generated") + self.packer_chassis = CANPackerSafety("gm_global_a_chassis") self.safety = libsafety_py.libsafety self.safety.set_safety_hooks(CarParams.SafetyModel.gm, 0) self.safety.init_tests() @@ -101,38 +101,38 @@ class TestGmSafetyBase(common.PandaCarSafetyTest, common.DriverTorqueSteeringSaf def _pcm_status_msg(self, enable): if self.PCM_CRUISE: values = {"CruiseState": enable} - return self.packer.make_can_msg_panda("AcceleratorPedal2", 0, values) + return self.packer.make_can_msg_safety("AcceleratorPedal2", 0, values) else: raise NotImplementedError def _speed_msg(self, speed): values = {"%sWheelSpd" % s: speed for s in ["RL", "RR"]} - return self.packer.make_can_msg_panda("EBCMWheelSpdRear", 0, values) + return self.packer.make_can_msg_safety("EBCMWheelSpdRear", 0, values) def _user_brake_msg(self, brake): # GM safety has a brake threshold of 8 values = {"BrakePedalPos": 8 if brake else 0} - return self.packer.make_can_msg_panda("ECMAcceleratorPos", 0, values) + return self.packer.make_can_msg_safety("ECMAcceleratorPos", 0, values) def _user_gas_msg(self, gas): values = {"AcceleratorPedal2": 1 if gas else 0} if self.PCM_CRUISE: # Fill CruiseState with expected value if the safety mode reads cruise state from gas msg values["CruiseState"] = self.safety.get_controls_allowed() - return self.packer.make_can_msg_panda("AcceleratorPedal2", 0, values) + return self.packer.make_can_msg_safety("AcceleratorPedal2", 0, values) def _torque_driver_msg(self, torque): # Safety tests assume driver torque is an int, use DBC factor values = {"LKADriverAppldTrq": torque * 0.01} - return self.packer.make_can_msg_panda("PSCMStatus", 0, values) + return self.packer.make_can_msg_safety("PSCMStatus", 0, values) def _torque_cmd_msg(self, torque, steer_req=1): values = {"LKASteeringCmd": torque, "LKASteeringCmdActive": steer_req} - return self.packer.make_can_msg_panda("ASCMLKASteeringCmd", 0, values) + return self.packer.make_can_msg_safety("ASCMLKASteeringCmd", 0, values) def _button_msg(self, buttons): values = {"ACCButtons": buttons} - return self.packer.make_can_msg_panda("ASCMSteeringButton", self.BUTTONS_BUS, values) + return self.packer.make_can_msg_safety("ASCMSteeringButton", self.BUTTONS_BUS, values) class TestGmEVSafetyBase(TestGmSafetyBase): @@ -141,7 +141,7 @@ class TestGmEVSafetyBase(TestGmSafetyBase): # existence of _user_regen_msg adds regen tests def _user_regen_msg(self, regen): values = {"RegenPaddle": 2 if regen else 0} - return self.packer.make_can_msg_panda("EBCMRegenPaddle", 0, values) + return self.packer.make_can_msg_safety("EBCMRegenPaddle", 0, values) class TestGmAscmSafety(GmLongitudinalBase, TestGmSafetyBase): @@ -158,8 +158,8 @@ class TestGmAscmSafety(GmLongitudinalBase, TestGmSafetyBase): INACTIVE_GAS = -650 def setUp(self): - self.packer = CANPackerPanda("gm_global_a_powertrain_generated") - self.packer_chassis = CANPackerPanda("gm_global_a_chassis") + self.packer = CANPackerSafety("gm_global_a_powertrain_generated") + self.packer_chassis = CANPackerSafety("gm_global_a_chassis") self.safety = libsafety_py.libsafety self.safety.set_safety_hooks(CarParams.SafetyModel.gm, self.EXTRA_SAFETY_PARAM) self.safety.init_tests() @@ -172,7 +172,7 @@ class TestGmAscmEVSafety(TestGmAscmSafety, TestGmEVSafetyBase): class TestGmCameraSafetyBase(TestGmSafetyBase): def _user_brake_msg(self, brake): values = {"BrakePressed": brake} - return self.packer.make_can_msg_panda("ECMEngineStatus", 0, values) + return self.packer.make_can_msg_safety("ECMEngineStatus", 0, values) class TestGmCameraSafety(TestGmCameraSafetyBase): @@ -182,8 +182,8 @@ class TestGmCameraSafety(TestGmCameraSafetyBase): BUTTONS_BUS = 2 # tx only def setUp(self): - self.packer = CANPackerPanda("gm_global_a_powertrain_generated") - self.packer_chassis = CANPackerPanda("gm_global_a_chassis") + self.packer = CANPackerSafety("gm_global_a_powertrain_generated") + self.packer_chassis = CANPackerSafety("gm_global_a_chassis") self.safety = libsafety_py.libsafety self.safety.set_safety_hooks(CarParams.SafetyModel.gm, GMSafetyFlags.HW_CAM | self.EXTRA_SAFETY_PARAM) self.safety.init_tests() @@ -219,8 +219,8 @@ class TestGmCameraLongitudinalSafety(GmLongitudinalBase, TestGmCameraSafetyBase) INACTIVE_GAS = -500 def setUp(self): - self.packer = CANPackerPanda("gm_global_a_powertrain_generated") - self.packer_chassis = CANPackerPanda("gm_global_a_chassis") + self.packer = CANPackerSafety("gm_global_a_powertrain_generated") + self.packer_chassis = CANPackerSafety("gm_global_a_chassis") self.safety = libsafety_py.libsafety self.safety.set_safety_hooks(CarParams.SafetyModel.gm, GMSafetyFlags.HW_CAM | GMSafetyFlags.HW_CAM_LONG | self.EXTRA_SAFETY_PARAM) self.safety.init_tests() @@ -233,8 +233,8 @@ class TestGmCameraLongitudinalEVSafety(TestGmCameraLongitudinalSafety, TestGmEVS class TestGmCameraNonACCSafety(TestGmCameraSafety): def setUp(self): - self.packer = CANPackerPanda("gm_global_a_powertrain_generated") - self.packer_chassis = CANPackerPanda("gm_global_a_chassis") + self.packer = CANPackerSafety("gm_global_a_powertrain_generated") + self.packer_chassis = CANPackerSafety("gm_global_a_chassis") self.safety = libsafety_py.libsafety self.safety.set_current_safety_param_sp(GMSafetyFlagsSP.NON_ACC) self.safety.set_safety_hooks(CarParams.SafetyModel.gm, GMSafetyFlags.HW_CAM | self.EXTRA_SAFETY_PARAM) @@ -242,7 +242,7 @@ class TestGmCameraNonACCSafety(TestGmCameraSafety): def _pcm_status_msg(self, enable): values = {"CruiseActive": enable} - return self.packer.make_can_msg_panda("ECMCruiseControl", 0, values) + return self.packer.make_can_msg_safety("ECMCruiseControl", 0, values) class TestGmCameraEVNonACCSafety(TestGmCameraNonACCSafety, TestGmEVSafetyBase): diff --git a/opendbc/safety/tests/test_honda.py b/opendbc/safety/tests/test_honda.py index cc413b5d..f71a988b 100755 --- a/opendbc/safety/tests/test_honda.py +++ b/opendbc/safety/tests/test_honda.py @@ -6,7 +6,7 @@ from opendbc.car.honda.values import HondaSafetyFlags from opendbc.safety.tests.libsafety import libsafety_py import opendbc.safety.tests.common as common from opendbc.car.structs import CarParams -from opendbc.safety.tests.common import CANPackerPanda, MAX_WRONG_COUNTERS +from opendbc.safety.tests.common import CANPackerSafety, MAX_WRONG_COUNTERS from opendbc.safety.tests.gas_interceptor_common import GasInterceptorSafetyTest from opendbc.sunnypilot.car.honda.values_ext import HondaSafetyFlagsSP @@ -33,7 +33,7 @@ class Btn: # * Bosch Radarless with Longitudinal Support -class HondaButtonEnableBase(common.PandaCarSafetyTest): +class HondaButtonEnableBase(common.CarSafetyTest): # override these inherited tests since we're using button enable def test_disable_control_allowed_from_cruise(self): @@ -139,7 +139,7 @@ class HondaButtonEnableBase(common.PandaCarSafetyTest): self.assertTrue(self.safety.get_controls_allowed()) -class HondaPcmEnableBase(common.PandaCarSafetyTest): +class HondaPcmEnableBase(common.CarSafetyTest): def test_buttons(self): """ @@ -166,7 +166,7 @@ class HondaPcmEnableBase(common.PandaCarSafetyTest): self.assertEqual(controls_allowed, self.safety.get_controls_allowed()) -class HondaBase(common.PandaCarSafetyTest): +class HondaBase(common.CarSafetyTest): MAX_BRAKE = 255 PT_BUS: int | None = None # must be set when inherited STEER_BUS: int | None = None # must be set when inherited @@ -197,7 +197,7 @@ class HondaBase(common.PandaCarSafetyTest): "COUNTER": self.cnt_powertrain_data % 4 } self.__class__.cnt_powertrain_data += 1 - return self.packer.make_can_msg_panda("POWERTRAIN_DATA", self.PT_BUS, values) + return self.packer.make_can_msg_safety("POWERTRAIN_DATA", self.PT_BUS, values) def _pcm_status_msg(self, enable): return self._powertrain_data_msg(cruise_on=enable) @@ -205,18 +205,18 @@ class HondaBase(common.PandaCarSafetyTest): def _speed_msg(self, speed): values = {"XMISSION_SPEED": speed, "COUNTER": self.cnt_speed % 4} self.__class__.cnt_speed += 1 - return self.packer.make_can_msg_panda("ENGINE_DATA", self.PT_BUS, values) + return self.packer.make_can_msg_safety("ENGINE_DATA", self.PT_BUS, values) def _acc_state_msg(self, main_on): values = {"MAIN_ON": main_on, "COUNTER": self.cnt_acc_state % 4} self.__class__.cnt_acc_state += 1 - return self.packer.make_can_msg_panda("SCM_FEEDBACK", self.PT_BUS, values) + return self.packer.make_can_msg_safety("SCM_FEEDBACK", self.PT_BUS, values) def _button_msg(self, buttons, main_on=False, bus=None): bus = self.PT_BUS if bus is None else bus values = {"CRUISE_BUTTONS": buttons, "COUNTER": self.cnt_button % 4} self.__class__.cnt_button += 1 - return self.packer.make_can_msg_panda("SCM_BUTTONS", bus, values) + return self.packer.make_can_msg_safety("SCM_BUTTONS", bus, values) def _user_brake_msg(self, brake): return self._powertrain_data_msg(brake_pressed=brake) @@ -226,7 +226,7 @@ class HondaBase(common.PandaCarSafetyTest): def _send_steer_msg(self, steer): values = {"STEER_TORQUE": steer} - return self.packer.make_can_msg_panda("STEERING_CONTROL", self.STEER_BUS, values) + return self.packer.make_can_msg_safety("STEERING_CONTROL", self.STEER_BUS, values) def _send_brake_msg(self, brake): # must be implemented when inherited @@ -245,7 +245,7 @@ class HondaBase(common.PandaCarSafetyTest): def _lkas_button_msg(self, lkas_button=False, setting_btn=0): values = {"CRUISE_SETTING": 1 if lkas_button else setting_btn, "COUNTER": self.cnt_button % 4} self.__class__.cnt_button += 1 - return self.packer.make_can_msg_panda("SCM_BUTTONS", self.PT_BUS, values) + return self.packer.make_can_msg_safety("SCM_BUTTONS", self.PT_BUS, values) def test_enable_control_allowed_with_mads_button(self): """Tests MADS button state transitions and internal button press state.""" @@ -298,14 +298,14 @@ class TestHondaNidecSafetyBase(HondaBase): BRAKE_SIG = "COMPUTER_BRAKE" def setUp(self): - self.packer = CANPackerPanda("honda_civic_touring_2016_can_generated") + self.packer = CANPackerSafety("honda_civic_touring_2016_can_generated") self.safety = libsafety_py.libsafety self.safety.set_safety_hooks(CarParams.SafetyModel.hondaNidec, 0) self.safety.init_tests() def _send_brake_msg(self, brake, aeb_req=0, bus=0): values = {self.BRAKE_SIG: brake, "AEB_REQ_1": aeb_req} - return self.packer.make_can_msg_panda("BRAKE_COMMAND", bus, values) + return self.packer.make_can_msg_safety("BRAKE_COMMAND", bus, values) def _rx_brake_msg(self, brake, aeb_req=0): return self._send_brake_msg(brake, aeb_req, bus=2) @@ -313,7 +313,7 @@ class TestHondaNidecSafetyBase(HondaBase): def _send_acc_hud_msg(self, pcm_gas, pcm_speed): # Used to control ACC on Nidec without pedal values = {"PCM_GAS": pcm_gas, "PCM_SPEED": pcm_speed} - return self.packer.make_can_msg_panda("ACC_HUD", 0, values) + return self.packer.make_can_msg_safety("ACC_HUD", 0, values) def test_acc_hud_safety_check(self): for controls_allowed in [True, False]: @@ -392,7 +392,7 @@ class TestHondaNidecGasInterceptorSafety(GasInterceptorSafetyTest, HondaButtonEn INTERCEPTOR_THRESHOLD = 492 def setUp(self): - self.packer = CANPackerPanda("honda_civic_touring_2016_can_generated") + self.packer = CANPackerSafety("honda_civic_touring_2016_can_generated") self.safety = libsafety_py.libsafety self.safety.set_current_safety_param_sp(HondaSafetyFlagsSP.GAS_INTERCEPTOR) self.safety.set_safety_hooks(CarParams.SafetyModel.hondaNidec, 0) @@ -404,7 +404,7 @@ class TestHondaNidecPcmAltSafety(TestHondaNidecPcmSafety): Covers the Honda Nidec safety mode with alt SCM messages """ def setUp(self): - self.packer = CANPackerPanda("acura_ilx_2016_can_generated") + self.packer = CANPackerSafety("acura_ilx_2016_can_generated") self.safety = libsafety_py.libsafety self.safety.set_safety_hooks(CarParams.SafetyModel.hondaNidec, HondaSafetyFlags.NIDEC_ALT) self.safety.init_tests() @@ -412,13 +412,13 @@ class TestHondaNidecPcmAltSafety(TestHondaNidecPcmSafety): def _acc_state_msg(self, main_on): values = {"MAIN_ON": main_on, "COUNTER": self.cnt_acc_state % 4} self.__class__.cnt_acc_state += 1 - return self.packer.make_can_msg_panda("SCM_BUTTONS", self.PT_BUS, values) + return self.packer.make_can_msg_safety("SCM_BUTTONS", self.PT_BUS, values) def _button_msg(self, buttons, main_on=False, bus=None): bus = self.PT_BUS if bus is None else bus values = {"CRUISE_BUTTONS": buttons, "MAIN_ON": main_on, "COUNTER": self.cnt_button % 4} self.__class__.cnt_button += 1 - return self.packer.make_can_msg_panda("SCM_BUTTONS", bus, values) + return self.packer.make_can_msg_safety("SCM_BUTTONS", bus, values) class TestHondaNidecAltGasInterceptorSafety(GasInterceptorSafetyTest, HondaButtonEnableBase, TestHondaNidecSafetyBase): @@ -430,7 +430,7 @@ class TestHondaNidecAltGasInterceptorSafety(GasInterceptorSafetyTest, HondaButto INTERCEPTOR_THRESHOLD = 492 def setUp(self): - self.packer = CANPackerPanda("acura_ilx_2016_can_generated") + self.packer = CANPackerSafety("acura_ilx_2016_can_generated") self.safety = libsafety_py.libsafety self.safety.set_current_safety_param_sp(HondaSafetyFlagsSP.GAS_INTERCEPTOR) self.safety.set_safety_hooks(CarParams.SafetyModel.hondaNidec, HondaSafetyFlags.NIDEC_ALT) @@ -439,13 +439,13 @@ class TestHondaNidecAltGasInterceptorSafety(GasInterceptorSafetyTest, HondaButto def _acc_state_msg(self, main_on): values = {"MAIN_ON": main_on, "COUNTER": self.cnt_acc_state % 4} self.__class__.cnt_acc_state += 1 - return self.packer.make_can_msg_panda("SCM_BUTTONS", self.PT_BUS, values) + return self.packer.make_can_msg_safety("SCM_BUTTONS", self.PT_BUS, values) def _button_msg(self, buttons, main_on=False, bus=None): bus = self.PT_BUS if bus is None else bus values = {"CRUISE_BUTTONS": buttons, "MAIN_ON": main_on, "COUNTER": self.cnt_button % 4} self.__class__.cnt_button += 1 - return self.packer.make_can_msg_panda("SCM_BUTTONS", bus, values) + return self.packer.make_can_msg_safety("SCM_BUTTONS", bus, values) # ********************* Honda Bosch ********************** @@ -461,13 +461,13 @@ class TestHondaBoschSafetyBase(HondaBase): RELAY_MALFUNCTION_ADDRS = {0: (0xE4, 0xE5, 0x33D, 0x33DA, 0x33DB)} # STEERING_CONTROL, BOSCH_SUPPLEMENTAL_1 def setUp(self): - self.packer = CANPackerPanda("honda_civic_hatchback_ex_2017_can_generated") + self.packer = CANPackerSafety("honda_civic_hatchback_ex_2017_can_generated") self.safety = libsafety_py.libsafety def _alt_brake_msg(self, brake): values = {"BRAKE_PRESSED": brake, "COUNTER": self.cnt_brake % 4} self.__class__.cnt_brake += 1 - return self.packer.make_can_msg_panda("BRAKE_MODULE", self.PT_BUS, values) + return self.packer.make_can_msg_safety("BRAKE_MODULE", self.PT_BUS, values) def _send_brake_msg(self, brake): pass @@ -557,7 +557,7 @@ class TestHondaBoschLongSafety(HondaButtonEnableBase, TestHondaBoschSafetyBase): "ACCEL_COMMAND": accel, "BRAKE_REQUEST": accel < 0, } - return self.packer.make_can_msg_panda("ACC_CONTROL", self.PT_BUS, values) + return self.packer.make_can_msg_safety("ACC_CONTROL", self.PT_BUS, values) # Longitudinal doesn't need to send buttons def test_spam_cancel_safety_check(self): @@ -598,7 +598,7 @@ class TestHondaBoschRadarlessSafetyBase(TestHondaBoschSafetyBase): RELAY_MALFUNCTION_ADDRS = {0: (0xE4, 0x33D)} # STEERING_CONTROL def setUp(self): - self.packer = CANPackerPanda("honda_bosch_radarless_generated") + self.packer = CANPackerSafety("honda_bosch_radarless_generated") self.safety = libsafety_py.libsafety @@ -642,7 +642,7 @@ class TestHondaBoschRadarlessLongSafety(common.LongitudinalAccelSafetyTest, Hond values = { "ACCEL_COMMAND": accel, } - return self.packer.make_can_msg_panda("ACC_CONTROL", self.PT_BUS, values) + return self.packer.make_can_msg_safety("ACC_CONTROL", self.PT_BUS, values) # Longitudinal doesn't need to send buttons def test_spam_cancel_safety_check(self): @@ -660,7 +660,7 @@ class TestHondaBoschCANFDSafetyBase(TestHondaBoschSafetyBase): RELAY_MALFUNCTION_ADDRS = {0: (0xE4, 0x33D)} def setUp(self): - self.packer = CANPackerPanda("honda_common_canfd_generated") + self.packer = CANPackerSafety("honda_common_canfd_generated") self.safety = libsafety_py.libsafety @@ -694,7 +694,7 @@ class TestHondaNidecHybridSafety(TestHondaNidecPcmSafety): BRAKE_SIG = "COMPUTER_BRAKE_HYBRID" def setUp(self): - self.packer = CANPackerPanda("honda_clarity_hybrid_2018_can_generated") + self.packer = CANPackerSafety("honda_clarity_hybrid_2018_can_generated") self.safety = libsafety_py.libsafety self.safety.set_current_safety_param_sp(HondaSafetyFlagsSP.NIDEC_HYBRID) self.safety.set_safety_hooks(CarParams.SafetyModel.hondaNidec, 0) diff --git a/opendbc/safety/tests/test_hyundai.py b/opendbc/safety/tests/test_hyundai.py index af4d13f8..00fec635 100755 --- a/opendbc/safety/tests/test_hyundai.py +++ b/opendbc/safety/tests/test_hyundai.py @@ -7,7 +7,7 @@ from opendbc.car.hyundai.values import HyundaiSafetyFlags from opendbc.car.structs import CarParams from opendbc.safety.tests.libsafety import libsafety_py import opendbc.safety.tests.common as common -from opendbc.safety.tests.common import CANPackerPanda +from opendbc.safety.tests.common import CANPackerSafety from opendbc.safety.tests.hyundai_common import HyundaiButtonBase, HyundaiLongitudinalBase from opendbc.sunnypilot.car.hyundai.values import HyundaiSafetyFlagsSP @@ -70,7 +70,7 @@ def checksum(msg): @parameterized_class(LDA_BUTTON) -class TestHyundaiSafety(HyundaiButtonBase, common.PandaCarSafetyTest, common.DriverTorqueSteeringSafetyTest, common.SteerRequestCutSafetyTest): +class TestHyundaiSafety(HyundaiButtonBase, common.CarSafetyTest, common.DriverTorqueSteeringSafetyTest, common.SteerRequestCutSafetyTest): TX_MSGS = [[0x340, 0], [0x4F1, 0], [0x485, 0]] STANDSTILL_THRESHOLD = 12 # 0.375 kph RELAY_MALFUNCTION_ADDRS = {0: (0x340, 0x485)} # LKAS11 @@ -102,7 +102,7 @@ class TestHyundaiSafety(HyundaiButtonBase, common.PandaCarSafetyTest, common.Dri raise unittest.SkipTest def setUp(self): - self.packer = CANPackerPanda("hyundai_kia_generic") + self.packer = CANPackerSafety("hyundai_kia_generic") self.safety = libsafety_py.libsafety self.safety.set_current_safety_param_sp(self.SAFETY_PARAM_SP) self.safety.set_safety_hooks(CarParams.SafetyModel.hyundai, 0) @@ -111,48 +111,48 @@ class TestHyundaiSafety(HyundaiButtonBase, common.PandaCarSafetyTest, common.Dri def _button_msg(self, buttons, main_button=0, bus=0): values = {"CF_Clu_CruiseSwState": buttons, "CF_Clu_CruiseSwMain": main_button, "CF_Clu_AliveCnt1": self.cnt_button} self.__class__.cnt_button += 1 - return self.packer.make_can_msg_panda("CLU11", bus, values) + return self.packer.make_can_msg_safety("CLU11", bus, values) def _user_gas_msg(self, gas): values = {"CF_Ems_AclAct": gas, "AliveCounter": self.cnt_gas % 4} self.__class__.cnt_gas += 1 - return self.packer.make_can_msg_panda("EMS16", 0, values, fix_checksum=checksum) + return self.packer.make_can_msg_safety("EMS16", 0, values, fix_checksum=checksum) def _user_brake_msg(self, brake): values = {"DriverOverride": 2 if brake else random.choice((0, 1, 3)), "AliveCounterTCS": self.cnt_brake % 8} self.__class__.cnt_brake += 1 - return self.packer.make_can_msg_panda("TCS13", 0, values, fix_checksum=checksum) + return self.packer.make_can_msg_safety("TCS13", 0, values, fix_checksum=checksum) def _speed_msg(self, speed): - # panda safety doesn't scale, so undo the scaling + # safety doesn't scale, so undo the scaling values = {"WHL_SPD_%s" % s: speed * 0.03125 for s in ["FL", "FR", "RL", "RR"]} values["WHL_SPD_AliveCounter_LSB"] = (self.cnt_speed % 16) & 0x3 values["WHL_SPD_AliveCounter_MSB"] = (self.cnt_speed % 16) >> 2 self.__class__.cnt_speed += 1 - return self.packer.make_can_msg_panda("WHL_SPD11", 0, values, fix_checksum=checksum) + return self.packer.make_can_msg_safety("WHL_SPD11", 0, values, fix_checksum=checksum) def _pcm_status_msg(self, enable): values = {"ACCMode": enable, "CR_VSM_Alive": self.cnt_cruise % 16} self.__class__.cnt_cruise += 1 - return self.packer.make_can_msg_panda("SCC12", self.SCC_BUS, values, fix_checksum=checksum) + return self.packer.make_can_msg_safety("SCC12", self.SCC_BUS, values, fix_checksum=checksum) def _torque_driver_msg(self, torque): values = {"CR_Mdps_StrColTq": torque} - return self.packer.make_can_msg_panda("MDPS12", 0, values) + return self.packer.make_can_msg_safety("MDPS12", 0, values) def _torque_cmd_msg(self, torque, steer_req=1): values = {"CR_Lkas_StrToqReq": torque, "CF_Lkas_ActToi": steer_req} - return self.packer.make_can_msg_panda("LKAS11", 0, values) + return self.packer.make_can_msg_safety("LKAS11", 0, values) def _acc_state_msg(self, enable): values = {"MainMode_ACC": enable} - return self.packer.make_can_msg_panda("SCC11", self.SCC_BUS, values) + return self.packer.make_can_msg_safety("SCC11", self.SCC_BUS, values) def _lkas_button_msg(self, enabled): if self.SAFETY_PARAM_SP & HyundaiSafetyFlagsSP.HAS_LDA_BUTTON: values = {"LDA_BTN": enabled} - return self.packer.make_can_msg_panda("BCM_PO_11", 0, values) + return self.packer.make_can_msg_safety("BCM_PO_11", 0, values) else: raise NotImplementedError @@ -218,7 +218,7 @@ class TestHyundaiSafetyAltLimits(TestHyundaiSafety): raise unittest.SkipTest def setUp(self): - self.packer = CANPackerPanda("hyundai_kia_generic") + self.packer = CANPackerSafety("hyundai_kia_generic") self.safety = libsafety_py.libsafety self.safety.set_current_safety_param_sp(self.SAFETY_PARAM_SP) self.safety.set_safety_hooks(CarParams.SafetyModel.hyundai, HyundaiSafetyFlags.ALT_LIMITS) @@ -238,7 +238,7 @@ class TestHyundaiSafetyAltLimits2(TestHyundaiSafety): raise unittest.SkipTest def setUp(self): - self.packer = CANPackerPanda("hyundai_kia_generic") + self.packer = CANPackerSafety("hyundai_kia_generic") self.safety = libsafety_py.libsafety self.safety.set_current_safety_param_sp(self.SAFETY_PARAM_SP) self.safety.set_safety_hooks(CarParams.SafetyModel.hyundai, HyundaiSafetyFlags.ALT_LIMITS_2) @@ -257,7 +257,7 @@ class TestHyundaiSafetyCameraSCC(TestHyundaiSafety): raise unittest.SkipTest def setUp(self): - self.packer = CANPackerPanda("hyundai_kia_generic") + self.packer = CANPackerSafety("hyundai_kia_generic") self.safety = libsafety_py.libsafety self.safety.set_current_safety_param_sp(self.SAFETY_PARAM_SP) self.safety.set_safety_hooks(CarParams.SafetyModel.hyundai, HyundaiSafetyFlags.CAMERA_SCC) @@ -284,7 +284,7 @@ class TestHyundaiSafetyFCEV(TestHyundaiSafety): raise unittest.SkipTest def setUp(self): - self.packer = CANPackerPanda("hyundai_kia_generic") + self.packer = CANPackerSafety("hyundai_kia_generic") self.safety = libsafety_py.libsafety self.safety.set_current_safety_param_sp(self.SAFETY_PARAM_SP) self.safety.set_safety_hooks(CarParams.SafetyModel.hyundai, HyundaiSafetyFlags.FCEV_GAS) @@ -292,12 +292,12 @@ class TestHyundaiSafetyFCEV(TestHyundaiSafety): def _user_gas_msg(self, gas): values = {"ACCELERATOR_PEDAL": gas} - return self.packer.make_can_msg_panda("FCEV_ACCELERATOR", 0, values) + return self.packer.make_can_msg_safety("FCEV_ACCELERATOR", 0, values) class TestHyundaiLegacySafety(TestHyundaiSafety): def setUp(self): - self.packer = CANPackerPanda("hyundai_kia_generic") + self.packer = CANPackerSafety("hyundai_kia_generic") self.safety = libsafety_py.libsafety self.safety.set_safety_hooks(CarParams.SafetyModel.hyundaiLegacy, 0) self.safety.init_tests() @@ -305,26 +305,26 @@ class TestHyundaiLegacySafety(TestHyundaiSafety): class TestHyundaiLegacySafetyEV(TestHyundaiSafety): def setUp(self): - self.packer = CANPackerPanda("hyundai_kia_generic") + self.packer = CANPackerSafety("hyundai_kia_generic") self.safety = libsafety_py.libsafety self.safety.set_safety_hooks(CarParams.SafetyModel.hyundaiLegacy, HyundaiSafetyFlags.EV_GAS) self.safety.init_tests() def _user_gas_msg(self, gas): values = {"Accel_Pedal_Pos": gas} - return self.packer.make_can_msg_panda("E_EMS11", 0, values, fix_checksum=checksum) + return self.packer.make_can_msg_safety("E_EMS11", 0, values, fix_checksum=checksum) class TestHyundaiLegacySafetyHEV(TestHyundaiSafety): def setUp(self): - self.packer = CANPackerPanda("hyundai_kia_generic") + self.packer = CANPackerSafety("hyundai_kia_generic") self.safety = libsafety_py.libsafety self.safety.set_safety_hooks(CarParams.SafetyModel.hyundaiLegacy, HyundaiSafetyFlags.HYBRID_GAS) self.safety.init_tests() def _user_gas_msg(self, gas): values = {"CR_Vcu_AccPedDep_Pos": gas} - return self.packer.make_can_msg_panda("E_EMS11", 0, values, fix_checksum=checksum) + return self.packer.make_can_msg_safety("E_EMS11", 0, values, fix_checksum=checksum) @parameterized_class(LDA_BUTTON) @@ -345,7 +345,7 @@ class TestHyundaiLongitudinalSafety(HyundaiLongitudinalBase, TestHyundaiSafety): raise unittest.SkipTest def setUp(self): - self.packer = CANPackerPanda("hyundai_kia_generic") + self.packer = CANPackerSafety("hyundai_kia_generic") self.safety = libsafety_py.libsafety self.safety.set_current_safety_param_sp(self.SAFETY_PARAM_SP) self.safety.set_safety_hooks(CarParams.SafetyModel.hyundai, HyundaiSafetyFlags.LONG) @@ -358,7 +358,7 @@ class TestHyundaiLongitudinalSafety(HyundaiLongitudinalBase, TestHyundaiSafety): "AEB_CmdAct": int(aeb_req), "CR_VSM_DecCmd": aeb_decel, } - return self.packer.make_can_msg_panda("SCC12", self.SCC_BUS, values) + return self.packer.make_can_msg_safety("SCC12", self.SCC_BUS, values) def _fca11_msg(self, idx=0, vsm_aeb_req=False, fca_aeb_req=False, aeb_decel=0): values = { @@ -368,11 +368,11 @@ class TestHyundaiLongitudinalSafety(HyundaiLongitudinalBase, TestHyundaiSafety): "CF_VSM_DecCmdAct": int(vsm_aeb_req), "FCA_CmdAct": int(fca_aeb_req), } - return self.packer.make_can_msg_panda("FCA11", 0, values) + return self.packer.make_can_msg_safety("FCA11", 0, values) def _tx_acc_state_msg(self, enable): values = {"MainMode_ACC": enable} - return self.packer.make_can_msg_panda("SCC11", 0, values) + return self.packer.make_can_msg_safety("SCC11", 0, values) def test_no_aeb_fca11(self): self.assertTrue(self._tx(self._fca11_msg())) @@ -393,7 +393,7 @@ class TestHyundaiLongitudinalSafetyCameraSCC(HyundaiLongitudinalBase, TestHyunda RELAY_MALFUNCTION_ADDRS = {0: (0x340, 0x485, 0x421, 0x420, 0x50A, 0x389)} # LKAS11, LFAHDA_MFC, SCC12, SCC11, SCC13, SCC14 def setUp(self): - self.packer = CANPackerPanda("hyundai_kia_generic") + self.packer = CANPackerSafety("hyundai_kia_generic") self.safety = libsafety_py.libsafety self.safety.set_current_safety_param_sp(HyundaiSafetyFlagsSP.HAS_LDA_BUTTON) self.safety.set_safety_hooks(CarParams.SafetyModel.hyundai, HyundaiSafetyFlags.LONG | HyundaiSafetyFlags.CAMERA_SCC) @@ -406,11 +406,11 @@ class TestHyundaiLongitudinalSafetyCameraSCC(HyundaiLongitudinalBase, TestHyunda "AEB_CmdAct": int(aeb_req), "CR_VSM_DecCmd": aeb_decel, } - return self.packer.make_can_msg_panda("SCC12", self.SCC_BUS, values) + return self.packer.make_can_msg_safety("SCC12", self.SCC_BUS, values) def _tx_acc_state_msg(self, enable): values = {"MainMode_ACC": enable} - return self.packer.make_can_msg_panda("SCC11", self.SCC_BUS, values) + return self.packer.make_can_msg_safety("SCC11", self.SCC_BUS, values) def test_no_aeb_scc12(self): self.assertTrue(self._tx(self._accel_msg(0))) @@ -433,7 +433,7 @@ class TestHyundaiSafetyFCEVLong(TestHyundaiLongitudinalSafety, TestHyundaiSafety raise unittest.SkipTest def setUp(self): - self.packer = CANPackerPanda("hyundai_kia_generic") + self.packer = CANPackerSafety("hyundai_kia_generic") self.safety = libsafety_py.libsafety self.safety.set_current_safety_param_sp(self.SAFETY_PARAM_SP) self.safety.set_safety_hooks(CarParams.SafetyModel.hyundai, HyundaiSafetyFlags.FCEV_GAS | HyundaiSafetyFlags.LONG) @@ -454,7 +454,7 @@ class TestHyundaiLongitudinalESCCSafety(HyundaiLongitudinalBase, TestHyundaiSafe raise unittest.SkipTest def setUp(self): - self.packer = CANPackerPanda("hyundai_kia_generic") + self.packer = CANPackerSafety("hyundai_kia_generic") self.safety = libsafety_py.libsafety self.safety.set_current_safety_param_sp(HyundaiSafetyFlagsSP.ESCC | self.SAFETY_PARAM_SP) self.safety.set_safety_hooks(CarParams.SafetyModel.hyundai, HyundaiSafetyFlags.LONG) @@ -465,11 +465,11 @@ class TestHyundaiLongitudinalESCCSafety(HyundaiLongitudinalBase, TestHyundaiSafe "aReqRaw": accel, "aReqValue": accel, } - return self.packer.make_can_msg_panda("SCC12", self.SCC_BUS, values) + return self.packer.make_can_msg_safety("SCC12", self.SCC_BUS, values) def _tx_acc_state_msg(self, enable): values = {"MainMode_ACC": enable} - return self.packer.make_can_msg_panda("SCC11", 0, values) + return self.packer.make_can_msg_safety("SCC11", 0, values) def test_tester_present_allowed(self): pass @@ -488,7 +488,7 @@ class TestHyundaiNonSCCSafety(TestHyundaiSafety): raise unittest.SkipTest def setUp(self): - self.packer = CANPackerPanda("hyundai_kia_generic") + self.packer = CANPackerSafety("hyundai_kia_generic") self.safety = libsafety_py.libsafety self.safety.set_current_safety_param_sp(HyundaiSafetyFlagsSP.NON_SCC | self.SAFETY_PARAM_SP) self.safety.set_safety_hooks(CarParams.SafetyModel.hyundai, 0) @@ -497,17 +497,17 @@ class TestHyundaiNonSCCSafety(TestHyundaiSafety): def _pcm_status_msg(self, enable): values = {"CRUISE_LAMP_S": enable, "AliveCounter": self.cnt_gas % 4} self.__class__.cnt_gas += 1 - return self.packer.make_can_msg_panda("EMS16", 0, values, fix_checksum=checksum) + return self.packer.make_can_msg_safety("EMS16", 0, values, fix_checksum=checksum) def _acc_state_msg(self, enable): values = {"CRUISE_LAMP_M": enable, "AliveCounter": self.cnt_gas % 4} self.__class__.cnt_gas += 1 - return self.packer.make_can_msg_panda("EMS16", 0, values, fix_checksum=checksum) + return self.packer.make_can_msg_safety("EMS16", 0, values, fix_checksum=checksum) def _user_gas_msg(self, gas: float, controls_allowed: bool = True): values = {"CF_Ems_AclAct": gas, "CRUISE_LAMP_M": 1, "CRUISE_LAMP_S": controls_allowed, "AliveCounter": self.cnt_gas % 4} self.__class__.cnt_gas += 1 - return self.packer.make_can_msg_panda("EMS16", 0, values, fix_checksum=checksum) + return self.packer.make_can_msg_safety("EMS16", 0, values, fix_checksum=checksum) def test_allow_engage_with_gas_pressed(self): self._rx(self._user_gas_msg(1, self.safety.get_controls_allowed())) @@ -544,7 +544,7 @@ class TestHyundaiNonSCCSafety_HEV_EV(TestHyundaiSafety): raise unittest.SkipTest def setUp(self): - self.packer = CANPackerPanda("hyundai_kia_generic") + self.packer = CANPackerSafety("hyundai_kia_generic") self.safety = libsafety_py.libsafety self.safety.set_current_safety_param_sp(HyundaiSafetyFlagsSP.NON_SCC | self.SAFETY_PARAM_SP) self.safety.set_safety_hooks(CarParams.SafetyModel.hyundai, self.SAFETY_PARAM) @@ -552,15 +552,15 @@ class TestHyundaiNonSCCSafety_HEV_EV(TestHyundaiSafety): def _pcm_status_msg(self, enable): values = {self.PCM_STATUS_MSG[1]: enable} - return self.packer.make_can_msg_panda(self.PCM_STATUS_MSG[0], 0, values) + return self.packer.make_can_msg_safety(self.PCM_STATUS_MSG[0], 0, values) def _acc_state_msg(self, enable): values = {self.ACC_STATE_MSG[1]: enable} - return self.packer.make_can_msg_panda(self.ACC_STATE_MSG[0], 0, values) + return self.packer.make_can_msg_safety(self.ACC_STATE_MSG[0], 0, values) def _user_gas_msg(self, gas): values = {self.GAS_MSG[1]: gas} - return self.packer.make_can_msg_panda(self.GAS_MSG[0], 0, values, fix_checksum=checksum) + return self.packer.make_can_msg_safety(self.GAS_MSG[0], 0, values, fix_checksum=checksum) if __name__ == "__main__": diff --git a/opendbc/safety/tests/test_hyundai_canfd.py b/opendbc/safety/tests/test_hyundai_canfd.py index 95f31921..2aa2edaf 100755 --- a/opendbc/safety/tests/test_hyundai_canfd.py +++ b/opendbc/safety/tests/test_hyundai_canfd.py @@ -6,7 +6,7 @@ from opendbc.car.hyundai.values import HyundaiSafetyFlags from opendbc.car.structs import CarParams from opendbc.safety.tests.libsafety import libsafety_py import opendbc.safety.tests.common as common -from opendbc.safety.tests.common import CANPackerPanda +from opendbc.safety.tests.common import CANPackerSafety from opendbc.safety.tests.hyundai_common import HyundaiButtonBase, HyundaiLongitudinalBase # All combinations of radar/camera-SCC and gas/hybrid/EV cars @@ -22,7 +22,7 @@ ALL_GAS_EV_HYBRID_COMBOS = [ ] -class TestHyundaiCanfdBase(HyundaiButtonBase, common.PandaCarSafetyTest, common.DriverTorqueSteeringSafetyTest, common.SteerRequestCutSafetyTest): +class TestHyundaiCanfdBase(HyundaiButtonBase, common.CarSafetyTest, common.DriverTorqueSteeringSafetyTest, common.SteerRequestCutSafetyTest): TX_MSGS = [[0x50, 0], [0x1CF, 1], [0x2A4, 0]] STANDSTILL_THRESHOLD = 12 # 0.375 kph @@ -50,27 +50,27 @@ class TestHyundaiCanfdBase(HyundaiButtonBase, common.PandaCarSafetyTest, common. def _torque_driver_msg(self, torque): values = {"STEERING_COL_TORQUE": torque} - return self.packer.make_can_msg_panda("MDPS", self.PT_BUS, values) + return self.packer.make_can_msg_safety("MDPS", self.PT_BUS, values) def _torque_cmd_msg(self, torque, steer_req=1): values = {"TORQUE_REQUEST": torque, "STEER_REQ": steer_req} - return self.packer.make_can_msg_panda(self.STEER_MSG, self.STEER_BUS, values) + return self.packer.make_can_msg_safety(self.STEER_MSG, self.STEER_BUS, values) def _speed_msg(self, speed): values = {f"WHL_Spd{pos}Val": speed * 0.03125 for pos in ["FL", "FR", "RL", "RR"]} - return self.packer.make_can_msg_panda("WHEEL_SPEEDS", self.PT_BUS, values) + return self.packer.make_can_msg_safety("WHEEL_SPEEDS", self.PT_BUS, values) def _user_brake_msg(self, brake): values = {"DriverBraking": brake} - return self.packer.make_can_msg_panda("TCS", self.PT_BUS, values) + return self.packer.make_can_msg_safety("TCS", self.PT_BUS, values) def _user_gas_msg(self, gas): values = {self.GAS_MSG[1]: gas} - return self.packer.make_can_msg_panda(self.GAS_MSG[0], self.PT_BUS, values) + return self.packer.make_can_msg_safety(self.GAS_MSG[0], self.PT_BUS, values) def _pcm_status_msg(self, enable): values = {"ACCMode": 1 if enable else 0} - return self.packer.make_can_msg_panda("SCC_CONTROL", self.SCC_BUS, values) + return self.packer.make_can_msg_safety("SCC_CONTROL", self.SCC_BUS, values) def _button_msg(self, buttons, main_button=0, bus=None): if bus is None: @@ -79,15 +79,15 @@ class TestHyundaiCanfdBase(HyundaiButtonBase, common.PandaCarSafetyTest, common. "CRUISE_BUTTONS": buttons, "ADAPTIVE_CRUISE_MAIN_BTN": main_button, } - return self.packer.make_can_msg_panda("CRUISE_BUTTONS", bus, values) + return self.packer.make_can_msg_safety("CRUISE_BUTTONS", bus, values) def _acc_state_msg(self, enable): values = {"MainMode_ACC": enable} - return self.packer.make_can_msg_panda("SCC_CONTROL", self.SCC_BUS, values) + return self.packer.make_can_msg_safety("SCC_CONTROL", self.SCC_BUS, values) def _lkas_button_msg(self, enabled): values = {"LDA_BTN": enabled} - return self.packer.make_can_msg_panda("CRUISE_BUTTONS", self.PT_BUS, values) + return self.packer.make_can_msg_safety("CRUISE_BUTTONS", self.PT_BUS, values) def _main_cruise_button_msg(self, enabled): return self._button_msg(0, enabled) @@ -112,7 +112,7 @@ class TestHyundaiCanfdLFASteeringBase(TestHyundaiCanfdBase): raise unittest.SkipTest def setUp(self): - self.packer = CANPackerPanda("hyundai_canfd_generated") + self.packer = CANPackerSafety("hyundai_canfd_generated") self.safety = libsafety_py.libsafety self.safety.set_safety_hooks(CarParams.SafetyModel.hyundaiCanfd, self.SAFETY_PARAM) self.safety.init_tests() @@ -128,7 +128,7 @@ class TestHyundaiCanfdLFASteeringAltButtonsBase(TestHyundaiCanfdLFASteeringBase) SAFETY_PARAM: int def setUp(self): - self.packer = CANPackerPanda("hyundai_canfd_generated") + self.packer = CANPackerSafety("hyundai_canfd_generated") self.safety = libsafety_py.libsafety self.safety.set_safety_hooks(CarParams.SafetyModel.hyundaiCanfd, HyundaiSafetyFlags.CANFD_ALT_BUTTONS | self.SAFETY_PARAM) self.safety.init_tests() @@ -138,15 +138,15 @@ class TestHyundaiCanfdLFASteeringAltButtonsBase(TestHyundaiCanfdLFASteeringBase) "CRUISE_BUTTONS": buttons, "ADAPTIVE_CRUISE_MAIN_BTN": main_button, } - return self.packer.make_can_msg_panda("CRUISE_BUTTONS_ALT", self.PT_BUS, values) + return self.packer.make_can_msg_safety("CRUISE_BUTTONS_ALT", self.PT_BUS, values) def _lkas_button_msg(self, enabled): values = {"LDA_BTN": enabled} - return self.packer.make_can_msg_panda("CRUISE_BUTTONS_ALT", self.PT_BUS, values) + return self.packer.make_can_msg_safety("CRUISE_BUTTONS_ALT", self.PT_BUS, values) def _acc_cancel_msg(self, cancel, accel=0): values = {"ACCMode": 4 if cancel else 0, "aReqRaw": accel, "aReqValue": accel} - return self.packer.make_can_msg_panda("SCC_CONTROL", self.PT_BUS, values) + return self.packer.make_can_msg_safety("SCC_CONTROL", self.PT_BUS, values) def test_button_sends(self): """ @@ -183,7 +183,7 @@ class TestHyundaiCanfdLKASteeringEV(TestHyundaiCanfdBase): GAS_MSG = ("ACCELERATOR", "ACCELERATOR_PEDAL") def setUp(self): - self.packer = CANPackerPanda("hyundai_canfd_generated") + self.packer = CANPackerSafety("hyundai_canfd_generated") self.safety = libsafety_py.libsafety self.safety.set_safety_hooks(CarParams.SafetyModel.hyundaiCanfd, HyundaiSafetyFlags.CANFD_LKA_STEERING | HyundaiSafetyFlags.EV_GAS) self.safety.init_tests() @@ -202,7 +202,7 @@ class TestHyundaiCanfdLKASteeringAltEV(TestHyundaiCanfdBase): GAS_MSG = ("ACCELERATOR", "ACCELERATOR_PEDAL") def setUp(self): - self.packer = CANPackerPanda("hyundai_canfd_generated") + self.packer = CANPackerSafety("hyundai_canfd_generated") self.safety = libsafety_py.libsafety self.safety.set_safety_hooks(CarParams.SafetyModel.hyundaiCanfd, HyundaiSafetyFlags.CANFD_LKA_STEERING | HyundaiSafetyFlags.EV_GAS | HyundaiSafetyFlags.CANFD_LKA_STEERING_ALT) @@ -224,7 +224,7 @@ class TestHyundaiCanfdLKASteeringLongEV(HyundaiLongitudinalBase, TestHyundaiCanf STEER_BUS = 1 def setUp(self): - self.packer = CANPackerPanda("hyundai_canfd_generated") + self.packer = CANPackerSafety("hyundai_canfd_generated") self.safety = libsafety_py.libsafety self.safety.set_safety_hooks(CarParams.SafetyModel.hyundaiCanfd, HyundaiSafetyFlags.CANFD_LKA_STEERING | HyundaiSafetyFlags.LONG | HyundaiSafetyFlags.EV_GAS) @@ -235,11 +235,11 @@ class TestHyundaiCanfdLKASteeringLongEV(HyundaiLongitudinalBase, TestHyundaiCanf "aReqRaw": accel, "aReqValue": accel, } - return self.packer.make_can_msg_panda("SCC_CONTROL", self.PT_BUS, values) + return self.packer.make_can_msg_safety("SCC_CONTROL", self.PT_BUS, values) def _tx_acc_state_msg(self, enable): values = {"MainMode_ACC": enable} - return self.packer.make_can_msg_panda("SCC_CONTROL", self.PT_BUS, values) + return self.packer.make_can_msg_safety("SCC_CONTROL", self.PT_BUS, values) # Tests longitudinal for ICE, hybrid, EV cars with LFA steering @@ -259,7 +259,7 @@ class TestHyundaiCanfdLFASteeringLongBase(HyundaiLongitudinalBase, TestHyundaiCa raise unittest.SkipTest def setUp(self): - self.packer = CANPackerPanda("hyundai_canfd_generated") + self.packer = CANPackerSafety("hyundai_canfd_generated") self.safety = libsafety_py.libsafety self.safety.set_safety_hooks(CarParams.SafetyModel.hyundaiCanfd, HyundaiSafetyFlags.LONG | self.SAFETY_PARAM) self.safety.init_tests() @@ -269,11 +269,11 @@ class TestHyundaiCanfdLFASteeringLongBase(HyundaiLongitudinalBase, TestHyundaiCa "aReqRaw": accel, "aReqValue": accel, } - return self.packer.make_can_msg_panda("SCC_CONTROL", self.PT_BUS, values) + return self.packer.make_can_msg_safety("SCC_CONTROL", self.PT_BUS, values) def _tx_acc_state_msg(self, enable): values = {"MainMode_ACC": enable} - return self.packer.make_can_msg_panda("SCC_CONTROL", self.PT_BUS, values) + return self.packer.make_can_msg_safety("SCC_CONTROL", self.PT_BUS, values) # no knockout def test_tester_present_allowed(self): @@ -298,7 +298,7 @@ class TestHyundaiCanfdLFASteeringLongAltButtons(TestHyundaiCanfdLFASteeringLongB raise unittest.SkipTest def setUp(self): - self.packer = CANPackerPanda("hyundai_canfd_generated") + self.packer = CANPackerSafety("hyundai_canfd_generated") self.safety = libsafety_py.libsafety self.safety.set_safety_hooks(CarParams.SafetyModel.hyundaiCanfd, HyundaiSafetyFlags.LONG | HyundaiSafetyFlags.CANFD_ALT_BUTTONS | self.SAFETY_PARAM) self.safety.init_tests() diff --git a/opendbc/safety/tests/test_mazda.py b/opendbc/safety/tests/test_mazda.py index a39b25b4..607edcbf 100755 --- a/opendbc/safety/tests/test_mazda.py +++ b/opendbc/safety/tests/test_mazda.py @@ -4,10 +4,10 @@ import unittest from opendbc.car.structs import CarParams from opendbc.safety.tests.libsafety import libsafety_py import opendbc.safety.tests.common as common -from opendbc.safety.tests.common import CANPackerPanda +from opendbc.safety.tests.common import CANPackerSafety -class TestMazdaSafety(common.PandaCarSafetyTest, common.DriverTorqueSteeringSafetyTest): +class TestMazdaSafety(common.CarSafetyTest, common.DriverTorqueSteeringSafetyTest): TX_MSGS = [[0x243, 0], [0x09d, 0], [0x440, 0]] STANDSTILL_THRESHOLD = .1 @@ -27,38 +27,38 @@ class TestMazdaSafety(common.PandaCarSafetyTest, common.DriverTorqueSteeringSafe NO_STEER_REQ_BIT = True def setUp(self): - self.packer = CANPackerPanda("mazda_2017") + self.packer = CANPackerSafety("mazda_2017") self.safety = libsafety_py.libsafety self.safety.set_safety_hooks(CarParams.SafetyModel.mazda, 0) self.safety.init_tests() def _torque_meas_msg(self, torque): values = {"STEER_TORQUE_MOTOR": torque} - return self.packer.make_can_msg_panda("STEER_TORQUE", 0, values) + return self.packer.make_can_msg_safety("STEER_TORQUE", 0, values) def _torque_driver_msg(self, torque): values = {"STEER_TORQUE_SENSOR": torque} - return self.packer.make_can_msg_panda("STEER_TORQUE", 0, values) + return self.packer.make_can_msg_safety("STEER_TORQUE", 0, values) def _torque_cmd_msg(self, torque, steer_req=1): values = {"LKAS_REQUEST": torque} - return self.packer.make_can_msg_panda("CAM_LKAS", 0, values) + return self.packer.make_can_msg_safety("CAM_LKAS", 0, values) def _speed_msg(self, speed): values = {"SPEED": speed} - return self.packer.make_can_msg_panda("ENGINE_DATA", 0, values) + return self.packer.make_can_msg_safety("ENGINE_DATA", 0, values) def _user_brake_msg(self, brake): values = {"BRAKE_ON": brake} - return self.packer.make_can_msg_panda("PEDALS", 0, values) + return self.packer.make_can_msg_safety("PEDALS", 0, values) def _user_gas_msg(self, gas): values = {"PEDAL_GAS": gas} - return self.packer.make_can_msg_panda("ENGINE_DATA", 0, values) + return self.packer.make_can_msg_safety("ENGINE_DATA", 0, values) def _pcm_status_msg(self, enable): values = {"CRZ_ACTIVE": enable} - return self.packer.make_can_msg_panda("CRZ_CTRL", 0, values) + return self.packer.make_can_msg_safety("CRZ_CTRL", 0, values) def _button_msg(self, resume=False, cancel=False): values = { @@ -67,7 +67,7 @@ class TestMazdaSafety(common.PandaCarSafetyTest, common.DriverTorqueSteeringSafe "RES": resume, "RES_INV": (resume + 1) % 2, } - return self.packer.make_can_msg_panda("CRZ_BTNS", 0, values) + return self.packer.make_can_msg_safety("CRZ_BTNS", 0, values) def test_buttons(self): # only cancel allows while controls not allowed diff --git a/opendbc/safety/tests/test_nissan.py b/opendbc/safety/tests/test_nissan.py index 13722888..a9d1b486 100755 --- a/opendbc/safety/tests/test_nissan.py +++ b/opendbc/safety/tests/test_nissan.py @@ -6,10 +6,10 @@ from opendbc.sunnypilot.car.nissan.values import NissanSafetyFlagsSP from opendbc.car.structs import CarParams from opendbc.safety.tests.libsafety import libsafety_py import opendbc.safety.tests.common as common -from opendbc.safety.tests.common import CANPackerPanda +from opendbc.safety.tests.common import CANPackerSafety -class TestNissanSafety(common.PandaCarSafetyTest, common.AngleSteeringSafetyTest): +class TestNissanSafety(common.CarSafetyTest, common.AngleSteeringSafetyTest): TX_MSGS = [[0x169, 0], [0x2b1, 0], [0x4cc, 0], [0x20b, 2], [0x280, 2]] GAS_PRESSED_THRESHOLD = 3 @@ -29,45 +29,45 @@ class TestNissanSafety(common.PandaCarSafetyTest, common.AngleSteeringSafetyTest ANGLE_RATE_DOWN = [5., 3.5, .4] # unwind limit def setUp(self): - self.packer = CANPackerPanda("nissan_x_trail_2017_generated") + self.packer = CANPackerSafety("nissan_x_trail_2017_generated") self.safety = libsafety_py.libsafety self.safety.set_safety_hooks(CarParams.SafetyModel.nissan, 0) self.safety.init_tests() def _angle_cmd_msg(self, angle: float, enabled: bool): values = {"DESIRED_ANGLE": angle, "LKA_ACTIVE": 1 if enabled else 0} - return self.packer.make_can_msg_panda("LKAS", 0, values) + return self.packer.make_can_msg_safety("LKAS", 0, values) def _angle_meas_msg(self, angle: float): values = {"STEER_ANGLE": angle} - return self.packer.make_can_msg_panda("STEER_ANGLE_SENSOR", self.EPS_BUS, values) + return self.packer.make_can_msg_safety("STEER_ANGLE_SENSOR", self.EPS_BUS, values) def _pcm_status_msg(self, enable): values = {"CRUISE_ENABLED": enable} - return self.packer.make_can_msg_panda("CRUISE_STATE", self.CRUISE_BUS, values) + return self.packer.make_can_msg_safety("CRUISE_STATE", self.CRUISE_BUS, values) def _speed_msg(self, speed): values = {"WHEEL_SPEED_%s" % s: speed * 3.6 for s in ["RR", "RL"]} - return self.packer.make_can_msg_panda("WHEEL_SPEEDS_REAR", self.EPS_BUS, values) + return self.packer.make_can_msg_safety("WHEEL_SPEEDS_REAR", self.EPS_BUS, values) def _user_brake_msg(self, brake): values = {"USER_BRAKE_PRESSED": brake} - return self.packer.make_can_msg_panda("DOORS_LIGHTS", self.EPS_BUS, values) + return self.packer.make_can_msg_safety("DOORS_LIGHTS", self.EPS_BUS, values) def _user_gas_msg(self, gas): values = {"GAS_PEDAL": gas} - return self.packer.make_can_msg_panda("GAS_PEDAL", self.EPS_BUS, values) + return self.packer.make_can_msg_safety("GAS_PEDAL", self.EPS_BUS, values) def _acc_state_msg(self, main_on): values = {"CRUISE_ON": main_on} - return self.packer.make_can_msg_panda("PRO_PILOT", self.ACC_MAIN_BUS, values) + return self.packer.make_can_msg_safety("PRO_PILOT", self.ACC_MAIN_BUS, values) def _acc_button_cmd(self, cancel=0, propilot=0, flw_dist=0, _set=0, res=0): no_button = not any([cancel, propilot, flw_dist, _set, res]) values = {"CANCEL_BUTTON": cancel, "PROPILOT_BUTTON": propilot, "FOLLOW_DISTANCE_BUTTON": flw_dist, "SET_BUTTON": _set, "RES_BUTTON": res, "NO_BUTTON_PRESSED": no_button} - return self.packer.make_can_msg_panda("CRUISE_THROTTLE", 2, values) + return self.packer.make_can_msg_safety("CRUISE_THROTTLE", 2, values) def test_acc_buttons(self): btns = [ @@ -94,7 +94,7 @@ class TestNissanSafetyAltEpsBus(TestNissanSafety): ACC_MAIN_BUS = 2 def setUp(self): - self.packer = CANPackerPanda("nissan_x_trail_2017_generated") + self.packer = CANPackerSafety("nissan_x_trail_2017_generated") self.safety = libsafety_py.libsafety self.safety.set_safety_hooks(CarParams.SafetyModel.nissan, NissanSafetyFlags.ALT_EPS_BUS) self.safety.init_tests() @@ -103,7 +103,7 @@ class TestNissanSafetyAltEpsBus(TestNissanSafety): class TestNissanLeafSafety(TestNissanSafety): def setUp(self): - self.packer = CANPackerPanda("nissan_leaf_2018_generated") + self.packer = CANPackerSafety("nissan_leaf_2018_generated") self.safety = libsafety_py.libsafety self.safety.set_current_safety_param_sp(NissanSafetyFlagsSP.LEAF) self.safety.set_safety_hooks(CarParams.SafetyModel.nissan, 0) @@ -111,15 +111,15 @@ class TestNissanLeafSafety(TestNissanSafety): def _user_brake_msg(self, brake): values = {"USER_BRAKE_PRESSED": brake} - return self.packer.make_can_msg_panda("CRUISE_THROTTLE", 0, values) + return self.packer.make_can_msg_safety("CRUISE_THROTTLE", 0, values) def _user_gas_msg(self, gas): values = {"GAS_PEDAL": gas} - return self.packer.make_can_msg_panda("CRUISE_THROTTLE", 0, values) + return self.packer.make_can_msg_safety("CRUISE_THROTTLE", 0, values) def _acc_state_msg(self, main_on): values = {"CRUISE_AVAILABLE": main_on} - return self.packer.make_can_msg_panda("CRUISE_THROTTLE", 0, values) + return self.packer.make_can_msg_safety("CRUISE_THROTTLE", 0, values) # TODO: leaf should use its own safety param def test_acc_buttons(self): diff --git a/opendbc/safety/tests/test_psa.py b/opendbc/safety/tests/test_psa.py index 268e7f4f..ac456663 100644 --- a/opendbc/safety/tests/test_psa.py +++ b/opendbc/safety/tests/test_psa.py @@ -4,12 +4,12 @@ import unittest from opendbc.car.structs import CarParams from opendbc.safety.tests.libsafety import libsafety_py import opendbc.safety.tests.common as common -from opendbc.safety.tests.common import CANPackerPanda +from opendbc.safety.tests.common import CANPackerSafety LANE_KEEP_ASSIST = 0x3F2 -class TestPsaSafetyBase(common.PandaCarSafetyTest, common.AngleSteeringSafetyTest): +class TestPsaSafetyBase(common.CarSafetyTest, common.AngleSteeringSafetyTest): RELAY_MALFUNCTION_ADDRS = {0: (LANE_KEEP_ASSIST,)} FWD_BLACKLISTED_ADDRS = {2: [LANE_KEEP_ASSIST]} TX_MSGS = [[1010, 0]] @@ -26,34 +26,34 @@ class TestPsaSafetyBase(common.PandaCarSafetyTest, common.AngleSteeringSafetyTes ANGLE_RATE_DOWN = [5., 2., .3] def setUp(self): - self.packer = CANPackerPanda("psa_aee2010_r3") + self.packer = CANPackerSafety("psa_aee2010_r3") self.safety = libsafety_py.libsafety self.safety.set_safety_hooks(CarParams.SafetyModel.psa, 0) self.safety.init_tests() def _angle_cmd_msg(self, angle: float, enabled: bool): values = {"SET_ANGLE": angle, "TORQUE_FACTOR": 100 if enabled else 0} - return self.packer.make_can_msg_panda("LANE_KEEP_ASSIST", self.MAIN_BUS, values) + return self.packer.make_can_msg_safety("LANE_KEEP_ASSIST", self.MAIN_BUS, values) def _angle_meas_msg(self, angle: float): values = {"ANGLE": angle} - return self.packer.make_can_msg_panda("STEERING_ALT", self.MAIN_BUS, values) + return self.packer.make_can_msg_safety("STEERING_ALT", self.MAIN_BUS, values) def _pcm_status_msg(self, enable): values = {"RVV_ACC_ACTIVATION_REQ": enable} - return self.packer.make_can_msg_panda("HS2_DAT_MDD_CMD_452", self.ADAS_BUS, values) + return self.packer.make_can_msg_safety("HS2_DAT_MDD_CMD_452", self.ADAS_BUS, values) def _speed_msg(self, speed): values = {"VITESSE_VEHICULE_ROUES": speed * 3.6} - return self.packer.make_can_msg_panda("HS2_DYN_ABR_38D", self.MAIN_BUS, values) + return self.packer.make_can_msg_safety("HS2_DYN_ABR_38D", self.MAIN_BUS, values) def _user_brake_msg(self, brake): values = {"P013_MainBrake": brake} - return self.packer.make_can_msg_panda("Dat_BSI", self.CAM_BUS, values) + return self.packer.make_can_msg_safety("Dat_BSI", self.CAM_BUS, values) def _user_gas_msg(self, gas): values = {"P002_Com_rAPP": int(gas * 100)} - return self.packer.make_can_msg_panda("Dyn_CMM", self.MAIN_BUS, values) + return self.packer.make_can_msg_safety("Dyn_CMM", self.MAIN_BUS, values) def test_rx_hook(self): # speed @@ -80,7 +80,7 @@ class TestPsaSafetyBase(common.PandaCarSafetyTest, common.AngleSteeringSafetyTes class TestPsaStockSafety(TestPsaSafetyBase): def setUp(self): - self.packer = CANPackerPanda("psa_aee2010_r3") + self.packer = CANPackerSafety("psa_aee2010_r3") self.safety = libsafety_py.libsafety self.safety.set_safety_hooks(CarParams.SafetyModel.psa, 0) self.safety.init_tests() diff --git a/opendbc/safety/tests/test_rivian.py b/opendbc/safety/tests/test_rivian.py index f41d3aa5..f1393e60 100755 --- a/opendbc/safety/tests/test_rivian.py +++ b/opendbc/safety/tests/test_rivian.py @@ -4,7 +4,7 @@ import unittest from opendbc.car.structs import CarParams from opendbc.safety.tests.libsafety import libsafety_py import opendbc.safety.tests.common as common -from opendbc.safety.tests.common import CANPackerPanda +from opendbc.safety.tests.common import CANPackerSafety from opendbc.car.rivian.values import RivianSafetyFlags from opendbc.car.rivian.riviancan import checksum as _checksum @@ -22,7 +22,7 @@ def checksum(msg): return addr, ret, bus -class TestRivianSafetyBase(common.PandaCarSafetyTest, common.DriverTorqueSteeringSafetyTest, common.LongitudinalAccelSafetyTest, +class TestRivianSafetyBase(common.CarSafetyTest, common.DriverTorqueSteeringSafetyTest, common.LongitudinalAccelSafetyTest, common.VehicleSpeedSafetyTest): TX_MSGS = [[0x120, 0], [0x321, 2], [0x162, 2]] @@ -44,17 +44,17 @@ class TestRivianSafetyBase(common.PandaCarSafetyTest, common.DriverTorqueSteerin def _torque_driver_msg(self, torque): values = {"EPAS_TorsionBarTorque": torque / 100.0} - return self.packer.make_can_msg_panda("EPAS_SystemStatus", 0, values) + return self.packer.make_can_msg_safety("EPAS_SystemStatus", 0, values) def _torque_cmd_msg(self, torque, steer_req=1): values = {"ACM_lkaStrToqReq": torque, "ACM_lkaActToi": steer_req} - return self.packer.make_can_msg_panda("ACM_lkaHbaCmd", 0, values) + return self.packer.make_can_msg_safety("ACM_lkaHbaCmd", 0, values) def _speed_msg(self, speed, quality_flag=True): values = {"ESP_Vehicle_Speed": speed * 3.6, "ESP_Status_Counter": self.cnt_speed % 15, "ESP_Vehicle_Speed_Q": 1 if quality_flag else 0} self.__class__.cnt_speed += 1 - return self.packer.make_can_msg_panda("ESP_Status", 0, values, fix_checksum=checksum) + return self.packer.make_can_msg_safety("ESP_Status", 0, values, fix_checksum=checksum) def _speed_msg_2(self, speed, quality_flag=True): # Rivian has a dynamic max torque limit based on speed, so it checks two sources @@ -62,21 +62,21 @@ class TestRivianSafetyBase(common.PandaCarSafetyTest, common.DriverTorqueSteerin def _user_brake_msg(self, brake): values = {"iBESP2_BrakePedalApplied": brake} - return self.packer.make_can_msg_panda("iBESP2", 0, values) + return self.packer.make_can_msg_safety("iBESP2", 0, values) def _user_gas_msg(self, gas, speed=0, quality_flag=True): values = {"VDM_AcceleratorPedalPosition": gas, "VDM_VehicleSpeed": speed * 3.6, "VDM_PropStatus_Counter": self.cnt_speed_2 % 15, "VDM_VehicleSpeedQ": 1 if quality_flag else 0} self.__class__.cnt_speed_2 += 1 - return self.packer.make_can_msg_panda("VDM_PropStatus", 0, values, fix_checksum=checksum) + return self.packer.make_can_msg_safety("VDM_PropStatus", 0, values, fix_checksum=checksum) def _pcm_status_msg(self, enable): values = {"ACM_FeatureStatus": enable, "ACM_Unkown1": 1} - return self.packer.make_can_msg_panda("ACM_Status", 2, values) + return self.packer.make_can_msg_safety("ACM_Status", 2, values) def _accel_msg(self, accel: float): values = {"ACM_AccelerationRequest": accel} - return self.packer.make_can_msg_panda("ACM_longitudinalRequest", 0, values) + return self.packer.make_can_msg_safety("ACM_longitudinalRequest", 0, values) def test_wheel_touch(self): # For hiding hold wheel alert on engage @@ -87,7 +87,7 @@ class TestRivianSafetyBase(common.PandaCarSafetyTest, common.DriverTorqueSteerin "SCCM_WheelTouch_CapacitiveValue": 100 if controls_allowed else 0, "SETME_X52": 100, } - self.assertTrue(self._tx(self.packer.make_can_msg_panda("SCCM_WheelTouch", 2, values))) + self.assertTrue(self._tx(self.packer.make_can_msg_safety("SCCM_WheelTouch", 2, values))) def test_rx_hook(self): # checksum, counter, and quality flag checks @@ -115,7 +115,7 @@ class TestRivianStockSafety(TestRivianSafetyBase): LONGITUDINAL = False def setUp(self): - self.packer = CANPackerPanda("rivian_primary_actuator") + self.packer = CANPackerSafety("rivian_primary_actuator") self.safety = libsafety_py.libsafety self.safety.set_safety_hooks(CarParams.SafetyModel.rivian, 0) self.safety.init_tests() @@ -126,7 +126,7 @@ class TestRivianStockSafety(TestRivianSafetyBase): self.safety.set_controls_allowed(controls_allowed) for interface_status in range(4): values = {"VDM_AdasInterfaceStatus": interface_status} - self.assertTrue(self._tx(self.packer.make_can_msg_panda("VDM_AdasSts", 2, values))) + self.assertTrue(self._tx(self.packer.make_can_msg_safety("VDM_AdasSts", 2, values))) class TestRivianLongitudinalSafety(TestRivianSafetyBase): @@ -136,7 +136,7 @@ class TestRivianLongitudinalSafety(TestRivianSafetyBase): FWD_BLACKLISTED_ADDRS = {0: [0x321], 2: [0x120, 0x160]} def setUp(self): - self.packer = CANPackerPanda("rivian_primary_actuator") + self.packer = CANPackerSafety("rivian_primary_actuator") self.safety = libsafety_py.libsafety self.safety.set_safety_hooks(CarParams.SafetyModel.rivian, RivianSafetyFlags.LONG_CONTROL) self.safety.init_tests() diff --git a/opendbc/safety/tests/test_subaru.py b/opendbc/safety/tests/test_subaru.py index 6143a041..5c1b335a 100755 --- a/opendbc/safety/tests/test_subaru.py +++ b/opendbc/safety/tests/test_subaru.py @@ -6,7 +6,7 @@ from opendbc.car.subaru.values import SubaruSafetyFlags from opendbc.car.structs import CarParams from opendbc.safety.tests.libsafety import libsafety_py import opendbc.safety.tests.common as common -from opendbc.safety.tests.common import CANPackerPanda +from opendbc.safety.tests.common import CANPackerSafety from functools import partial @@ -59,7 +59,7 @@ def fwd_blacklisted_addr(lkas_msg=SubaruMsg.ES_LKAS): return {SUBARU_CAM_BUS: [lkas_msg, SubaruMsg.ES_DashStatus, SubaruMsg.ES_LKAS_State, SubaruMsg.ES_Infotainment]} -class TestSubaruSafetyBase(common.PandaCarSafetyTest): +class TestSubaruSafetyBase(common.CarSafetyTest): FLAGS = 0 RELAY_MALFUNCTION_ADDRS = {SUBARU_MAIN_BUS: (SubaruMsg.ES_LKAS, SubaruMsg.ES_DashStatus, SubaruMsg.ES_LKAS_State, SubaruMsg.ES_Infotainment)} @@ -78,7 +78,7 @@ class TestSubaruSafetyBase(common.PandaCarSafetyTest): INACTIVE_GAS = 1818 def setUp(self): - self.packer = CANPackerPanda("subaru_global_2017_generated") + self.packer = CANPackerSafety("subaru_global_2017_generated") self.safety = libsafety_py.libsafety self.safety.set_safety_hooks(CarParams.SafetyModel.subaru, self.FLAGS) self.safety.init_tests() @@ -89,31 +89,31 @@ class TestSubaruSafetyBase(common.PandaCarSafetyTest): def _torque_driver_msg(self, torque): values = {"Steer_Torque_Sensor": torque} - return self.packer.make_can_msg_panda("Steering_Torque", 0, values) + return self.packer.make_can_msg_safety("Steering_Torque", 0, values) def _speed_msg(self, speed): values = {s: speed for s in ["FR", "FL", "RR", "RL"]} - return self.packer.make_can_msg_panda("Wheel_Speeds", self.ALT_MAIN_BUS, values) + return self.packer.make_can_msg_safety("Wheel_Speeds", self.ALT_MAIN_BUS, values) def _angle_meas_msg(self, angle): values = {"Steering_Angle": angle} - return self.packer.make_can_msg_panda("Steering_Torque", 0, values) + return self.packer.make_can_msg_safety("Steering_Torque", 0, values) def _user_brake_msg(self, brake): values = {"Brake": brake} - return self.packer.make_can_msg_panda("Brake_Status", self.ALT_MAIN_BUS, values) + return self.packer.make_can_msg_safety("Brake_Status", self.ALT_MAIN_BUS, values) def _user_gas_msg(self, gas): values = {"Throttle_Pedal": gas} - return self.packer.make_can_msg_panda("Throttle", 0, values) + return self.packer.make_can_msg_safety("Throttle", 0, values) def _pcm_status_msg(self, enable): values = {"Cruise_Activated": enable} - return self.packer.make_can_msg_panda("CruiseControl", self.ALT_MAIN_BUS, values) + return self.packer.make_can_msg_safety("CruiseControl", self.ALT_MAIN_BUS, values) def _lkas_button_msg(self, lkas_pressed=False, lkas_hud=0): values = {"LKAS_Dash_State": 2 if lkas_pressed else lkas_hud} - return self.packer.make_can_msg_panda("ES_LKAS_State", SUBARU_CAM_BUS, values) + return self.packer.make_can_msg_safety("ES_LKAS_State", SUBARU_CAM_BUS, values) def test_enable_control_allowed_with_mads_button(self): for enable_mads in (True, False): @@ -130,7 +130,7 @@ class TestSubaruSafetyBase(common.PandaCarSafetyTest): class TestSubaruStockLongitudinalSafetyBase(TestSubaruSafetyBase): def _cancel_msg(self, cancel, cruise_throttle=0): values = {"Cruise_Cancel": cancel, "Cruise_Throttle": cruise_throttle} - return self.packer.make_can_msg_panda("ES_Distance", self.ALT_MAIN_BUS, values) + return self.packer.make_can_msg_safety("ES_Distance", self.ALT_MAIN_BUS, values) def test_cancel_message(self): # test that we can only send the cancel message (ES_Distance) with inactive throttle (1818) and Cruise_Cancel=1 @@ -161,15 +161,15 @@ class TestSubaruLongitudinalSafetyBase(TestSubaruSafetyBase, common.Longitudinal def _send_brake_msg(self, brake): values = {"Brake_Pressure": brake} - return self.packer.make_can_msg_panda("ES_Brake", self.ALT_MAIN_BUS, values) + return self.packer.make_can_msg_safety("ES_Brake", self.ALT_MAIN_BUS, values) def _send_gas_msg(self, gas): values = {"Cruise_Throttle": gas} - return self.packer.make_can_msg_panda("ES_Distance", self.ALT_MAIN_BUS, values) + return self.packer.make_can_msg_safety("ES_Distance", self.ALT_MAIN_BUS, values) def _send_rpm_msg(self, rpm): values = {"Cruise_RPM": rpm} - return self.packer.make_can_msg_panda("ES_Status", self.ALT_MAIN_BUS, values) + return self.packer.make_can_msg_safety("ES_Status", self.ALT_MAIN_BUS, values) class TestSubaruTorqueSafetyBase(TestSubaruSafetyBase, common.DriverTorqueSteeringSafetyTest, common.SteerRequestCutSafetyTest): @@ -184,7 +184,7 @@ class TestSubaruTorqueSafetyBase(TestSubaruSafetyBase, common.DriverTorqueSteeri def _torque_cmd_msg(self, torque, steer_req=1): values = {"LKAS_Output": torque, "LKAS_Request": steer_req} - return self.packer.make_can_msg_panda("ES_LKAS", SUBARU_MAIN_BUS, values) + return self.packer.make_can_msg_safety("ES_LKAS", SUBARU_MAIN_BUS, values) class TestSubaruGen1TorqueStockLongitudinalSafety(TestSubaruStockLongitudinalSafetyBase, TestSubaruTorqueSafetyBase): diff --git a/opendbc/safety/tests/test_subaru_preglobal.py b/opendbc/safety/tests/test_subaru_preglobal.py index 44aef081..fb96de24 100755 --- a/opendbc/safety/tests/test_subaru_preglobal.py +++ b/opendbc/safety/tests/test_subaru_preglobal.py @@ -5,10 +5,10 @@ from opendbc.car.structs import CarParams from opendbc.car.subaru.values import SubaruSafetyFlags from opendbc.safety.tests.libsafety import libsafety_py import opendbc.safety.tests.common as common -from opendbc.safety.tests.common import CANPackerPanda +from opendbc.safety.tests.common import CANPackerSafety -class TestSubaruPreglobalSafety(common.PandaCarSafetyTest, common.DriverTorqueSteeringSafetyTest): +class TestSubaruPreglobalSafety(common.CarSafetyTest, common.DriverTorqueSteeringSafetyTest): FLAGS = 0 DBC = "subaru_outback_2015_generated" TX_MSGS = [[0x161, 0], [0x164, 0]] @@ -25,7 +25,7 @@ class TestSubaruPreglobalSafety(common.PandaCarSafetyTest, common.DriverTorqueSt DRIVER_TORQUE_FACTOR = 10 def setUp(self): - self.packer = CANPackerPanda(self.DBC) + self.packer = CANPackerSafety(self.DBC) self.safety = libsafety_py.libsafety self.safety.set_safety_hooks(CarParams.SafetyModel.subaruPreglobal, self.FLAGS) self.safety.init_tests() @@ -36,28 +36,28 @@ class TestSubaruPreglobalSafety(common.PandaCarSafetyTest, common.DriverTorqueSt def _torque_driver_msg(self, torque): values = {"Steer_Torque_Sensor": torque} - return self.packer.make_can_msg_panda("Steering_Torque", 0, values) + return self.packer.make_can_msg_safety("Steering_Torque", 0, values) def _speed_msg(self, speed): # subaru safety doesn't use the scaled value, so undo the scaling values = {s: speed*0.0592 for s in ["FR", "FL", "RR", "RL"]} - return self.packer.make_can_msg_panda("Wheel_Speeds", 0, values) + return self.packer.make_can_msg_safety("Wheel_Speeds", 0, values) def _user_brake_msg(self, brake): values = {"Brake_Pedal": brake} - return self.packer.make_can_msg_panda("Brake_Pedal", 0, values) + return self.packer.make_can_msg_safety("Brake_Pedal", 0, values) def _torque_cmd_msg(self, torque, steer_req=1): values = {"LKAS_Command": torque, "LKAS_Active": steer_req} - return self.packer.make_can_msg_panda("ES_LKAS", 0, values) + return self.packer.make_can_msg_safety("ES_LKAS", 0, values) def _user_gas_msg(self, gas): values = {"Throttle_Pedal": gas} - return self.packer.make_can_msg_panda("Throttle", 0, values) + return self.packer.make_can_msg_safety("Throttle", 0, values) def _pcm_status_msg(self, enable): values = {"Cruise_Activated": enable} - return self.packer.make_can_msg_panda("CruiseControl", 0, values) + return self.packer.make_can_msg_safety("CruiseControl", 0, values) class TestSubaruPreglobalReversedDriverTorqueSafety(TestSubaruPreglobalSafety): diff --git a/opendbc/safety/tests/test_tesla.py b/opendbc/safety/tests/test_tesla.py index 585c2145..cc99d80b 100755 --- a/opendbc/safety/tests/test_tesla.py +++ b/opendbc/safety/tests/test_tesla.py @@ -11,7 +11,7 @@ from opendbc.car.vehicle_model import VehicleModel from opendbc.can import CANDefine from opendbc.safety.tests.libsafety import libsafety_py import opendbc.safety.tests.common as common -from opendbc.safety.tests.common import CANPackerPanda, MAX_SPEED_DELTA, MAX_WRONG_COUNTERS, away_round, round_speed +from opendbc.safety.tests.common import CANPackerSafety, MAX_SPEED_DELTA, MAX_WRONG_COUNTERS, away_round, round_speed from opendbc.sunnypilot.car.tesla.values import TeslaSafetyFlagsSP @@ -27,7 +27,7 @@ def round_angle(apply_angle, can_offset=0): return away_round(apply_angle_can + rnd_offset) * 0.1 - 1638.35 -class TestTeslaSafetyBase(common.PandaCarSafetyTest, common.AngleSteeringSafetyTest, common.LongitudinalAccelSafetyTest): +class TestTeslaSafetyBase(common.CarSafetyTest, common.AngleSteeringSafetyTest, common.LongitudinalAccelSafetyTest): RELAY_MALFUNCTION_ADDRS = {0: (MSG_DAS_steeringControl, MSG_APS_eacMonitor)} FWD_BLACKLISTED_ADDRS = {2: [MSG_DAS_steeringControl, MSG_APS_eacMonitor]} TX_MSGS = [[MSG_DAS_steeringControl, 0], [MSG_APS_eacMonitor, 0], [MSG_DAS_Control, 0]] @@ -56,14 +56,14 @@ class TestTeslaSafetyBase(common.PandaCarSafetyTest, common.AngleSteeringSafetyT cnt_epas = 0 cnt_angle_cmd = 0 - packer: CANPackerPanda + packer: CANPackerSafety def _get_steer_cmd_angle_max(self, speed): return get_max_angle_vm(max(speed, 1), self.VM, CarControllerParams) def setUp(self): self.VM = VehicleModel(get_safety_CP()) - self.packer = CANPackerPanda("tesla_model3_party") + self.packer = CANPackerSafety("tesla_model3_party") self.define = CANDefine("tesla_model3_party") self.acc_states = {d: v for v, d in self.define.dv["DAS_control"]["DAS_accState"].items()} self.autopark_states = {d: v for v, d in self.define.dv["DI_state"]["DI_autoparkState"].items()} @@ -76,44 +76,44 @@ class TestTeslaSafetyBase(common.PandaCarSafetyTest, common.AngleSteeringSafetyT if increment_timer: self.safety.set_timer(self.cnt_angle_cmd * int(1e6 / self.LATERAL_FREQUENCY)) self.__class__.cnt_angle_cmd += 1 - return self.packer.make_can_msg_panda("DAS_steeringControl", bus, values) + return self.packer.make_can_msg_safety("DAS_steeringControl", bus, values) def _angle_meas_msg(self, angle: float, hands_on_level: int = 0, eac_status: int = 1, eac_error_code: int = 0): values = {"EPAS3S_internalSAS": angle, "EPAS3S_handsOnLevel": hands_on_level, "EPAS3S_eacStatus": eac_status, "EPAS3S_eacErrorCode": eac_error_code, "EPAS3S_sysStatusCounter": self.cnt_epas % 16} self.__class__.cnt_epas += 1 - return self.packer.make_can_msg_panda("EPAS3S_sysStatus", 0, values) + return self.packer.make_can_msg_safety("EPAS3S_sysStatus", 0, values) def _user_brake_msg(self, brake, quality_flag: bool = True): values = {"IBST_driverBrakeApply": 2 if brake else 1} if not quality_flag: values["IBST_driverBrakeApply"] = random.choice((0, 3)) # NOT_INIT_OR_OFF, FAULT - return self.packer.make_can_msg_panda("IBST_status", 0, values) + return self.packer.make_can_msg_safety("IBST_status", 0, values) def _speed_msg(self, speed): values = {"DI_vehicleSpeed": speed * 3.6} - return self.packer.make_can_msg_panda("DI_speed", 0, values) + return self.packer.make_can_msg_safety("DI_speed", 0, values) def _speed_msg_2(self, speed, quality_flag=True): values = {"ESP_vehicleSpeed": speed * 3.6, "ESP_wheelSpeedsQF": quality_flag} - return self.packer.make_can_msg_panda("ESP_B", 0, values) + return self.packer.make_can_msg_safety("ESP_B", 0, values) def _vehicle_moving_msg(self, speed: float, quality_flag=True): values = {"ESP_vehicleStandstillSts": 1 if speed <= self.STANDSTILL_THRESHOLD else 0, "ESP_wheelSpeedsQF": quality_flag} - return self.packer.make_can_msg_panda("ESP_B", 0, values) + return self.packer.make_can_msg_safety("ESP_B", 0, values) def _user_gas_msg(self, gas): values = {"DI_accelPedalPos": gas} - return self.packer.make_can_msg_panda("DI_systemStatus", 0, values) + return self.packer.make_can_msg_safety("DI_systemStatus", 0, values) def _pcm_status_msg(self, enable, autopark_state=0): values = { "DI_cruiseState": 2 if enable else 0, "DI_autoparkState": autopark_state, } - return self.packer.make_can_msg_panda("DI_state", 0, values) + return self.packer.make_can_msg_safety("DI_state", 0, values) def _long_control_msg(self, set_speed, acc_state=0, jerk_limits=(0, 0), accel_limits=(0, 0), aeb_event=0, bus=0): values = { @@ -125,7 +125,7 @@ class TestTeslaSafetyBase(common.PandaCarSafetyTest, common.AngleSteeringSafetyT "DAS_accelMin": accel_limits[0], "DAS_accelMax": accel_limits[1], } - return self.packer.make_can_msg_panda("DAS_control", bus, values) + return self.packer.make_can_msg_safety("DAS_control", bus, values) def _accel_msg(self, accel: float): # For common.LongitudinalAccelSafetyTest @@ -457,14 +457,14 @@ class TestTeslaVehicleBusSafety(TestTeslaSafetyBase): def setUp(self): super().setUp() self.safety = libsafety_py.libsafety - self.packer_adas = CANPackerPanda("tesla_model3_vehicle") + self.packer_adas = CANPackerSafety("tesla_model3_vehicle") self.safety.set_current_safety_param_sp(TeslaSafetyFlagsSP.HAS_VEHICLE_BUS) self.safety.set_safety_hooks(CarParams.SafetyModel.tesla, 0) self.safety.init_tests() def _lkas_button_msg(self, enabled): values = {"UI_activeTouchPoints": 3 if enabled else 0} - return self.packer_adas.make_can_msg_panda("UI_status2", CANBUS.vehicle, values) + return self.packer_adas.make_can_msg_safety("UI_status2", CANBUS.vehicle, values) if __name__ == "__main__": diff --git a/opendbc/safety/tests/test_toyota.py b/opendbc/safety/tests/test_toyota.py index fc7f32ae..ceee0dce 100755 --- a/opendbc/safety/tests/test_toyota.py +++ b/opendbc/safety/tests/test_toyota.py @@ -11,7 +11,7 @@ from opendbc.car.structs import CarParams from opendbc.safety import ALTERNATIVE_EXPERIENCE from opendbc.safety.tests.libsafety import libsafety_py import opendbc.safety.tests.common as common -from opendbc.safety.tests.common import CANPackerPanda +from opendbc.safety.tests.common import CANPackerSafety from opendbc.safety.tests.gas_interceptor_common import GasInterceptorSafetyTest TOYOTA_COMMON_TX_MSGS = [[0x2E4, 0], [0x191, 0], [0x412, 0], [0x343, 0], [0x1D2, 0]] # LKAS + LTA + ACC & PCM cancel cmds @@ -28,7 +28,7 @@ UNSUPPORTED_DSU = [ ] -class TestToyotaSafetyBase(common.PandaCarSafetyTest, common.LongitudinalAccelSafetyTest): +class TestToyotaSafetyBase(common.CarSafetyTest, common.LongitudinalAccelSafetyTest): TX_MSGS = TOYOTA_COMMON_TX_MSGS + TOYOTA_COMMON_LONG_TX_MSGS RELAY_MALFUNCTION_ADDRS = {0: (0x2E4, 0x191, 0x412, 0x343)} @@ -37,58 +37,61 @@ class TestToyotaSafetyBase(common.PandaCarSafetyTest, common.LongitudinalAccelSa SAFETY_PARAM_SP: int = 0 - packer: CANPackerPanda - safety: libsafety_py.Panda + packer: CANPackerSafety + safety: libsafety_py.LibSafety def _torque_meas_msg(self, torque: int, driver_torque: int | None = None): values = {"STEER_TORQUE_EPS": (torque / self.EPS_SCALE) * 100.} if driver_torque is not None: values["STEER_TORQUE_DRIVER"] = driver_torque - return self.packer.make_can_msg_panda("STEER_TORQUE_SENSOR", 0, values) + return self.packer.make_can_msg_safety("STEER_TORQUE_SENSOR", 0, values) # Both torque and angle safety modes test with each other's steering commands def _torque_cmd_msg(self, torque, steer_req=1): values = {"STEER_TORQUE_CMD": torque, "STEER_REQUEST": steer_req} - return self.packer.make_can_msg_panda("STEERING_LKA", 0, values) + return self.packer.make_can_msg_safety("STEERING_LKA", 0, values) def _angle_meas_msg(self, angle: float, steer_angle_initializing: bool = False): # This creates a steering torque angle message. Not set on all platforms, # relative to init angle on some older TSS2 platforms. Only to be used with LTA values = {"STEER_ANGLE": angle, "STEER_ANGLE_INITIALIZING": int(steer_angle_initializing)} - return self.packer.make_can_msg_panda("STEER_TORQUE_SENSOR", 0, values) + return self.packer.make_can_msg_safety("STEER_TORQUE_SENSOR", 0, values) def _angle_cmd_msg(self, angle: float, enabled: bool): return self._lta_msg(int(enabled), int(enabled), angle, torque_wind_down=100 if enabled else 0) def _lta_msg(self, req, req2, angle_cmd, torque_wind_down=100): values = {"STEER_REQUEST": req, "STEER_REQUEST_2": req2, "STEER_ANGLE_CMD": angle_cmd, "TORQUE_WIND_DOWN": torque_wind_down} - return self.packer.make_can_msg_panda("STEERING_LTA", 0, values) + return self.packer.make_can_msg_safety("STEERING_LTA", 0, values) + + def _accel_msg_343(self, accel, cancel_req=0): + values = {"ACCEL_CMD": accel, "CANCEL_REQ": cancel_req} + return self.packer.make_can_msg_safety("ACC_CONTROL", 0, values) def _accel_msg(self, accel, cancel_req=0): - values = {"ACCEL_CMD": accel, "CANCEL_REQ": cancel_req} - return self.packer.make_can_msg_panda("ACC_CONTROL", 0, values) + return self._accel_msg_343(accel, cancel_req) def _speed_msg(self, speed): values = {("WHEEL_SPEED_%s" % n): speed * 3.6 for n in ["FR", "FL", "RR", "RL"]} - return self.packer.make_can_msg_panda("WHEEL_SPEEDS", 0, values) + return self.packer.make_can_msg_safety("WHEEL_SPEEDS", 0, values) def _user_brake_msg(self, brake): values = {"BRAKE_PRESSED": brake} - return self.packer.make_can_msg_panda("BRAKE_MODULE", 0, values) + return self.packer.make_can_msg_safety("BRAKE_MODULE", 0, values) def _user_gas_msg(self, gas): cruise_active = self.safety.get_controls_allowed() values = {"GAS_RELEASED": not gas, "CRUISE_ACTIVE": cruise_active} - return self.packer.make_can_msg_panda("PCM_CRUISE", 0, values) + return self.packer.make_can_msg_safety("PCM_CRUISE", 0, values) def _pcm_status_msg(self, enable): values = {"CRUISE_ACTIVE": enable} - return self.packer.make_can_msg_panda("PCM_CRUISE", 0, values) + return self.packer.make_can_msg_safety("PCM_CRUISE", 0, values) def _acc_state_msg(self, enabled): msg = "DSU_CRUISE" if self.SAFETY_PARAM_SP & ToyotaSafetyFlagsSP.UNSUPPORTED_DSU else "PCM_CRUISE_2" values = {"MAIN_ON": enabled} - return self.packer.make_can_msg_panda(msg, 0, values) + return self.packer.make_can_msg_safety(msg, 0, values) def test_diagnostics(self, stock_longitudinal: bool = False, ecu_disabled: bool = True): for should_tx, msg in ((False, b"\x6D\x02\x3E\x00\x00\x00\x00\x00"), # fwdCamera tester present @@ -186,7 +189,7 @@ class TestToyotaSafetyTorque(TestToyotaSafetyBase, common.MotorTorqueSteeringSaf raise unittest.SkipTest def setUp(self): - self.packer = CANPackerPanda("toyota_nodsu_pt_generated") + self.packer = CANPackerSafety("toyota_nodsu_pt_generated") self.safety = libsafety_py.libsafety self.safety.set_current_safety_param_sp(self.SAFETY_PARAM_SP) self.safety.set_safety_hooks(CarParams.SafetyModel.toyota, self.EPS_SCALE) @@ -218,7 +221,7 @@ class TestToyotaSafetyAngle(TestToyotaSafetyBase, common.AngleSteeringSafetyTest MAX_LTA_DRIVER_TORQUE = 150 # max allowed driver torque before wind down def setUp(self): - self.packer = CANPackerPanda("toyota_nodsu_pt_generated") + self.packer = CANPackerSafety("toyota_nodsu_pt_generated") self.safety = libsafety_py.libsafety self.safety.set_safety_hooks(CarParams.SafetyModel.toyota, self.EPS_SCALE | ToyotaSafetyFlags.LTA) self.safety.init_tests() @@ -323,7 +326,7 @@ class TestToyotaAltBrakeSafety(TestToyotaSafetyTorque): raise unittest.SkipTest def setUp(self): - self.packer = CANPackerPanda("toyota_new_mc_pt_generated") + self.packer = CANPackerSafety("toyota_new_mc_pt_generated") self.safety = libsafety_py.libsafety self.safety.set_current_safety_param_sp(self.SAFETY_PARAM_SP) self.safety.set_safety_hooks(CarParams.SafetyModel.toyota, self.EPS_SCALE | ToyotaSafetyFlags.ALT_BRAKE) @@ -331,7 +334,7 @@ class TestToyotaAltBrakeSafety(TestToyotaSafetyTorque): def _user_brake_msg(self, brake): values = {"BRAKE_PRESSED": brake} - return self.packer.make_can_msg_panda("BRAKE_MODULE", 0, values) + return self.packer.make_can_msg_safety("BRAKE_MODULE", 0, values) # No LTA message in the DBC def test_lta_steer_cmd(self): @@ -374,9 +377,9 @@ class TestToyotaStockLongitudinalBase(TestToyotaSafetyBase): for controls_allowed in [True, False]: self.safety.set_controls_allowed(controls_allowed) for accel in np.arange(self.MIN_ACCEL - 1, self.MAX_ACCEL + 1, 0.1): - self.assertFalse(self._tx(self._accel_msg(accel))) - should_tx = np.isclose(accel, 0, atol=0.0001) - self.assertEqual(should_tx, self._tx(self._accel_msg(accel, cancel_req=1))) + self.assertFalse(self._tx(self._accel_msg_343(accel))) + should_tx = np.isclose(accel, self.INACTIVE_ACCEL, atol=0.0001) + self.assertEqual(should_tx, self._tx(self._accel_msg_343(accel, cancel_req=1))) @parameterized_class(UNSUPPORTED_DSU) @@ -389,7 +392,7 @@ class TestToyotaStockLongitudinalTorque(TestToyotaStockLongitudinalBase, TestToy raise unittest.SkipTest def setUp(self): - self.packer = CANPackerPanda("toyota_nodsu_pt_generated") + self.packer = CANPackerSafety("toyota_nodsu_pt_generated") self.safety = libsafety_py.libsafety self.safety.set_current_safety_param_sp(self.SAFETY_PARAM_SP) self.safety.set_safety_hooks(CarParams.SafetyModel.toyota, self.EPS_SCALE | ToyotaSafetyFlags.STOCK_LONGITUDINAL) @@ -399,7 +402,7 @@ class TestToyotaStockLongitudinalTorque(TestToyotaStockLongitudinalBase, TestToy class TestToyotaStockLongitudinalAngle(TestToyotaStockLongitudinalBase, TestToyotaSafetyAngle): def setUp(self): - self.packer = CANPackerPanda("toyota_nodsu_pt_generated") + self.packer = CANPackerSafety("toyota_nodsu_pt_generated") self.safety = libsafety_py.libsafety self.safety.set_safety_hooks(CarParams.SafetyModel.toyota, self.EPS_SCALE | ToyotaSafetyFlags.STOCK_LONGITUDINAL | ToyotaSafetyFlags.LTA) @@ -413,31 +416,27 @@ class TestToyotaSecOcSafetyBase(TestToyotaSafetyBase): FWD_BLACKLISTED_ADDRS = {2: [0x2E4, 0x191, 0x412, 0x131]} def setUp(self): - self.packer = CANPackerPanda("toyota_secoc_pt_generated") + self.packer = CANPackerSafety("toyota_secoc_pt_generated") self.safety = libsafety_py.libsafety self.safety.set_safety_hooks(CarParams.SafetyModel.toyota, self.EPS_SCALE | ToyotaSafetyFlags.SECOC) self.safety.init_tests() - # 0x283|PRE_COLLISION is not allowed on SecOC platforms - def test_block_aeb(self, stock_longitudinal: bool = False): - pass - - def test_diagnostics(self, stock_longitudinal: bool = False, ecu_disabled: bool = False): - super().test_diagnostics(stock_longitudinal=stock_longitudinal, ecu_disabled=ecu_disabled) + def test_diagnostics(self, ecu_disabled: bool = False): + super().test_diagnostics(ecu_disabled=ecu_disabled) # This platform also has alternate brake and PCM messages, but same naming in the DBC, so same packers work def _user_gas_msg(self, gas): values = {"GAS_PEDAL_USER": gas} - return self.packer.make_can_msg_panda("GAS_PEDAL", 0, values) + return self.packer.make_can_msg_safety("GAS_PEDAL", 0, values) # This platform sends both STEERING_LTA (same as other Toyota) and STEERING_LTA_2 (SecOC signed) # STEERING_LTA is checked for no-actuation by the base class, STEERING_LTA_2 is checked for no-actuation below def _lta_2_msg(self, req, req2, angle_cmd, torque_wind_down=100): values = {"STEER_REQUEST": req, "STEER_REQUEST_2": req2, "STEER_ANGLE_CMD": angle_cmd} - return self.packer.make_can_msg_panda("STEERING_LTA_2", 0, values) + return self.packer.make_can_msg_safety("STEERING_LTA_2", 0, values) def test_lta_2_steer_cmd(self): for engaged, req, req2, angle in itertools.product([True, False], [0, 1], [0, 1], np.linspace(-20, 20, 5)): @@ -446,6 +445,51 @@ class TestToyotaSecOcSafetyBase(TestToyotaSafetyBase): should_tx = not req and not req2 and angle == 0 self.assertEqual(should_tx, self._tx(self._lta_2_msg(req, req2, angle)), f"{req=} {req2=} {angle=}") + def _accel_msg_183(self, accel): + values = {"ACCEL_CMD": accel} + return self.packer.make_can_msg_safety("ACC_CONTROL_2", 0, values) + + def _accel_msg(self, accel, cancel_req=0): + return self._accel_msg_183(accel) + + +class TestToyotaSecOcSafetyStockLongitudinal(TestToyotaSecOcSafetyBase, TestToyotaStockLongitudinalBase): + + def setUp(self): + self.packer = CANPackerSafety("toyota_secoc_pt_generated") + self.safety = libsafety_py.libsafety + self.safety.set_safety_hooks(CarParams.SafetyModel.toyota, + self.EPS_SCALE | ToyotaSafetyFlags.STOCK_LONGITUDINAL | ToyotaSafetyFlags.SECOC) + self.safety.init_tests() + + +class TestToyotaSecOcSafety(TestToyotaSecOcSafetyBase): + + RELAY_MALFUNCTION_ADDRS = {0: (0x2E4, 0x191, 0x412, 0x131, 0x343, 0x183)} + FWD_BLACKLISTED_ADDRS = {2: [0x2E4, 0x191, 0x412, 0x131, 0x343, 0x183]} + + def setUp(self): + self.packer = CANPackerSafety("toyota_secoc_pt_generated") + self.safety = libsafety_py.libsafety + self.safety.set_safety_hooks(CarParams.SafetyModel.toyota, self.EPS_SCALE | ToyotaSafetyFlags.SECOC) + self.safety.init_tests() + + @unittest.skip("test not applicable for cars without a DSU") + def test_block_aeb(self, stock_longitudinal: bool = False): + pass + + def test_343_actuation_blocked(self): + """ + For SecOC cars, longitudinal acceleration must be sent in ACC_CONTROL_2, but all other ACC + data remains in ACC_CONTROL. Verify no actuation is sent via ACC_CONTROL. + """ + for controls_allowed in [True, False]: + self.safety.set_controls_allowed(controls_allowed) + for accel in np.arange(self.MIN_ACCEL - 1, self.MAX_ACCEL + 1, 0.1): + should_tx = np.isclose(accel, self.INACTIVE_ACCEL, atol=0.0001) + self.assertEqual(should_tx, self._tx(self._accel_msg_343(accel))) + self.assertEqual(should_tx, self._tx(self._accel_msg_343(accel, cancel_req=1))) + class TestToyotaSecOcSafetyStockLongitudinal(TestToyotaSecOcSafetyBase, TestToyotaStockLongitudinalBase): diff --git a/opendbc/safety/tests/test_volkswagen_mlb.py b/opendbc/safety/tests/test_volkswagen_mlb.py new file mode 100755 index 00000000..562bfce6 --- /dev/null +++ b/opendbc/safety/tests/test_volkswagen_mlb.py @@ -0,0 +1,141 @@ +#!/usr/bin/env python3 +import unittest +from opendbc.car.structs import CarParams +from opendbc.safety.tests.libsafety import libsafety_py +import opendbc.safety.tests.common as common +from opendbc.safety.tests.common import CANPackerSafety + +MSG_LH_EPS_03 = 0x9F # RX from EPS, for driver steering torque +MSG_ESP_03 = 0x103 # RX from ABS, for wheel speeds +MSG_MOTOR_03 = 0x105 # RX from ECU, for driver throttle input and driver brake input +MSG_ESP_05 = 0x106 # RX from ABS, for brake light state +MSG_LS_01 = 0x10B # TX by OP, ACC control buttons for cancel/resume +MSG_TSK_02 = 0x10C # RX from ECU, for ACC status from drivetrain coordinator +MSG_HCA_01 = 0x126 # TX by OP, Heading Control Assist steering torque +MSG_LDW_02 = 0x397 # TX by OP, Lane line recognition and text alerts + + +class TestVolkswagenMlbSafetyBase(common.CarSafetyTest, common.DriverTorqueSteeringSafetyTest): + RELAY_MALFUNCTION_ADDRS = {0: (MSG_HCA_01, MSG_LDW_02)} + + MAX_RATE_UP = 9 + MAX_RATE_DOWN = 10 + MAX_TORQUE_LOOKUP = [0], [300] + MAX_RT_DELTA = 169 + + DRIVER_TORQUE_ALLOWANCE = 60 + DRIVER_TORQUE_FACTOR = 3 + + # Wheel speeds _esp_03_msg + def _speed_msg(self, speed): + values = {"ESP_%s_Radgeschw" % s: speed for s in ["HL", "HR", "VL", "VR"]} + return self.packer.make_can_msg_safety("ESP_03", 0, values) + + # Driver brake pressure over threshold + def _esp_05_msg(self, brake): + values = {"ESP_Fahrer_bremst": brake} + return self.packer.make_can_msg_safety("ESP_05", 0, values) + + # Brake pedal switch + def _motor_03_msg(self, brake_signal=False, gas_signal=0): + values = { + "MO_Fahrer_bremst": brake_signal, + "MO_Fahrpedalrohwert_01": gas_signal, + } + return self.packer.make_can_msg_safety("Motor_03", 0, values) + + def _user_brake_msg(self, brake): + return self._motor_03_msg(brake_signal=brake) + + def _user_gas_msg(self, gas): + return self._motor_03_msg(gas_signal=gas) + + # ACC engagement status + def _tsk_status_msg(self, enable, main_switch=True): + values = {"ACC_Status_ACC": 1 if not main_switch else 3 if enable else 2} + return self.packer.make_can_msg_safety("ACC_05", 2, values) + + def _pcm_status_msg(self, enable): + return self._tsk_status_msg(enable) + + # Driver steering input torque + def _torque_driver_msg(self, torque): + values = {"EPS_Lenkmoment": abs(torque), "EPS_VZ_Lenkmoment": torque < 0} + return self.packer.make_can_msg_safety("LH_EPS_03", 0, values) + + # openpilot steering output torque + def _torque_cmd_msg(self, torque, steer_req=1): + values = {"HCA_01_LM_Offset": abs(torque), + "HCA_01_LM_OffSign": torque < 0, + "HCA_01_Sendestatus": steer_req, + "HCA_01_Status_HCA": 7 if steer_req else 3} + return self.packer.make_can_msg_safety("HCA_01", 0, values) + + # Cruise control buttons + def _ls_01_msg(self, cancel=0, resume=0, _set=0, bus=2): + values = {"LS_Abbrechen": cancel, "LS_Tip_Setzen": _set, "LS_Tip_Wiederaufnahme": resume} + return self.packer.make_can_msg_safety("LS_01", bus, values) + + # Verify brake_pressed is true if either the switch or pressure threshold signals are true + def test_redundant_brake_signals(self): + test_combinations = [(True, True, True), (True, True, False), (True, False, True), (False, False, False)] + for brake_pressed, motor_03_signal, esp_05_signal in test_combinations: + self._rx(self._motor_03_msg(brake_signal=False)) + self._rx(self._esp_05_msg(False)) + self.assertFalse(self.safety.get_brake_pressed_prev()) + self._rx(self._motor_03_msg(brake_signal=motor_03_signal)) + self._rx(self._esp_05_msg(esp_05_signal)) + self.assertEqual(brake_pressed, self.safety.get_brake_pressed_prev(), + f"expected {brake_pressed=} with {motor_03_signal=} and {esp_05_signal=}") + + def test_torque_measurements(self): + # TODO: make this test work with all cars + self._rx(self._torque_driver_msg(50)) + self._rx(self._torque_driver_msg(-50)) + self._rx(self._torque_driver_msg(0)) + self._rx(self._torque_driver_msg(0)) + self._rx(self._torque_driver_msg(0)) + self._rx(self._torque_driver_msg(0)) + + self.assertEqual(-50, self.safety.get_torque_driver_min()) + self.assertEqual(50, self.safety.get_torque_driver_max()) + + self._rx(self._torque_driver_msg(0)) + self.assertEqual(0, self.safety.get_torque_driver_max()) + self.assertEqual(-50, self.safety.get_torque_driver_min()) + + self._rx(self._torque_driver_msg(0)) + self.assertEqual(0, self.safety.get_torque_driver_max()) + self.assertEqual(0, self.safety.get_torque_driver_min()) + + +class TestVolkswagenMlbStockSafety(TestVolkswagenMlbSafetyBase): + TX_MSGS = [[MSG_HCA_01, 0], [MSG_LDW_02, 0], [MSG_LS_01, 0], [MSG_LS_01, 2]] + FWD_BLACKLISTED_ADDRS = {2: [MSG_HCA_01, MSG_LDW_02]} + FWD_BUS_LOOKUP = {0: 2, 2: 0} + + def setUp(self): + self.packer = CANPackerSafety("vw_mlb") + self.safety = libsafety_py.libsafety + self.safety.set_safety_hooks(CarParams.SafetyModel.volkswagenMlb, 0) + self.safety.init_tests() + + def test_spam_cancel_safety_check(self): + self.safety.set_controls_allowed(0) + self.assertTrue(self._tx(self._ls_01_msg(cancel=1))) + self.assertFalse(self._tx(self._ls_01_msg(resume=1))) + self.assertFalse(self._tx(self._ls_01_msg(_set=1))) + # do not block resume if we are engaged already + self.safety.set_controls_allowed(1) + self.assertTrue(self._tx(self._ls_01_msg(resume=1))) + + def test_cancel_button(self): + # Disable on rising edge of cancel button + self._rx(self._tsk_status_msg(False, main_switch=True)) + self.safety.set_controls_allowed(1) + self._rx(self._ls_01_msg(cancel=True, bus=0)) + self.assertFalse(self.safety.get_controls_allowed(), "controls allowed after cancel") + + +if __name__ == "__main__": + unittest.main() diff --git a/opendbc/safety/tests/test_volkswagen_mqb.py b/opendbc/safety/tests/test_volkswagen_mqb.py index 92d659f4..47f77a8d 100755 --- a/opendbc/safety/tests/test_volkswagen_mqb.py +++ b/opendbc/safety/tests/test_volkswagen_mqb.py @@ -4,7 +4,7 @@ import numpy as np from opendbc.car.structs import CarParams from opendbc.safety.tests.libsafety import libsafety_py import opendbc.safety.tests.common as common -from opendbc.safety.tests.common import CANPackerPanda +from opendbc.safety.tests.common import CANPackerSafety from opendbc.car.volkswagen.values import VolkswagenSafetyFlags MAX_ACCEL = 2.0 @@ -23,7 +23,7 @@ MSG_ACC_02 = 0x30C # TX by OP, ACC HUD data to the instrument cluster MSG_LDW_02 = 0x397 # TX by OP, Lane line recognition and text alerts -class TestVolkswagenMqbSafetyBase(common.PandaCarSafetyTest, common.DriverTorqueSteeringSafetyTest): +class TestVolkswagenMqbSafetyBase(common.CarSafetyTest, common.DriverTorqueSteeringSafetyTest): RELAY_MALFUNCTION_ADDRS = {0: (MSG_HCA_01, MSG_LDW_02), 2: (MSG_LH_EPS_03,)} MAX_RATE_UP = 4 @@ -37,17 +37,17 @@ class TestVolkswagenMqbSafetyBase(common.PandaCarSafetyTest, common.DriverTorque # Wheel speeds _esp_19_msg def _speed_msg(self, speed): values = {"ESP_%s_Radgeschw_02" % s: speed for s in ["HL", "HR", "VL", "VR"]} - return self.packer.make_can_msg_panda("ESP_19", 0, values) + return self.packer.make_can_msg_safety("ESP_19", 0, values) # Driver brake pressure over threshold def _esp_05_msg(self, brake): values = {"ESP_Fahrer_bremst": brake} - return self.packer.make_can_msg_panda("ESP_05", 0, values) + return self.packer.make_can_msg_safety("ESP_05", 0, values) # Brake pedal switch def _motor_14_msg(self, brake): values = {"MO_Fahrer_bremst": brake} - return self.packer.make_can_msg_panda("Motor_14", 0, values) + return self.packer.make_can_msg_safety("Motor_14", 0, values) def _user_brake_msg(self, brake): return self._motor_14_msg(brake) @@ -55,7 +55,7 @@ class TestVolkswagenMqbSafetyBase(common.PandaCarSafetyTest, common.DriverTorque # Driver throttle input def _user_gas_msg(self, gas): values = {"MO_Fahrpedalrohwert_01": gas} - return self.packer.make_can_msg_panda("Motor_20", 0, values) + return self.packer.make_can_msg_safety("Motor_20", 0, values) # ACC engagement status def _tsk_status_msg(self, enable, main_switch=True): @@ -64,7 +64,7 @@ class TestVolkswagenMqbSafetyBase(common.PandaCarSafetyTest, common.DriverTorque else: tsk_status = 0 values = {"TSK_Status": tsk_status} - return self.packer.make_can_msg_panda("TSK_06", 0, values) + return self.packer.make_can_msg_safety("TSK_06", 0, values) def _pcm_status_msg(self, enable): return self._tsk_status_msg(enable) @@ -72,27 +72,27 @@ class TestVolkswagenMqbSafetyBase(common.PandaCarSafetyTest, common.DriverTorque # Driver steering input torque def _torque_driver_msg(self, torque): values = {"EPS_Lenkmoment": abs(torque), "EPS_VZ_Lenkmoment": torque < 0} - return self.packer.make_can_msg_panda("LH_EPS_03", 0, values) + return self.packer.make_can_msg_safety("LH_EPS_03", 0, values) # openpilot steering output torque def _torque_cmd_msg(self, torque, steer_req=1): values = {"HCA_01_LM_Offset": abs(torque), "HCA_01_LM_OffSign": torque < 0, "HCA_01_Sendestatus": steer_req} - return self.packer.make_can_msg_panda("HCA_01", 0, values) + return self.packer.make_can_msg_safety("HCA_01", 0, values) # Cruise control buttons def _gra_acc_01_msg(self, cancel=0, resume=0, _set=0, bus=2): values = {"GRA_Abbrechen": cancel, "GRA_Tip_Setzen": _set, "GRA_Tip_Wiederaufnahme": resume} - return self.packer.make_can_msg_panda("GRA_ACC_01", bus, values) + return self.packer.make_can_msg_safety("GRA_ACC_01", bus, values) # Acceleration request to drivetrain coordinator def _acc_06_msg(self, accel): values = {"ACC_Sollbeschleunigung_02": accel} - return self.packer.make_can_msg_panda("ACC_06", 0, values) + return self.packer.make_can_msg_safety("ACC_06", 0, values) # Acceleration request to drivetrain coordinator def _acc_07_msg(self, accel, secondary_accel=3.02): values = {"ACC_Sollbeschleunigung_02": accel, "ACC_Folgebeschl": secondary_accel} - return self.packer.make_can_msg_panda("ACC_07", 0, values) + return self.packer.make_can_msg_safety("ACC_07", 0, values) # Verify brake_pressed is true if either the switch or pressure threshold signals are true def test_redundant_brake_signals(self): @@ -132,7 +132,7 @@ class TestVolkswagenMqbStockSafety(TestVolkswagenMqbSafetyBase): FWD_BLACKLISTED_ADDRS = {0: [MSG_LH_EPS_03], 2: [MSG_HCA_01, MSG_LDW_02]} def setUp(self): - self.packer = CANPackerPanda("vw_mqb") + self.packer = CANPackerSafety("vw_mqb") self.safety = libsafety_py.libsafety self.safety.set_safety_hooks(CarParams.SafetyModel.volkswagen, 0) self.safety.init_tests() @@ -154,7 +154,7 @@ class TestVolkswagenMqbLongSafety(TestVolkswagenMqbSafetyBase): INACTIVE_ACCEL = 3.01 def setUp(self): - self.packer = CANPackerPanda("vw_mqb") + self.packer = CANPackerSafety("vw_mqb") self.safety = libsafety_py.libsafety self.safety.set_safety_hooks(CarParams.SafetyModel.volkswagen, VolkswagenSafetyFlags.LONG_CONTROL) self.safety.init_tests() diff --git a/opendbc/safety/tests/test_volkswagen_pq.py b/opendbc/safety/tests/test_volkswagen_pq.py index 576de946..72f0bfa6 100755 --- a/opendbc/safety/tests/test_volkswagen_pq.py +++ b/opendbc/safety/tests/test_volkswagen_pq.py @@ -5,7 +5,7 @@ from opendbc.car.volkswagen.values import VolkswagenSafetyFlags from opendbc.car.structs import CarParams from opendbc.safety.tests.libsafety import libsafety_py import opendbc.safety.tests.common as common -from opendbc.safety.tests.common import CANPackerPanda +from opendbc.safety.tests.common import CANPackerSafety MSG_LENKHILFE_3 = 0x0D0 # RX from EPS, for steering angle and driver steering torque MSG_HCA_1 = 0x0D2 # TX by OP, Heading Control Assist steering torque @@ -19,7 +19,7 @@ MSG_ACC_GRA_ANZEIGE = 0x56A # TX by OP, ACC HUD MSG_LDW_1 = 0x5BE # TX by OP, Lane line recognition and text alerts -class TestVolkswagenPqSafetyBase(common.PandaCarSafetyTest, common.DriverTorqueSteeringSafetyTest): +class TestVolkswagenPqSafetyBase(common.CarSafetyTest, common.DriverTorqueSteeringSafetyTest): cruise_engaged = False RELAY_MALFUNCTION_ADDRS = {0: (MSG_HCA_1, MSG_LDW_1)} @@ -39,7 +39,7 @@ class TestVolkswagenPqSafetyBase(common.PandaCarSafetyTest, common.DriverTorqueS # Ego speed (Bremse_1) def _speed_msg(self, speed): values = {"BR1_Rad_kmh": speed} - return self.packer.make_can_msg_panda("Bremse_1", 0, values) + return self.packer.make_can_msg_safety("Bremse_1", 0, values) # Brake light switch (shared message Motor_2) def _user_brake_msg(self, brake): @@ -54,39 +54,39 @@ class TestVolkswagenPqSafetyBase(common.PandaCarSafetyTest, common.DriverTorqueS # Acceleration request to drivetrain coordinator def _accel_msg(self, accel): values = {"ACS_Sollbeschl": accel} - return self.packer.make_can_msg_panda("ACC_System", 0, values) + return self.packer.make_can_msg_safety("ACC_System", 0, values) # Driver steering input torque def _torque_driver_msg(self, torque): values = {"LH3_LM": abs(torque), "LH3_LMSign": torque < 0} - return self.packer.make_can_msg_panda("Lenkhilfe_3", 0, values) + return self.packer.make_can_msg_safety("Lenkhilfe_3", 0, values) # openpilot steering output torque def _torque_cmd_msg(self, torque, steer_req=1, hca_status=5): values = {"LM_Offset": abs(torque), "LM_OffSign": torque < 0, "HCA_Status": hca_status if steer_req else 3} - return self.packer.make_can_msg_panda("HCA_1", 0, values) + return self.packer.make_can_msg_safety("HCA_1", 0, values) # ACC engagement and brake light switch status # Called indirectly for compatibility with common.py tests def _motor_2_msg(self, brake_pressed=False, cruise_engaged=False): values = {"MO2_BLS": brake_pressed, "MO2_Sta_GRA": cruise_engaged} - return self.packer.make_can_msg_panda("Motor_2", 0, values) + return self.packer.make_can_msg_safety("Motor_2", 0, values) # ACC main switch status def _motor_5_msg(self, main_switch=False): - values = {"GRA_Hauptschalter": main_switch} - return self.packer.make_can_msg_panda("Motor_5", 0, values) + values = {"MO5_GRA_Hauptsch": main_switch} + return self.packer.make_can_msg_safety("Motor_5", 0, values) # Driver throttle input (Motor_3) def _user_gas_msg(self, gas): - values = {"Fahrpedal_Rohsignal": gas} - return self.packer.make_can_msg_panda("Motor_3", 0, values) + values = {"MO3_Pedalwert": gas} + return self.packer.make_can_msg_safety("Motor_3", 0, values) # Cruise control buttons (GRA_Neu) def _button_msg(self, _set=False, resume=False, cancel=False, bus=2): values = {"GRA_Neu_Setzen": _set, "GRA_Recall": resume, "GRA_Abbrechen": cancel} - return self.packer.make_can_msg_panda("GRA_Neu", bus, values) + return self.packer.make_can_msg_safety("GRA_Neu", bus, values) def test_torque_measurements(self): # TODO: make this test work with all cars @@ -115,7 +115,7 @@ class TestVolkswagenPqStockSafety(TestVolkswagenPqSafetyBase): FWD_BLACKLISTED_ADDRS = {2: [MSG_HCA_1, MSG_LDW_1]} def setUp(self): - self.packer = CANPackerPanda("vw_pq") + self.packer = CANPackerSafety("vw_pq") self.safety = libsafety_py.libsafety self.safety.set_safety_hooks(CarParams.SafetyModel.volkswagenPq, 0) self.safety.init_tests() @@ -137,7 +137,7 @@ class TestVolkswagenPqLongSafety(TestVolkswagenPqSafetyBase, common.Longitudinal INACTIVE_ACCEL = 3.01 def setUp(self): - self.packer = CANPackerPanda("vw_pq") + self.packer = CANPackerSafety("vw_pq") self.safety = libsafety_py.libsafety self.safety.set_safety_hooks(CarParams.SafetyModel.volkswagenPq, VolkswagenSafetyFlags.LONG_CONTROL) self.safety.init_tests() diff --git a/pyproject.toml b/pyproject.toml index 620bd452..cc2c0766 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -22,7 +22,8 @@ dependencies = [ testing = [ "cffi", "gcovr", - "pytest", + # FIXME: pytest 9.0.0 doesn't support unittest.SkipTest + "pytest==8.4.2", "pytest-coverage", "pytest-mock", "pytest-randomly", @@ -98,6 +99,7 @@ select = [ "INP001", ] ignore = [ + "E302", "E305", # too restrictive "W292", "E741", "E402", diff --git a/setup.sh b/setup.sh index 29c5bf2c..dce0a226 100755 --- a/setup.sh +++ b/setup.sh @@ -7,6 +7,15 @@ BASEDIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" export PYTHONPATH=$BASEDIR # *** dependencies install *** +if [ "$(uname -s)" = "Linux" ]; then + # TODO: add macOS support + if ! command -v "mull-runner-17" > /dev/null 2>&1; then + sudo apt-get update && sudo apt-get install -y curl clang-17 + curl -1sLf 'https://dl.cloudsmith.io/public/mull-project/mull-stable/setup.deb.sh' | sudo -E bash + sudo apt-get update && sudo apt-get install -y mull-17 + fi +fi + if ! command -v uv &>/dev/null; then echo "'uv' is not installed. Installing 'uv'..." curl -LsSf https://astral.sh/uv/install.sh | sh