diff --git a/.github/workflows/repo.yml b/.github/workflows/repo.yml index 94b58e263b..122bbb2fc4 100644 --- a/.github/workflows/repo.yml +++ b/.github/workflows/repo.yml @@ -12,7 +12,7 @@ jobs: container: image: ghcr.io/commaai/opendbc:latest steps: - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 - name: pre-commit autoupdate run: | git config --global --add safe.directory '*' diff --git a/.github/workflows/tests.yml b/.github/workflows/tests.yml index 94e4956572..5d3719fa27 100644 --- a/.github/workflows/tests.yml +++ b/.github/workflows/tests.yml @@ -4,10 +4,7 @@ on: [push, pull_request] env: RUN: docker run -v $GITHUB_WORKSPACE:/project/opendbc -w /project/opendbc -e PYTHONWARNINGS="error,default::DeprecationWarning" --shm-size 1G --rm opendbc /bin/bash -c - BUILD: | - docker pull $(grep -ioP '(?<=^from)\s+\S+' Dockerfile) || true - docker pull ghcr.io/commaai/opendbc:latest || true - docker build --cache-from ghcr.io/commaai/opendbc:latest -t opendbc -f Dockerfile . + BUILD: docker buildx build --pull --load --cache-to type=inline --cache-from type=registry,ref=ghcr.io/commaai/opendbc:latest -t opendbc -f Dockerfile . PYTHONWARNINGS: error jobs: @@ -19,7 +16,7 @@ jobs: # matrix: # run: [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14] steps: - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 - name: Build Docker image run: eval "$BUILD" - name: Build opendbc @@ -31,7 +28,7 @@ jobs: name: static analysis runs-on: ubuntu-20.04 steps: - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 - name: Build Docker image run: eval "$BUILD" - name: Build opendbc @@ -47,7 +44,7 @@ jobs: runs-on: ubuntu-20.04 if: github.ref == 'refs/heads/master' && github.event_name != 'pull_request' && github.repository == 'commaai/opendbc' steps: - - uses: actions/checkout@v3 + - uses: actions/checkout@v4 - name: Build Docker image run: eval "$BUILD" - name: Push to dockerhub diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 6de2400505..7c45c439e2 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -17,11 +17,11 @@ repos: - --check-hidden - --builtins clear,rare,informal,usage,code,names,en-GB_to_en-US - repo: https://github.com/pre-commit/mirrors-mypy - rev: v1.8.0 + rev: v1.9.0 hooks: - id: mypy - repo: https://github.com/astral-sh/ruff-pre-commit - rev: v0.1.9 + rev: v0.3.2 hooks: - id: ruff - repo: https://github.com/MarcoGorelli/cython-lint diff --git a/Dockerfile b/Dockerfile index 59e7bc4387..cda26e7229 100644 --- a/Dockerfile +++ b/Dockerfile @@ -49,7 +49,7 @@ RUN git config --global --add safe.directory '*' WORKDIR /project RUN git clone https://github.com/commaai/cereal.git /project/cereal && \ cd /project/cereal && \ - git checkout 82bca3a9714b73c05414fdf848b6016a0ffac17d && \ + git checkout a4255106b7255e00ae04162f7aa14aa3cae339c3 && \ rm -rf .git && \ scons -j$(nproc) --minimal diff --git a/acura_ilx_2016_can_generated.dbc b/acura_ilx_2016_can_generated.dbc index 1afb5bade6..24c8f67892 100644 --- a/acura_ilx_2016_can_generated.dbc +++ b/acura_ilx_2016_can_generated.dbc @@ -1,7 +1,7 @@ CM_ "AUTOGENERATED FILE, DO NOT EDIT"; -CM_ "Imported file _comma.dbc starts here"; +CM_ "Imported file _community.dbc starts here"; BO_ 512 GAS_COMMAND: 6 EON SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR diff --git a/acura_rdx_2018_can_generated.dbc b/acura_rdx_2018_can_generated.dbc index 6596b44514..4c23725176 100644 --- a/acura_rdx_2018_can_generated.dbc +++ b/acura_rdx_2018_can_generated.dbc @@ -1,7 +1,7 @@ CM_ "AUTOGENERATED FILE, DO NOT EDIT"; -CM_ "Imported file _comma.dbc starts here"; +CM_ "Imported file _community.dbc starts here"; BO_ 512 GAS_COMMAND: 6 EON SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR diff --git a/can/SConscript b/can/SConscript index f07234c111..7e8fd270f6 100644 --- a/can/SConscript +++ b/can/SConscript @@ -22,3 +22,7 @@ packer = lenv.Program('packer_pyx.so', 'packer_pyx.pyx') lenv.Depends(parser, libdbc) lenv.Depends(packer, libdbc) + +opendbc_python = Alias("opendbc_python", [parser, packer]) + +Export('opendbc_python') \ No newline at end of file diff --git a/can/packer_pyx.pyx b/can/packer_pyx.pyx index 5133fcc990..1b9fc8fab6 100644 --- a/can/packer_pyx.pyx +++ b/can/packer_pyx.pyx @@ -26,6 +26,10 @@ cdef class CANPacker: msg = self.dbc[0].msgs[i] self.name_to_address[string(msg.name)] = msg.address + def __dealloc__(self): + if self.packer: + del self.packer + cdef vector[uint8_t] pack(self, addr, values): cdef vector[SignalPackValue] values_thing values_thing.reserve(len(values)) diff --git a/can/parser_pyx.pyx b/can/parser_pyx.pyx index 808610e87a..8ce67740b0 100644 --- a/can/parser_pyx.pyx +++ b/can/parser_pyx.pyx @@ -66,6 +66,10 @@ cdef class CANParser: self.can = new cpp_CANParser(bus, dbc_name, message_v) self.update_strings([]) + def __dealloc__(self): + if self.can: + del self.can + def update_strings(self, strings, sendcan=False): for v in self.vl_all.values(): for l in v.values(): # no-cython-lint diff --git a/can/tests/test_packer_parser.py b/can/tests/test_packer_parser.py index 046c51e874..8c3653a220 100755 --- a/can/tests/test_packer_parser.py +++ b/can/tests/test_packer_parser.py @@ -12,8 +12,7 @@ # Python implementation so we don't have to depend on boardd def can_list_to_can_capnp(can_msgs, msgtype='can', logMonoTime=None): - dat = messaging.new_message() - dat.init(msgtype, len(can_msgs)) + dat = messaging.new_message(msgtype, len(can_msgs)) if logMonoTime is not None: dat.logMonoTime = logMonoTime @@ -365,6 +364,7 @@ def test_track_all_signals(self): "ACC_TYPE": 0, "CANCEL_REQ": 0, "ACC_CUT_IN": 0, + "LEAD_VEHICLE_STOPPED": 0, "PERMIT_BRAKING": 0, "RELEASE_STANDSTILL": 0, "ITS_CONNECT_LEAD": 0, diff --git a/ford_lincoln_base_pt.dbc b/ford_lincoln_base_pt.dbc index ebe7a43213..acd45e796b 100644 --- a/ford_lincoln_base_pt.dbc +++ b/ford_lincoln_base_pt.dbc @@ -3608,6 +3608,9 @@ BO_ 922 DCACA_Data1_FD1: 8 GWM SG_ DcacClntFlw_D_Rq : 5|2@0+ (1,0) [0|3] "SED" SOBDMC_HPCM_FD1 SG_ CoolFanDcac_D_Rq : 7|2@0+ (1,0) [0|3] "SED" SOBDMC_HPCM_FD1 +BO_ 1082 INSTRUMENT_PANEL: 8 GWM + SG_ METRIC_UNITS : 54|1@0+ (1,0) [0|1] "SED" IPMA,PCM,PCM_HEV + BO_TX_BU_ 2612224016 : ECM_Diesel,PCM,PCM_HEV; BO_TX_BU_ 878 : PCM,PCM_HEV; BO_TX_BU_ 1085 : ECM_Diesel,PCM; diff --git a/generator/gm/_comma.dbc b/generator/gm/_community.dbc similarity index 100% rename from generator/gm/_comma.dbc rename to generator/gm/_community.dbc diff --git a/generator/gm/gm_global_a_powertrain.dbc b/generator/gm/gm_global_a_powertrain.dbc index e9a5b2e8cc..e4315be99f 100644 --- a/generator/gm/gm_global_a_powertrain.dbc +++ b/generator/gm/gm_global_a_powertrain.dbc @@ -1,4 +1,4 @@ -CM_ "IMPORT _comma.dbc"; +CM_ "IMPORT _community.dbc"; VERSION "" @@ -168,6 +168,9 @@ BO_ 497 BCMGeneralPlatformStatus: 8 K9_BCM SG_ SystemBackUpPowerMode : 5|2@0+ (1,0) [0|3] "" XXX SG_ ParkBrakeSwActive : 36|1@0+ (1,0) [0|3] "" XXX +BO_ 500 SportMode: 6 XXX + SG_ SportMode : 15|1@0+ (1,0) [0|1] "" XXX + BO_ 501 ECMPRDNL2: 8 K20_ECM SG_ TransmissionState : 48|4@1+ (1,0) [0|7] "" NEO SG_ PRNDL2 : 27|4@0+ (1,0) [0|255] "" NEO diff --git a/generator/honda/_comma.dbc b/generator/honda/_community.dbc similarity index 100% rename from generator/honda/_comma.dbc rename to generator/honda/_community.dbc diff --git a/generator/honda/acura_ilx_2016_can.dbc b/generator/honda/acura_ilx_2016_can.dbc index 0fc474a647..11e1d9ecf3 100644 --- a/generator/honda/acura_ilx_2016_can.dbc +++ b/generator/honda/acura_ilx_2016_can.dbc @@ -1,4 +1,4 @@ -CM_ "IMPORT _comma.dbc"; +CM_ "IMPORT _community.dbc"; CM_ "IMPORT _honda_common.dbc"; CM_ "IMPORT _nidec_common.dbc"; CM_ "IMPORT _steering_sensors_b.dbc"; diff --git a/generator/honda/acura_rdx_2018_can.dbc b/generator/honda/acura_rdx_2018_can.dbc index 4514dea157..e83429e592 100644 --- a/generator/honda/acura_rdx_2018_can.dbc +++ b/generator/honda/acura_rdx_2018_can.dbc @@ -1,4 +1,4 @@ -CM_ "IMPORT _comma.dbc"; +CM_ "IMPORT _community.dbc"; CM_ "IMPORT _honda_common.dbc"; CM_ "IMPORT _nidec_common.dbc"; CM_ "IMPORT _steering_sensors_b.dbc"; diff --git a/generator/honda/honda_civic_ex_2022_can.dbc b/generator/honda/honda_civic_ex_2022_can.dbc index 97aee26423..8ca13746ea 100644 --- a/generator/honda/honda_civic_ex_2022_can.dbc +++ b/generator/honda/honda_civic_ex_2022_can.dbc @@ -1,4 +1,4 @@ -CM_ "IMPORT _comma.dbc"; +CM_ "IMPORT _community.dbc"; CM_ "IMPORT _honda_common.dbc"; CM_ "IMPORT _bosch_2018.dbc"; CM_ "IMPORT _steering_sensors_a.dbc"; diff --git a/generator/honda/honda_civic_touring_2016_can.dbc b/generator/honda/honda_civic_touring_2016_can.dbc index 09b64bbe7d..9346f5f881 100644 --- a/generator/honda/honda_civic_touring_2016_can.dbc +++ b/generator/honda/honda_civic_touring_2016_can.dbc @@ -1,4 +1,4 @@ -CM_ "IMPORT _comma.dbc"; +CM_ "IMPORT _community.dbc"; CM_ "IMPORT _honda_common.dbc"; CM_ "IMPORT _nidec_common.dbc"; CM_ "IMPORT _steering_sensors_a.dbc"; diff --git a/generator/honda/honda_clarity_hybrid_2018_can.dbc b/generator/honda/honda_clarity_hybrid_2018_can.dbc index 9499ddca2d..2d1ec35f20 100644 --- a/generator/honda/honda_clarity_hybrid_2018_can.dbc +++ b/generator/honda/honda_clarity_hybrid_2018_can.dbc @@ -1,4 +1,4 @@ -CM_ "IMPORT _comma.dbc"; +CM_ "IMPORT _community.dbc"; CM_ "IMPORT _honda_common.dbc"; CM_ "IMPORT _nidec_common.dbc"; CM_ "IMPORT _steering_sensors_a.dbc"; diff --git a/generator/honda/honda_crv_executive_2016_can.dbc b/generator/honda/honda_crv_executive_2016_can.dbc index a10c36da56..291795b9ee 100644 --- a/generator/honda/honda_crv_executive_2016_can.dbc +++ b/generator/honda/honda_crv_executive_2016_can.dbc @@ -1,4 +1,4 @@ -CM_ "IMPORT _comma.dbc"; +CM_ "IMPORT _community.dbc"; CM_ "IMPORT _honda_common.dbc"; CM_ "IMPORT _nidec_common.dbc"; diff --git a/generator/honda/honda_crv_touring_2016_can.dbc b/generator/honda/honda_crv_touring_2016_can.dbc index b607a4ffe5..9e33720b26 100644 --- a/generator/honda/honda_crv_touring_2016_can.dbc +++ b/generator/honda/honda_crv_touring_2016_can.dbc @@ -1,4 +1,4 @@ -CM_ "IMPORT _comma.dbc"; +CM_ "IMPORT _community.dbc"; CM_ "IMPORT _honda_common.dbc"; CM_ "IMPORT _nidec_common.dbc"; CM_ "IMPORT _steering_sensors_b.dbc"; diff --git a/generator/honda/honda_fit_ex_2018_can.dbc b/generator/honda/honda_fit_ex_2018_can.dbc index 59c6fb74fe..bb54f25850 100644 --- a/generator/honda/honda_fit_ex_2018_can.dbc +++ b/generator/honda/honda_fit_ex_2018_can.dbc @@ -1,4 +1,4 @@ -CM_ "IMPORT _comma.dbc"; +CM_ "IMPORT _community.dbc"; CM_ "IMPORT _honda_common.dbc"; CM_ "IMPORT _nidec_common.dbc"; CM_ "IMPORT _steering_sensors_b.dbc"; diff --git a/generator/honda/honda_fit_hybrid_2018_can.dbc b/generator/honda/honda_fit_hybrid_2018_can.dbc index cdd8b52f0e..c6d4fdde56 100644 --- a/generator/honda/honda_fit_hybrid_2018_can.dbc +++ b/generator/honda/honda_fit_hybrid_2018_can.dbc @@ -1,4 +1,4 @@ -CM_ "IMPORT _comma.dbc"; +CM_ "IMPORT _community.dbc"; CM_ "IMPORT _honda_common.dbc"; CM_ "IMPORT _nidec_common.dbc"; diff --git a/generator/honda/honda_odyssey_exl_2018.dbc b/generator/honda/honda_odyssey_exl_2018.dbc index 2db2f0433b..2b42d3e763 100644 --- a/generator/honda/honda_odyssey_exl_2018.dbc +++ b/generator/honda/honda_odyssey_exl_2018.dbc @@ -1,4 +1,4 @@ -CM_ "IMPORT _comma.dbc"; +CM_ "IMPORT _community.dbc"; CM_ "IMPORT _honda_common.dbc"; CM_ "IMPORT _nidec_common.dbc"; CM_ "IMPORT _steering_sensors_b.dbc"; diff --git a/generator/honda/honda_odyssey_extreme_edition_2018_china_can.dbc b/generator/honda/honda_odyssey_extreme_edition_2018_china_can.dbc index 10377b982d..fc3c152f1b 100644 --- a/generator/honda/honda_odyssey_extreme_edition_2018_china_can.dbc +++ b/generator/honda/honda_odyssey_extreme_edition_2018_china_can.dbc @@ -1,4 +1,4 @@ -CM_ "IMPORT _comma.dbc"; +CM_ "IMPORT _community.dbc"; CM_ "IMPORT _honda_common.dbc"; CM_ "IMPORT _nidec_common.dbc"; diff --git a/generator/honda/honda_pilot_2023_can.dbc b/generator/honda/honda_pilot_2023_can.dbc new file mode 100644 index 0000000000..df84d623fb --- /dev/null +++ b/generator/honda/honda_pilot_2023_can.dbc @@ -0,0 +1,86 @@ +CM_ "IMPORT _honda_common.dbc"; +CM_ "IMPORT _bosch_2018.dbc"; +CM_ "IMPORT _steering_sensors_a.dbc"; + +BO_ 419 GEARBOX: 8 XXX + SG_ GEAR_SHIFTER : 24|8@1+ (1,0) [0|255] "" XXX + SG_ GEAR : 32|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 432 STANDSTILL: 7 VSA + SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" EON + +BO_ 446 BRAKE_MODULE: 3 VSA + SG_ BRAKE_PRESSED : 4|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" XXX + +BO_ 479 ACC_CONTROL: 8 EON + SG_ SET_TO_0 : 20|5@0+ (1,0) [0|1] "" XXX + SG_ CONTROL_ON : 23|3@0+ (1,0) [0|5] "" XXX + SG_ GAS_COMMAND : 7|16@0- (1,0) [0|0] "" XXX + SG_ ACCEL_COMMAND : 31|11@0- (0.01,0) [0|0] "m/s2" XXX + SG_ BRAKE_LIGHTS : 62|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_REQUEST : 34|1@0+ (1,0) [0|1] "" XXX + SG_ STANDSTILL : 35|1@0+ (1,0) [0|1] "" XXX + SG_ STANDSTILL_RELEASE : 36|1@0+ (1,0) [0|1] "" XXX + SG_ AEB_STATUS : 33|1@0+ (1,0) [0|1] "" XXX + SG_ AEB_BRAKING : 47|1@0+ (1,0) [0|1] "" XXX + SG_ AEB_PREPARE : 43|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 495 ACC_CONTROL_ON: 8 XXX + SG_ SET_TO_75 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ SET_TO_30 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ ZEROS_BOH : 23|8@0+ (1,0) [0|255] "" XXX + SG_ ZEROS_BOH2 : 47|16@0+ (1,0) [0|255] "" XXX + SG_ SET_TO_FF : 15|8@0+ (1,0) [0|255] "" XXX + SG_ SET_TO_3 : 6|7@0+ (1,0) [0|4095] "" XXX + SG_ CONTROL_ON : 7|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + +BO_ 829 LKAS_HUD: 8 XXX + SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" XXX + SG_ BOH : 6|7@0+ (1,0) [0|127] "" XXX + SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" XXX + SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" XXX + SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" XXX + SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" XXX + SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" XXX + SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" XXX + SG_ DTC : 13|1@0+ (1,0) [0|1] "" XXX + SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" XXX + SG_ BEEP : 17|2@0+ (1,0) [0|1] "" XXX + SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" XXX + SG_ BOH_2 : 23|2@0+ (1,0) [0|4] "" XXX + SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" XXX + SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" XXX + SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ LANE_LINES : 36|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + +BO_ 1302 ODOMETER: 8 XXX + SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +CM_ SG_ 479 CONTROL_ON "Set to 5 when car is being controlled"; +CM_ SG_ 479 AEB_STATUS "set for the duration of AEB event"; +CM_ SG_ 479 AEB_BRAKING "set when braking is commanded during AEB event"; +CM_ SG_ 479 AEB_PREPARE "set 1s before AEB"; +CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnings etc..."; +CM_ SG_ 829 LANE_LINES "related to lane lines on cluster, left/right white/green"; + +VAL_ 419 GEAR_SHIFTER 2 "S" 32 "D" 16 "N" 8 "R" 4 "P"; +VAL_ 419 GEAR 26 "S" 20 "D" 19 "N" 18 "R" 17 "P"; +VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep"; +VAL_ 829 LANE_LINES 7 "both_lines_green" 6 "both_lines_white" 2 "left_line_white" 0 "no_lines"; diff --git a/generator/tesla/.gitignore b/generator/tesla/.gitignore new file mode 100644 index 0000000000..554aeeaf24 --- /dev/null +++ b/generator/tesla/.gitignore @@ -0,0 +1 @@ +*.dbc \ No newline at end of file diff --git a/generator/tesla/radar_common.py b/generator/tesla/radar_common.py new file mode 100755 index 0000000000..737c203b02 --- /dev/null +++ b/generator/tesla/radar_common.py @@ -0,0 +1,38 @@ +#!/usr/bin/env python3 + +def get_radar_point_definition(base_id, base_name): + return f""" +BO_ {base_id} {base_name}_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ {base_id+1} {base_name}_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot +""" + +def get_val_definition(base_id): + return f""" +VAL_ {base_id+1} MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ {base_id+1} Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 \ +"RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ;""" \ No newline at end of file diff --git a/generator/tesla/tesla_radar_bosch.py b/generator/tesla/tesla_radar_bosch.py new file mode 100755 index 0000000000..b7fa1ab4dc --- /dev/null +++ b/generator/tesla/tesla_radar_bosch.py @@ -0,0 +1,282 @@ +#!/usr/bin/env python3 + +import os +from opendbc.generator.tesla.radar_common import get_radar_point_definition, get_val_definition + +if __name__ == "__main__": + dbc_name = os.path.basename(__file__).replace(".py", ".dbc") + tesla_path = os.path.dirname(os.path.realpath(__file__)) + with open(os.path.join(tesla_path, dbc_name), "w", encoding='utf-8') as f: + f.write(""" +VERSION "" + +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_ + SG_MUL_VAL_ + +BS_: + +BU_: Autopilot Radar Diag + + +BO_ 769 TeslaRadarSguInfo: 8 Radar + SG_ RADC_VerticalMisalignment : 0|8@1+ (1,0) [0|255] "" Autopilot + SG_ RADC_SCUTemperature : 8|8@1+ (1,-128) [-128|127] "" Autopilot + SG_ RADC_VMA_Plaus : 16|8@1+ (1,0) [0|255] "" Autopilot + SG_ RADC_SGU_ITC : 24|8@1+ (1,0) [0|255] "" Autopilot + SG_ RADC_HorizontMisalignment : 32|12@1+ (1,0) [0|4096] "" Autopilot + SG_ RADC_SensorDirty : 44|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_HWFail : 45|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_SGUFail : 46|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_SGUInfoConsistBit : 47|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 770 TeslaRadarTguInfo: 8 Radar + SG_ RADC_ACCTargObj1_sguIndex : 0|6@1+ (1,0) [0|63] "" Autopilot + SG_ RADC_ACCTargObj2_sguIndex : 6|6@1+ (1,0) [0|63] "" Autopilot + SG_ RADC_ACCTargObj3_sguIndex : 12|6@1+ (1,0) [0|63] "" Autopilot + SG_ RADC_ACCTargObj4_sguIndex : 18|6@1+ (1,0) [0|63] "" Autopilot + SG_ RADC_ACCTargObj5_sguIndex : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ unused30 : 30|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_TGUInfoConsistBit : 31|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_ACCTargObj1_dBPower : 32|16@1+ (1,0) [0|65535] "" Autopilot + SG_ RADC_ACCTargObj5_dBPower : 48|16@1+ (1,0) [0|65535] "" Autopilot + +BO_ 1281 TeslaRadarAlertMatrix: 8 Radar + SG_ RADC_a001_ecuInternalPerf : 0|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a002_flashPerformance : 1|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a003_vBatHigh : 2|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a004_adjustmentNotDone : 3|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a005_adjustmentReq : 4|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a006_adjustmentNotOk : 5|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a007_sensorBlinded : 6|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a008_plantModeActive : 7|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a009_configMismatch : 8|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a010_canBusOff : 9|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a011_bdyMIA : 10|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a012_espMIA : 11|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a013_gtwMIA : 12|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a014_sccmMIA : 13|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a015_adasMIA : 14|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a016_bdyInvalidCount : 15|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a017_adasInvalidCount : 16|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a018_espInvalidCount : 17|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a019_sccmInvalidCount : 18|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a020_bdyInvalidChkSm : 19|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a021_espInvalidChkSm : 20|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a022_sccmInvalidChkSm : 21|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a023_sccmInvalidChkSm : 22|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a024_absValidity : 23|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a025_ambTValidity : 24|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a026_brakeValidity : 25|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a027_CntryCdValidity : 26|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a028_espValidity : 27|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a029_longAccOffValidity : 28|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a030_longAccValidity : 29|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a031_odoValidity : 30|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a032_gearValidity : 31|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a033_steerAngValidity : 32|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a034_steerAngSpdValidity : 33|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a035_indctrValidity : 34|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a036_vehStandStillValidity : 35|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a037_vinValidity : 36|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a038_whlRotValidity : 37|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a039_whlSpdValidity : 38|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a040_whlStandStillValidity : 39|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a041_wiperValidity : 40|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a042_xwdValidity : 41|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a043_yawOffValidity : 42|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a044_yawValidity : 43|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a045_bsdSanity : 44|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a046_rctaSanity : 45|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a047_lcwSanity : 46|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a048_steerAngOffSanity : 47|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a049_tireSizeSanity : 48|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a050_velocitySanity : 49|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a051_yawSanity : 50|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a052_radomeHtrInop : 51|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a053_espmodValidity : 52|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a054_gtwmodValidity : 53|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a055_stwmodValidity : 54|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a056_bcmodValidity : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a057_dimodValidity : 56|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a058_opmodValidity : 57|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a059_drmiInvalidChkSm : 58|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a060_drmiInvalidCount : 59|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a061_radPositionMismatch : 60|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a062_strRackMismatch : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ unused62 : 62|2@1+ (1,0) [0|3] "" Autopilot +""") + + M_RANGE = range(0x310, 0x36D + 1, 3) + for i, base_id in enumerate(M_RANGE): + f.write(get_radar_point_definition(base_id, f"RadarPoint{i}")) + + L_RANGE = range(0x371, 0x37D + 1, 3) + for i, base_id in enumerate(L_RANGE): + f.write(get_radar_point_definition(base_id, f"ProcessedRadarPoint{i+1}")) + + f.write(""" +BO_ 697 VIN_VIP_405HS: 8 Autopilot + SG_ VIN_MuxID M : 0|8@1+ (1,0) [0|0] "" Radar + SG_ VIN_Part1 m16 : 47|24@0+ (1,0) [0|16777215] "" Radar + SG_ VIN_Part2 m17 : 15|56@0+ (1,0) [0|7.2057594038E+16] "" Radar + SG_ VIN_Part3 m18 : 15|56@0+ (1,0) [0|7.2057594038E+16] "" Radar + +BO_ 681 Msg2A9_GTW_carConfig: 8 Autopilot + SG_ Msg2A9_Always0x02 : 48|8@1+ (1,0) [0|0] "" Radar + SG_ Msg2A9_Always0x10 : 56|8@1+ (1,0) [0|0] "" Radar + SG_ Msg2A9_Always0x16 : 8|8@1+ (1,0) [0|0] "" Radar + SG_ Msg2A9_Always0x41 : 24|8@1+ (1,0) [0|0] "" Radar + SG_ Msg2A9_Value1_0x02 : 0|3@1+ (1,0) [0|0] "" Radar + SG_ Msg2A9_FourWheelDrive : 3|2@1+ (1,0) [0|0] "" Radar + SG_ Msg2A9_Value2_0x02 : 5|3@1+ (1,0) [0|0] "" Radar + SG_ Msg2A9_Always0x43 : 16|8@1+ (1,0) [0|0] "" Radar + +BO_ 409 Msg199_STW_ANGLHP_STAT: 8 Autopilot + SG_ Msg199Always0x04 : 32|8@1+ (1,0) [0|0] "" Radar + SG_ Msg199Always0x20 : 16|8@1+ (1,0) [0|0] "" Radar + SG_ Msg199Always0x2F : 0|8@1+ (1,0) [0|0] "" Radar + SG_ Msg199Always0x67 : 8|8@1+ (1,0) [0|0] "" Radar + SG_ Msg199Always0xFF : 40|8@1+ (1,0) [0|0] "" Radar + SG_ Msg199Checksum : 56|8@1+ (1,0) [0|0] "" Radar + SG_ Msg199Counter : 52|4@1+ (1,0) [0|0] "" Radar + +BO_ 361 Msg169_ESP_wheelSpeeds: 8 Autopilot + SG_ ESP_wheelSpeedFrL_HS : 0|13@1+ (0.04,0) [0|327.64] "km/h" Radar + SG_ ESP_wheelSpeedFrR_HS : 13|13@1+ (0.04,0) [0|327.64] "km/h" Radar + SG_ ESP_wheelSpeedReL_HS : 26|13@1+ (0.04,0) [0|327.64] "km/h" Radar + SG_ ESP_wheelSpeedReR_HS : 39|13@1+ (0.04,0) [0|327.64] "km/h" Radar + SG_ Msg169Checksum : 56|8@1+ (1,0) [0|0] "" Radar + SG_ Msg169Counter : 52|4@1+ (1,0) [0|0] "" Radar + +BO_ 345 Msg159_ESP_C: 8 Autopilot + SG_ Msg159Always0x3A : 16|8@1+ (1,0) [0|0] "" Radar + SG_ Msg159Always0xA5 : 0|8@1+ (1,0) [0|0] "" Radar + SG_ Msg159Always0xCF : 32|8@1+ (1,0) [0|0] "" Radar + SG_ Msg159Always0xF4 : 8|8@1+ (1,0) [0|0] "" Radar + SG_ Msg159Counter : 44|4@1+ (1,0) [0|0] "" Radar + SG_ Msg159Checksum : 24|8@1+ (1,0) [0|0] "" Radar + +BO_ 329 Msg149_ESP_145h: 8 Autopilot + SG_ Msg149Always0x02 : 16|8@1+ (1,0) [0|0] "" Radar + SG_ Msg149Always0x04 : 40|8@1+ (1,0) [0|0] "" Radar + SG_ Msg149Always0x26 : 8|8@1+ (1,0) [0|0] "" Radar + SG_ Msg149Always0x6A : 24|8@1+ (1,0) [0|0] "" Radar + SG_ Msg149Always0xAA : 32|8@1+ (1,0) [0|0] "" Radar + SG_ Msg149Always0xF : 48|4@1+ (1,0) [0|0] "" Radar + SG_ Msg149Checksum : 56|8@1+ (1,0) [0|0] "" Radar + SG_ Msg149Counter : 52|4@1+ (1,0) [0|0] "" Radar + +BO_ 297 Msg129_ESP_115h: 6 Autopilot + SG_ Msg129Always0x20 : 24|8@1+ (1,0) [0|0] "" Radar + SG_ Msg129Checksum : 40|8@1+ (1,0) [0|0] "" Radar + SG_ Msg129Counter : 36|4@1+ (1,0) [0|0] "" Radar + +BO_ 281 Msg119_DI_torque2: 6 Autopilot + SG_ Msg119Always0x11 : 24|8@1+ (1,0) [0|0] "" Radar + SG_ Msg119Always0x1F : 8|8@1+ (1,0) [0|0] "" Radar + SG_ Msg119Always0x8 : 36|4@1+ (1,0) [0|0] "" Radar + SG_ Msg119Always0xF4 : 16|8@1+ (1,0) [0|0] "" Radar + SG_ Msg119Always0xFF : 0|8@1+ (1,0) [0|0] "" Radar + SG_ Msg119Checksum : 40|8@1+ (1,0) [0|0] "" Radar + SG_ Msg119Counter : 32|4@1+ (1,0) [0|0] "" Radar + +BO_ 265 Msg109_DI_torque1: 8 Autopilot + SG_ Msg109Always0x80 : 24|8@1+ (1,0) [0|0] "" Radar + SG_ Msg109Checksum : 56|8@1+ (1,0) [0|0] "" Radar + SG_ Msg109Counter : 13|3@1+ (1,0) [0|0] "" Radar + +BO_ 521 Msg209_GTW_odo: 8 Autopilot + SG_ Msg209Always0x61 : 8|8@1+ (1,0) [0|0] "" Radar + SG_ Msg209Always0x94 : 16|8@1+ (1,0) [0|0] "" Radar + SG_ Msg209Always0x52 : 24|8@1+ (1,0) [0|0] "" Radar + SG_ Msg209Always0x13 : 32|8@1+ (1,0) [0|0] "" Radar + SG_ Msg209Always0x03 : 40|8@1+ (1,0) [0|0] "" Radar + SG_ Msg209Always0x80 : 48|8@1+ (1,0) [0|0] "" Radar + +BO_ 537 Msg219_STW_ACTN_RQ: 8 Autopilot + SG_ Msg219Counter : 52|4@1+ (1,0) [0|15] "" Radar + SG_ Msg219CRC : 56|8@1+ (1,0) [0|0] "" Radar + +BO_ 425 Msg1A9_DI_espControl: 5 Autopilot + SG_ Msg1A9Always0x0C : 16|8@1+ (1,0) [0|0] "" Radar + SG_ Msg1A9Counter : 28|4@1+ (1,0) [0|0] "" Radar + SG_ Msg1A9Checksum : 32|8@1+ (1,0) [0|0] "" Radar + +BO_ 729 Msg2D9_BC_status : 8 Autopilot + SG_ Msg2D9Always0x80 : 0|8@1+ (1,0) [0|0] "" Radar + SG_ Msg2D9Always0x40 : 8|8@1+ (1,0) [0|0] "" Radar + SG_ Msg2D9Always0x83 : 16|8@1+ (1,0) [0|0] "" Radar + +BO_ 1601 UDS_radarRequest: 8 Diag + SG_ UDS_radarRequestData : 7|64@0+ (1,0) [0|0] "" Radar + +BO_ 1617 Radar_udsResponse: 8 Radar + SG_ Radar_udsResponseData : 7|64@0+ (1,0) [0|0] "" Diag + +CM_ BO_ 697 "Start with MuxID 0x12, then 0x11 and finally 0x10 (VIN is then transmitted in the reverse order)"; +CM_ BO_ 681 "Message sent every 1000 ms. All fixed bytes, no checksum, the byte for RWD or AWD needs to match VIN config"; +CM_ BO_ 409 "Message sent every 10ms. Checksum : use all first 7 bytes with the SAE J1850 CRC algo"; +CM_ BO_ 361 "Message sent every 10ms. Checksum : Sum of all first 7 bytes + 0x76"; +CM_ BO_ 345 "Message sent every 20ms. Checksum : Sum of all first bytes + 0xc; place checksum in 4th octet"; +CM_ BO_ 329 "Message sent every 20ms. Checksum : Sum of all first 7 bytes + 0x46"; +CM_ BO_ 297 "Message sent every 20ms. Checksum : Sum of all first 5 bytes + 0x16"; +CM_ BO_ 281 "Message sent every 10ms. Checksum : Sum of all first 5 bytes + 0x17"; +CM_ BO_ 265 "Message sent every 10ms. Checksum : Sum of all first 7 bytes + 0x7"; +CM_ BO_ 521 "Message sent every 100ms. All fixed bytes, no checksum."; +CM_ BO_ 537 "Message sent every 100ms. Checksum : use all first 7 bytes with the SAE J1850 CRC algo"; +CM_ BO_ 425 "Message sent every 20ms. Checksum : Sum of all first 4 bytes + 0x38"; +CM_ BO_ 729 "Message sent every 1000ms. All fixed bytes, no checksum."; + +BA_DEF_ "BusType" STRING ; +BA_DEF_ BO_ "GenMsgCycleTime" INT 0 0; +BA_DEF_ SG_ "FieldType" STRING ; + +BA_DEF_DEF_ "BusType" "CAN"; +BA_DEF_DEF_ "FieldType" ""; +BA_DEF_DEF_ "GenMsgCycleTime" 0; + +BA_ "GenMsgCycleTime" BO_ 697 250; +BA_ "GenMsgCycleTime" BO_ 681 1000; +BA_ "GenMsgCycleTime" BO_ 409 10; +BA_ "GenMsgCycleTime" BO_ 361 10; +BA_ "GenMsgCycleTime" BO_ 345 20; +BA_ "GenMsgCycleTime" BO_ 329 20; +BA_ "GenMsgCycleTime" BO_ 297 20; +BA_ "GenMsgCycleTime" BO_ 281 10; +BA_ "GenMsgCycleTime" BO_ 265 10; +BA_ "GenMsgCycleTime" BO_ 521 100; +BA_ "GenMsgCycleTime" BO_ 537 100; +BA_ "GenMsgCycleTime" BO_ 425 20; +BA_ "GenMsgCycleTime" BO_ 729 1000; + +VAL_ 681 Msg2A9_FourWheelDrive 3 "SNA" 2 "UNUSED" 1 "4WD" 0 "2WD" ;""") + + for base_id in list(M_RANGE) + list(L_RANGE): + f.write(get_val_definition(base_id)) diff --git a/generator/tesla/tesla_radar_continental.py b/generator/tesla/tesla_radar_continental.py new file mode 100755 index 0000000000..c785c7ec25 --- /dev/null +++ b/generator/tesla/tesla_radar_continental.py @@ -0,0 +1,77 @@ +#!/usr/bin/env python3 + +import os +from opendbc.generator.tesla.radar_common import get_radar_point_definition, get_val_definition + +if __name__ == "__main__": + dbc_name = os.path.basename(__file__).replace(".py", ".dbc") + tesla_path = os.path.dirname(os.path.realpath(__file__)) + with open(os.path.join(tesla_path, dbc_name), "w", encoding='utf-8') as f: + f.write(""" +VERSION "" + +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_ + SG_MUL_VAL_ + +BS_: + +BU_: Autopilot Radar Diag + +BO_ 1025 RadarStatus: 8 Radar + SG_ carparkDetected : 29|1@1+ (1,0) [0|1] "" Autopilot + SG_ decreaseBlockage : 25|1@1+ (1,0) [0|1] "" Autopilot + SG_ horizontMisalignment : 8|12@1+ (0.00012207,-0.25) [-0.25|0.249878] "rad" Autopilot + SG_ increaseBlockage : 24|1@1+ (1,0) [0|1] "" Autopilot + SG_ lowPowerMode : 20|2@1+ (1,0) [0|3] "" Autopilot + SG_ powerOnSelfTest : 22|1@1+ (1,0) [0|1] "" Autopilot + SG_ sensorBlocked : 26|1@1+ (1,0) [0|1] "" Autopilot + SG_ sensorInfoConsistBit : 30|1@1+ (1,0) [0|1] "" Autopilot + SG_ sensorReplace : 31|1@1+ (1,0) [0|1] "" Autopilot + SG_ shortTermUnavailable : 23|1@1+ (1,0) [0|1] "" Autopilot + SG_ tunnelDetected : 28|1@1+ (1,0) [0|1] "" Autopilot + SG_ vehDynamicsError : 27|1@1+ (1,0) [0|1] "" Autopilot + SG_ verticalMisalignment : 0|8@1+ (0.00195313,-0.25) [-0.25|0.248047] "rad" Autopilot + +BO_ 1617 Radar_udsResponse: 8 Radar + SG_ Radar_udsResponseData : 7|64@0+ (1,0) [0|1.84467e+19] "" Diag + +BO_ 1601 UDS_radcRequest: 8 Diag + SG_ UDS_radcRequestData : 7|64@0+ (1,0) [0|1.84467e+19] "" Radar +""") + + POINT_RANGE = range(0x410, 0x45E + 1, 2) + for i, base_id in enumerate(POINT_RANGE): + f.write(get_radar_point_definition(base_id, f"RadarPoint{i}")) + + f.write(""" +VAL_ 1025 lowPowerMode 1 "COMMANDED_LOW_POWER" 0 "DEFAULT_LOW_POWER" 2 "NORMAL_POWER" 3 "SNA";""") + + for base_id in list(POINT_RANGE): + f.write(get_val_definition(base_id)) diff --git a/generator/toyota/_comma.dbc b/generator/toyota/_community.dbc similarity index 84% rename from generator/toyota/_comma.dbc rename to generator/toyota/_community.dbc index b4dd0d9c9b..58bcfd3be4 100644 --- a/generator/toyota/_comma.dbc +++ b/generator/toyota/_community.dbc @@ -33,6 +33,9 @@ CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor th BO_ 767 SDSU: 8 XXX SG_ FD_BUTTON : 7|1@0+ (1,0) [0|1] "" XXX + SG_ STATE : 23|4@0+ (1,0) [0|15] "" XXX -CM_ "BO_ SDSU: The sDSU is a modified DSU for use in TSS1 Toyotas. Learn more: https://github.com/wocsor/panda/tree/smart_dsu"; +CM_ "BO_ SDSU: The sDSU is a modified DSU for use in TSS-P Toyotas. Learn more: https://github.com/RetroPilot/ocelot/tree/main/firmware/smart_dsu"; CM_ SG_ 767 FD_BUTTON "The follow distance button signal as forwarded by the sdsu"; + +VAL_ 767 STATE 7 "STATE_AEB_CTRL" 6 "FAULT_INVALID" 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; diff --git a/generator/toyota/_toyota_2017.dbc b/generator/toyota/_toyota_2017.dbc index 52e6c6386e..e21f7426b5 100644 --- a/generator/toyota/_toyota_2017.dbc +++ b/generator/toyota/_toyota_2017.dbc @@ -157,6 +157,7 @@ BO_ 835 ACC_CONTROL: 8 DSU SG_ ACC_TYPE : 23|2@0+ (1,0) [0|3] "" HCU SG_ CANCEL_REQ : 24|1@0+ (1,0) [0|1] "" HCU SG_ ACC_CUT_IN : 25|1@0+ (1,0) [0|1] "" XXX + SG_ LEAD_VEHICLE_STOPPED : 29|1@0+ (1,0) [0|0] "" DSU SG_ PERMIT_BRAKING : 30|1@0+ (1,0) [0|1] "" HCU SG_ RELEASE_STANDSTILL : 31|1@0+ (1,0) [0|1] "" HCU SG_ ITS_CONNECT_LEAD : 39|8@0+ (1,0) [0|1] "" Vector__XXX @@ -405,6 +406,7 @@ CM_ SG_ 835 ACC_MALFUNCTION "display ACC fault on dash if set to 1"; CM_ SG_ 835 ACC_CUT_IN "Display blinking yellow lead if set to 1"; CM_ SG_ 835 DISTANCE "Cycle through ACC following distance from long, mid, short when set to 1"; CM_ SG_ 835 ITS_CONNECT_LEAD "Displayed when lead car is capable of ITS Connect"; +CM_ SG_ 835 LEAD_VEHICLE_STOPPED "Set to 1 when lead is stopped, likely only used in older TSS-P vehicles"; CM_ SG_ 835 ALLOW_LONG_PRESS "Enable Toyota's factory set speed increment behaviour, available on both metrics cars and imperial unit cars"; CM_ SG_ 835 PERMIT_BRAKING "Original ACC has this going high when a car in front is detected. In openpilot and before the PERMIT_BRAKING name, this was 'SET_ME_1' and is hardcoded to be high. Unsure if only informational or has an effect though existing usage in openpilot is to always set it to 1. Originally 'PMTBRKG' in the leaked toyota_2017_ref_pt.dbc file and name expansion speculated to be PerMiT BRaKinG."; CM_ SG_ 835 ACCEL_CMD_ALT "Copy of main ACCEL_CMD, but across 8 bits instead of 16 bits like ACCEL_CMD. Unsure if only informational or has an effect. Likely informational as existing openpilot sets this to 0 and no loss of functionality observed. Originally 'AT_RAW' in leaked toyota_2017_ref_pt.dbc file."; @@ -475,6 +477,7 @@ VAL_ 835 ACC_CUT_IN 1 "CUT-IN Detected" 0 "clear"; VAL_ 835 ALLOW_LONG_PRESS 2 "set speed increase by 5 speed units regardless" 1 "set speed increase by 1 speed unit on short press, 5 speed units on long press"; VAL_ 865 CLUTCH_RELEASED 0 "clutch pressed any amount" 1 "clutch released" VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted"; +VAL_ 921 DISTANCE_LINES 0 "not displayed" 1 "close" 2 "medium" 3 "far"; VAL_ 956 SPORT_ON 0 "off" 1 "on"; VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; VAL_ 956 SPORT_GEAR_ON 0 "off" 1 "on"; diff --git a/generator/toyota/toyota_new_mc_pt.dbc b/generator/toyota/toyota_new_mc_pt.dbc index 2e74a5e8d4..be824cc043 100644 --- a/generator/toyota/toyota_new_mc_pt.dbc +++ b/generator/toyota/toyota_new_mc_pt.dbc @@ -1,4 +1,4 @@ -CM_ "IMPORT _comma.dbc"; +CM_ "IMPORT _community.dbc"; CM_ "IMPORT _toyota_2017.dbc"; BO_ 548 BRAKE_MODULE: 8 XXX diff --git a/generator/toyota/toyota_nodsu_pt.dbc b/generator/toyota/toyota_nodsu_pt.dbc index b09762a4b6..f35f5571a3 100644 --- a/generator/toyota/toyota_nodsu_pt.dbc +++ b/generator/toyota/toyota_nodsu_pt.dbc @@ -1,4 +1,4 @@ -CM_ "IMPORT _comma.dbc"; +CM_ "IMPORT _community.dbc"; CM_ "IMPORT _toyota_2017.dbc"; BO_ 401 STEERING_LTA: 8 XXX diff --git a/generator/toyota/toyota_tnga_k_pt.dbc b/generator/toyota/toyota_tnga_k_pt.dbc index cfabf582d7..faf5b0a942 100644 --- a/generator/toyota/toyota_tnga_k_pt.dbc +++ b/generator/toyota/toyota_tnga_k_pt.dbc @@ -1,4 +1,4 @@ -CM_ "IMPORT _comma.dbc"; +CM_ "IMPORT _community.dbc"; CM_ "IMPORT _toyota_2017.dbc"; BO_ 550 BRAKE_MODULE: 8 XXX diff --git a/gm_global_a_powertrain_generated.dbc b/gm_global_a_powertrain_generated.dbc index 37ad918cb2..1c78dd7b07 100644 --- a/gm_global_a_powertrain_generated.dbc +++ b/gm_global_a_powertrain_generated.dbc @@ -1,7 +1,7 @@ CM_ "AUTOGENERATED FILE, DO NOT EDIT"; -CM_ "Imported file _comma.dbc starts here"; +CM_ "Imported file _community.dbc starts here"; BO_ 512 GAS_COMMAND: 6 NEO SG_ GAS_COMMAND : 7|16@0+ (0.125677,-75.909) [0|1] "" INTERCEPTOR SG_ GAS_COMMAND2 : 23|16@0+ (0.251976,-76.601) [0|1] "" INTERCEPTOR @@ -188,6 +188,9 @@ BO_ 497 BCMGeneralPlatformStatus: 8 K9_BCM SG_ SystemBackUpPowerMode : 5|2@0+ (1,0) [0|3] "" XXX SG_ ParkBrakeSwActive : 36|1@0+ (1,0) [0|3] "" XXX +BO_ 500 SportMode: 6 XXX + SG_ SportMode : 15|1@0+ (1,0) [0|1] "" XXX + BO_ 501 ECMPRDNL2: 8 K20_ECM SG_ TransmissionState : 48|4@1+ (1,0) [0|7] "" NEO SG_ PRNDL2 : 27|4@0+ (1,0) [0|255] "" NEO diff --git a/honda_civic_ex_2022_can_generated.dbc b/honda_civic_ex_2022_can_generated.dbc index 581e7c66e4..8433001dcf 100644 --- a/honda_civic_ex_2022_can_generated.dbc +++ b/honda_civic_ex_2022_can_generated.dbc @@ -1,7 +1,7 @@ CM_ "AUTOGENERATED FILE, DO NOT EDIT"; -CM_ "Imported file _comma.dbc starts here"; +CM_ "Imported file _community.dbc starts here"; BO_ 512 GAS_COMMAND: 6 EON SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR diff --git a/honda_civic_touring_2016_can_generated.dbc b/honda_civic_touring_2016_can_generated.dbc index 82271c417e..db6b21423f 100644 --- a/honda_civic_touring_2016_can_generated.dbc +++ b/honda_civic_touring_2016_can_generated.dbc @@ -1,7 +1,7 @@ CM_ "AUTOGENERATED FILE, DO NOT EDIT"; -CM_ "Imported file _comma.dbc starts here"; +CM_ "Imported file _community.dbc starts here"; BO_ 512 GAS_COMMAND: 6 EON SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR diff --git a/honda_clarity_hybrid_2018_can_generated.dbc b/honda_clarity_hybrid_2018_can_generated.dbc index 5e5cf294fc..f47f7628b8 100644 --- a/honda_clarity_hybrid_2018_can_generated.dbc +++ b/honda_clarity_hybrid_2018_can_generated.dbc @@ -1,7 +1,7 @@ CM_ "AUTOGENERATED FILE, DO NOT EDIT"; -CM_ "Imported file _comma.dbc starts here"; +CM_ "Imported file _community.dbc starts here"; BO_ 512 GAS_COMMAND: 6 EON SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR diff --git a/honda_crv_executive_2016_can_generated.dbc b/honda_crv_executive_2016_can_generated.dbc index 272cf5dd36..c218b19ed5 100644 --- a/honda_crv_executive_2016_can_generated.dbc +++ b/honda_crv_executive_2016_can_generated.dbc @@ -1,7 +1,7 @@ CM_ "AUTOGENERATED FILE, DO NOT EDIT"; -CM_ "Imported file _comma.dbc starts here"; +CM_ "Imported file _community.dbc starts here"; BO_ 512 GAS_COMMAND: 6 EON SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR diff --git a/honda_crv_touring_2016_can_generated.dbc b/honda_crv_touring_2016_can_generated.dbc index 1648442155..8b3f1b208b 100644 --- a/honda_crv_touring_2016_can_generated.dbc +++ b/honda_crv_touring_2016_can_generated.dbc @@ -1,7 +1,7 @@ CM_ "AUTOGENERATED FILE, DO NOT EDIT"; -CM_ "Imported file _comma.dbc starts here"; +CM_ "Imported file _community.dbc starts here"; BO_ 512 GAS_COMMAND: 6 EON SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR diff --git a/honda_fit_ex_2018_can_generated.dbc b/honda_fit_ex_2018_can_generated.dbc index 1a80a9d4e2..05cd391c78 100644 --- a/honda_fit_ex_2018_can_generated.dbc +++ b/honda_fit_ex_2018_can_generated.dbc @@ -1,7 +1,7 @@ CM_ "AUTOGENERATED FILE, DO NOT EDIT"; -CM_ "Imported file _comma.dbc starts here"; +CM_ "Imported file _community.dbc starts here"; BO_ 512 GAS_COMMAND: 6 EON SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR diff --git a/honda_fit_hybrid_2018_can_generated.dbc b/honda_fit_hybrid_2018_can_generated.dbc index 68d603734c..3ada5c74f0 100644 --- a/honda_fit_hybrid_2018_can_generated.dbc +++ b/honda_fit_hybrid_2018_can_generated.dbc @@ -1,7 +1,7 @@ CM_ "AUTOGENERATED FILE, DO NOT EDIT"; -CM_ "Imported file _comma.dbc starts here"; +CM_ "Imported file _community.dbc starts here"; BO_ 512 GAS_COMMAND: 6 EON SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR diff --git a/honda_odyssey_exl_2018_generated.dbc b/honda_odyssey_exl_2018_generated.dbc index bb33513b28..1dd222ed97 100644 --- a/honda_odyssey_exl_2018_generated.dbc +++ b/honda_odyssey_exl_2018_generated.dbc @@ -1,7 +1,7 @@ CM_ "AUTOGENERATED FILE, DO NOT EDIT"; -CM_ "Imported file _comma.dbc starts here"; +CM_ "Imported file _community.dbc starts here"; BO_ 512 GAS_COMMAND: 6 EON SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR diff --git a/honda_odyssey_extreme_edition_2018_china_can_generated.dbc b/honda_odyssey_extreme_edition_2018_china_can_generated.dbc index b5664d9e74..b109a70b62 100644 --- a/honda_odyssey_extreme_edition_2018_china_can_generated.dbc +++ b/honda_odyssey_extreme_edition_2018_china_can_generated.dbc @@ -1,7 +1,7 @@ CM_ "AUTOGENERATED FILE, DO NOT EDIT"; -CM_ "Imported file _comma.dbc starts here"; +CM_ "Imported file _community.dbc starts here"; BO_ 512 GAS_COMMAND: 6 EON SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR diff --git a/honda_pilot_2023_can_generated.dbc b/honda_pilot_2023_can_generated.dbc new file mode 100644 index 0000000000..91686e80b0 --- /dev/null +++ b/honda_pilot_2023_can_generated.dbc @@ -0,0 +1,495 @@ +CM_ "AUTOGENERATED FILE, DO NOT EDIT"; + + +CM_ "Imported file _honda_common.dbc starts here"; +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 + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 316 GAS_PEDAL: 8 PCM + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 344 ENGINE_DATA: 8 PCM + SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ XMISSION_SPEED2 : 39|16@0+ (0.01,0) [0|250] "kph" EON + SG_ ODOMETER : 55|8@0+ (10,0) [0|2550] "m" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 380 POWERTRAIN_DATA: 8 PCM + SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" EON + SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "" EON + SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "" EON + SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "" EON + SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "" EON + SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" EON + SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 420 VSA_STATUS: 8 VSA + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON + SG_ COMPUTER_BRAKING : 23|1@0+ (1,0) [0|1] "" EON + SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_HOLD_RELATED : 52|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_HOLD_ENABLED : 45|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 427 STEER_MOTOR_TORQUE: 3 EPS + SG_ CONFIG_VALID : 7|1@0+ (1,0) [0|1] "" EON + SG_ MOTOR_TORQUE : 1|10@0+ (1,0) [0|256] "" EON + SG_ OUTPUT_DISABLED : 22|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" EON + +BO_ 464 WHEEL_SPEEDS: 8 VSA + SG_ WHEEL_SPEED_FL : 7|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RL : 25|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RR : 42|15@0+ (0.01,0) [0|250] "kph" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 490 VEHICLE_DYNAMICS: 8 VSA + SG_ LAT_ACCEL : 7|16@0- (0.0015,0) [-20|20] "m/s2" EON + SG_ LONG_ACCEL : 23|16@0- (0.0015,0) [-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_ 773 SEATBELT_STATUS: 7 BDY + SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 777 CAR_SPEED: 8 PCM + SG_ ROUGH_CAR_SPEED : 23|8@0+ (1,0) [0|255] "mph" XXX + SG_ CAR_SPEED : 7|16@0+ (0.01,0) [0|65535] "kph" XXX + SG_ ROUGH_CAR_SPEED_3 : 39|16@0+ (0.01,0) [0|65535] "kph" XXX + SG_ ROUGH_CAR_SPEED_2 : 31|8@0+ (1,0) [0|255] "mph" XXX + SG_ LOCK_STATUS : 55|2@0+ (1,0) [0|255] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ IMPERIAL_UNIT : 63|1@0+ (1,0) [0|1] "" XXX + +BO_ 780 ACC_HUD: 8 ADAS + SG_ PCM_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" BDY + SG_ PCM_GAS : 23|8@0+ (1,0) [0|127] "" BDY + SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "kph" BDY + SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY + SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_OFF : 35|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_OFF_2 : 36|1@0+ (1,0) [0|1] "" BDY + SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY + SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY + SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY + SG_ HUD_DISTANCE : 47|2@0+ (1,0) [0|3] "" BDY + SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY + SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY + SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY + SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY + SG_ SET_ME_X01_2 : 55|1@0+ (1,0) [0|1] "" BDY + SG_ IMPERIAL_UNIT : 54|1@0+ (1,0) [0|1] "" BDY + SG_ ACC_ON : 52|1@0+ (1,0) [0|1] "" BDY + SG_ CHIME : 51|3@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X01 : 48|1@0+ (1,0) [0|1] "" BDY + SG_ ICONS : 63|2@0+ (1,0) [0|1] "" BDY + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY + +BO_ 804 CRUISE: 8 PCM + SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" EON + SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" EON + SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON + SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" EON + SG_ BOH2 : 47|8@0- (1,0) [0|255] "" EON + SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 884 STALK_STATUS: 8 XXX + SG_ DASHBOARD_ALERT : 39|8@0+ (1,0) [0|255] "" EON + SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON + SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON + SG_ WIPER_SWITCH : 53|2@0+ (1,0) [0|3] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 891 STALK_STATUS_2: 8 XXX + SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON + SG_ LOW_BEAMS : 35|1@0+ (1,0) [0|1] "" XXX + SG_ HIGH_BEAMS : 34|1@0+ (1,0) [0|1] "" XXX + SG_ PARK_LIGHTS : 36|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 1029 DOORS_STATUS: 8 BDY + SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" EON + SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +CM_ SG_ 304 "Seems to be platform-agnostic"; +CM_ SG_ 316 "Should exist on Nidec"; +CM_ SG_ 420 BRAKE_HOLD_RELATED "On when Brake Hold engaged"; +CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; +CM_ SG_ 773 PASS_AIRBAG_ON "Might just be indicator light"; +CM_ SG_ 773 PASS_AIRBAG_OFF "Might just be indicator light"; +CM_ SG_ 780 CRUISE_SPEED "255 = no speed"; +CM_ SG_ 780 PCM_SPEED "Used by Nidec"; +CM_ SG_ 780 PCM_GAS "Used by Nidec"; +CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; + +VAL_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped"; +VAL_ 780 HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car"; +VAL_ 884 DASHBOARD_ALERT 0 "none" 51 "acc_problem" 55 "cmbs_problem" 75 "key_not_detected" 79 "fasten_seatbelt" 111 "lkas_problem" 131 "brake_system_problem" 132 "brake_hold_problem" 139 "tbd" 161 "door_open"; +VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off"; + + +CM_ "Imported file _bosch_2018.dbc starts here"; +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_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS + SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS + SG_ SET_ME_X00_2 : 31|8@0+ (1,0) [0|0] "" EPS + SG_ STEER_TORQUE : 7|16@0- (1,0) [-4096|4096] "" EPS + SG_ STEER_DOWN_TO_ZERO : 38|1@0+ (1,0) [0|1] "" EPS + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" EPS + +BO_ 229 BOSCH_SUPPLEMENTAL_1: 8 XXX + SG_ SET_ME_X04 : 0|8@1+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 8|8@1+ (1,0) [0|255] "" XXX + SG_ SET_ME_X80 : 16|8@1+ (1,0) [0|255] "" XXX + SG_ SET_ME_X10 : 24|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 232 BRAKE_HOLD: 7 XXX + SG_ XMISSION_SPEED : 7|14@0- (1,0) [1|0] "" XXX + SG_ COMPUTER_BRAKE : 39|16@0+ (1,0) [0|0] "" XXX + SG_ COMPUTER_BRAKE_REQUEST : 29|1@0+ (1,0) [0|0] "" XXX + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" XXX + +BO_ 399 STEER_STATUS: 7 EPS + SG_ STEER_TORQUE_SENSOR : 7|16@0- (-1,0) [-31000|31000] "tbd" EON + SG_ STEER_ANGLE_RATE : 23|16@0- (-0.1,0) [-31000|31000] "deg/s" EON + SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" EON + SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" EON + SG_ STEER_CONFIG_INDEX : 43|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" EON + +BO_ 450 EPB_STATUS: 8 EPB + SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" EON + SG_ EPB_STATE : 29|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 545 XXX_16: 6 SCM + SG_ ECON_ON : 23|1@0+ (1,0) [0|1] "" XXX + SG_ DRIVE_MODE : 37|2@0+ (1,0) [0|3] "" XXX + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" BDY + +BO_ 576 LEFT_LANE_LINE_1: 8 CAM + SG_ LINE_DISTANCE_VISIBLE : 39|9@0+ (1,0) [0|1] "" XXX + SG_ LINE_PROBABILITY : 46|6@0+ (0.015625,0) [0|1] "" XXX + SG_ LINE_OFFSET : 23|12@0+ (0.004,-8.192) [0|1] "Meters" XXX + SG_ LINE_ANGLE : 7|12@0+ (0.0005,-1.024) [0|1] "" XXX + SG_ FRAME_INDEX : 8|4@1+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|1] "" XXX + +BO_ 577 LEFT_LANE_LINE_2: 8 CAM + SG_ LINE_FAR_EDGE_POSITION : 55|8@0+ (1,-128) [0|1] "" XXX + SG_ LINE_SOLID : 13|1@0+ (1,0) [0|1] "" XXX + SG_ LINE_DASHED : 14|1@0+ (1,0) [0|1] "" XXX + SG_ LINE_CURVATURE : 23|12@0+ (0.00001,-0.02048) [0|1] "" XXX + SG_ LINE_PARAMETER : 39|12@0+ (1,0) [0|1] "" XXX + SG_ FRAME_INDEX : 7|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|1] "" XXX + +BO_ 579 RIGHT_LANE_LINE_1: 8 CAM + SG_ LINE_DISTANCE_VISIBLE : 39|9@0+ (1,0) [0|1] "" XXX + SG_ LINE_PROBABILITY : 46|6@0+ (0.015625,0) [0|1] "" XXX + SG_ LINE_OFFSET : 23|12@0+ (0.004,-8.192) [0|1] "Meters" XXX + SG_ LINE_ANGLE : 7|12@0+ (0.0005,-1.024) [0|1] "" XXX + SG_ FRAME_INDEX : 8|4@1+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|1] "" XXX + +BO_ 580 RIGHT_LANE_LINE_2: 8 CAM + SG_ LINE_FAR_EDGE_POSITION : 55|8@0+ (1,-128) [0|1] "" XXX + SG_ LINE_SOLID : 13|1@0+ (1,0) [0|1] "" XXX + SG_ LINE_DASHED : 14|1@0+ (1,0) [0|1] "" XXX + SG_ LINE_CURVATURE : 23|12@0+ (0.00001,-0.02048) [0|1] "" XXX + SG_ LINE_PARAMETER : 39|12@0+ (1,0) [0|1] "" XXX + SG_ FRAME_INDEX : 7|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|1] "" XXX + +BO_ 582 ADJACENT_LEFT_LANE_LINE_1: 8 CAM + SG_ LINE_DISTANCE_VISIBLE : 39|9@0+ (1,0) [0|1] "" XXX + SG_ LINE_PROBABILITY : 46|6@0+ (0.015625,0) [0|1] "" XXX + SG_ LINE_OFFSET : 23|12@0+ (0.004,-8.192) [0|1] "Meters" XXX + SG_ LINE_ANGLE : 7|12@0+ (0.0005,-1.024) [0|1] "" XXX + SG_ FRAME_INDEX : 8|4@1+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|1] "" XXX + +BO_ 583 ADJACENT_LEFT_LANE_LINE_2: 8 CAM + SG_ LINE_FAR_EDGE_POSITION : 55|8@0+ (1,-128) [0|1] "" XXX + SG_ LINE_SOLID : 13|1@0+ (1,0) [0|1] "" XXX + SG_ LINE_DASHED : 14|1@0+ (1,0) [0|1] "" XXX + SG_ LINE_CURVATURE : 23|12@0+ (0.00001,-0.02048) [0|1] "" XXX + SG_ LINE_PARAMETER : 39|12@0+ (1,0) [0|1] "" XXX + SG_ FRAME_INDEX : 7|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|1] "" XXX + +BO_ 585 ADJACENT_RIGHT_LANE_LINE_1: 8 CAM + SG_ LINE_DISTANCE_VISIBLE : 39|9@0+ (1,0) [0|1] "" XXX + SG_ LINE_PROBABILITY : 46|6@0+ (0.015625,0) [0|1] "" XXX + SG_ LINE_OFFSET : 23|12@0+ (0.004,-8.192) [0|1] "Meters" XXX + SG_ LINE_ANGLE : 7|12@0+ (0.0005,-1.024) [0|1] "" XXX + SG_ FRAME_INDEX : 8|4@1+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|1] "" XXX + +BO_ 586 ADJACENT_RIGHT_LANE_LINE_2: 8 CAM + SG_ LINE_FAR_EDGE_POSITION : 55|8@0+ (1,-128) [0|1] "" XXX + SG_ LINE_SOLID : 13|1@0+ (1,0) [0|1] "" XXX + SG_ LINE_DASHED : 14|1@0+ (1,0) [0|1] "" XXX + SG_ LINE_CURVATURE : 23|12@0+ (0.00001,-0.02048) [0|1] "" XXX + SG_ LINE_PARAMETER : 39|12@0+ (1,0) [0|1] "" XXX + SG_ FRAME_INDEX : 7|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|1] "" XXX + +BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA + SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" EON + SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" EON + SG_ SET_TO_X55 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ SET_TO_X55_2 : 47|8@0+ (1,0) [0|255] "" EON + SG_ LONG_COUNTER : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + +BO_ 662 SCM_BUTTONS: 4 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" EON + +BO_ 806 SCM_FEEDBACK: 8 SCM + SG_ DRIVERS_DOOR_OPEN : 17|1@0+ (1,0) [0|1] "" XXX + SG_ MAIN_ON : 28|1@0+ (1,0) [0|1] "" EON + SG_ RIGHT_BLINKER : 27|1@0+ (1,0) [0|1] "" EON + SG_ LEFT_BLINKER : 26|1@0+ (1,0) [0|1] "" EON + SG_ CMBS_STATES : 22|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 862 CAMERA_MESSAGES: 8 CAM + SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY + SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX + SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ ZEROS_BOH_2 : 51|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 927 RADAR_HUD: 8 RADAR + SG_ ZEROS_BOH : 7|10@0+ (1,0) [0|127] "" BDY + SG_ CMBS_OFF : 12|1@0+ (1,0) [0|1] "" BDY + SG_ RESUME_INSTRUCTION : 21|1@0+ (1,0) [0|1] "" XXX + SG_ SET_TO_1 : 13|1@0+ (1,0) [0|1] "" BDY + SG_ ZEROS_BOH2 : 11|4@0+ (1,0) [0|1] "" XXX + SG_ APPLY_BRAKES_FOR_CANC : 23|1@0+ (1,0) [0|1] "" XXX + SG_ ACC_ALERTS : 20|5@0+ (1,0) [0|1] "" BDY + SG_ SET_TO_0 : 22|1@0+ (1,0) [0|1] "" XXX + SG_ HUD_LEAD : 40|1@0+ (1,0) [0|1] "" XXX + SG_ SET_TO_64 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ LEAD_DISTANCE : 39|8@0+ (1,0) [0|255] "" XXX + SG_ ZEROS_BOH3 : 47|7@0+ (1,0) [0|127] "" XXX + SG_ ZEROS_BOH4 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 13274 LKAS_HUD_A: 5 ADAS + SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY + SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY + SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY + SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY + SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY + SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY + SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY + SG_ BOH_2 : 23|2@0+ (1,0) [0|4] "" BDY + SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY + SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X01 : 20|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY + SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY + +BO_ 13275 LKAS_HUD_B: 8 ADAS + SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY + SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY + SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY + SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY + SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY + SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY + SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY + SG_ BOH_2 : 23|2@0+ (1,0) [0|4] "" BDY + SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY + SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X01 : 20|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY + SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" BDY + +CM_ SG_ 450 EPB_STATE "3: On, 2: Disengaging, 1: Engaging, 0: Off"; +CM_ SG_ 576 LINE_DISTANCE_VISIBLE "Length of line visible, undecoded"; +CM_ SG_ 577 LINE_FAR_EDGE_POSITION "Appears to be a measure of line thickness, indicates location of the portion of the line furthest from the car, undecoded"; +CM_ SG_ 577 LINE_PARAMETER "Unclear if this is low quality line curvature rate or if this is something else, but it is correlated with line curvature, undecoded"; +CM_ SG_ 577 LINE_DASHED "1 = line is dashed"; +CM_ SG_ 577 LINE_SOLID "1 = line is solid"; + +VAL_ 399 STEER_STATUS 6 "tmp_fault" 5 "fault_1" 4 "no_torque_alert_2" 3 "low_speed_lockout" 2 "no_torque_alert_1" 0 "normal"; + + +CM_ "Imported file _steering_sensors_a.dbc starts here"; +BO_ 330 STEERING_SENSORS: 8 EPS + SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON + SG_ STEER_ANGLE_RATE : 23|16@0- (-1,0) [-3000|3000] "deg/s" EON + SG_ STEER_SENSOR_STATUS_1 : 34|1@0+ (1,0) [0|1] "" EON + SG_ STEER_SENSOR_STATUS_2 : 33|1@0+ (1,0) [0|1] "" EON + SG_ STEER_SENSOR_STATUS_3 : 32|1@0+ (1,0) [0|1] "" EON + SG_ STEER_WHEEL_ANGLE : 47|16@0- (-0.1,0) [-500|500] "deg" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +CM_ "honda_pilot_2023_can.dbc starts here"; + +BO_ 419 GEARBOX: 8 XXX + SG_ GEAR_SHIFTER : 24|8@1+ (1,0) [0|255] "" XXX + SG_ GEAR : 32|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 432 STANDSTILL: 7 VSA + SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" EON + +BO_ 446 BRAKE_MODULE: 3 VSA + SG_ BRAKE_PRESSED : 4|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" XXX + +BO_ 479 ACC_CONTROL: 8 EON + SG_ SET_TO_0 : 20|5@0+ (1,0) [0|1] "" XXX + SG_ CONTROL_ON : 23|3@0+ (1,0) [0|5] "" XXX + SG_ GAS_COMMAND : 7|16@0- (1,0) [0|0] "" XXX + SG_ ACCEL_COMMAND : 31|11@0- (0.01,0) [0|0] "m/s2" XXX + SG_ BRAKE_LIGHTS : 62|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_REQUEST : 34|1@0+ (1,0) [0|1] "" XXX + SG_ STANDSTILL : 35|1@0+ (1,0) [0|1] "" XXX + SG_ STANDSTILL_RELEASE : 36|1@0+ (1,0) [0|1] "" XXX + SG_ AEB_STATUS : 33|1@0+ (1,0) [0|1] "" XXX + SG_ AEB_BRAKING : 47|1@0+ (1,0) [0|1] "" XXX + SG_ AEB_PREPARE : 43|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 495 ACC_CONTROL_ON: 8 XXX + SG_ SET_TO_75 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ SET_TO_30 : 39|8@0+ (1,0) [0|255] "" XXX + SG_ ZEROS_BOH : 23|8@0+ (1,0) [0|255] "" XXX + SG_ ZEROS_BOH2 : 47|16@0+ (1,0) [0|255] "" XXX + SG_ SET_TO_FF : 15|8@0+ (1,0) [0|255] "" XXX + SG_ SET_TO_3 : 6|7@0+ (1,0) [0|4095] "" XXX + SG_ CONTROL_ON : 7|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + +BO_ 829 LKAS_HUD: 8 XXX + SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" XXX + SG_ BOH : 6|7@0+ (1,0) [0|127] "" XXX + SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" XXX + SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" XXX + SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" XXX + SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" XXX + SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" XXX + SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" XXX + SG_ DTC : 13|1@0+ (1,0) [0|1] "" XXX + SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" XXX + SG_ BEEP : 17|2@0+ (1,0) [0|1] "" XXX + SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" XXX + SG_ BOH_2 : 23|2@0+ (1,0) [0|4] "" XXX + SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" XXX + SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" XXX + SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" XXX + SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ LANE_LINES : 36|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + +BO_ 1302 ODOMETER: 8 XXX + SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +CM_ SG_ 479 CONTROL_ON "Set to 5 when car is being controlled"; +CM_ SG_ 479 AEB_STATUS "set for the duration of AEB event"; +CM_ SG_ 479 AEB_BRAKING "set when braking is commanded during AEB event"; +CM_ SG_ 479 AEB_PREPARE "set 1s before AEB"; +CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnings etc..."; +CM_ SG_ 829 LANE_LINES "related to lane lines on cluster, left/right white/green"; + +VAL_ 419 GEAR_SHIFTER 2 "S" 32 "D" 16 "N" 8 "R" 4 "P"; +VAL_ 419 GEAR 26 "S" 20 "D" 19 "N" 18 "R" 17 "P"; +VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep"; +VAL_ 829 LANE_LINES 7 "both_lines_green" 6 "both_lines_white" 2 "left_line_white" 0 "no_lines"; diff --git a/hyundai_canfd.dbc b/hyundai_canfd.dbc index 8d27594528..1ef67c044a 100644 --- a/hyundai_canfd.dbc +++ b/hyundai_canfd.dbc @@ -263,7 +263,7 @@ BO_ 416 SCC_CONTROL: 32 ADRV SG_ aReqValue : 128|11@1+ (0.01,-10.23) [-10.23|10.24] "m/s^2" XXX SG_ ZEROS_7 : 63|8@0+ (1,0) [0|255] "" XXX SG_ ACCMode : 68|3@1+ (1,0) [0|7] "" XXX - SG_ NEW_SIGNAL_12 : 35|9@1+ (0.1,0) [0|255] "" XXX + SG_ ACC_ObjRelSpd : 35|9@1+ (0.1,-16.4) [-16.4|34.7] "m/s" XXX SG_ JerkLowerLimit : 166|7@0+ (0.1,0) [0|12.7] "m/s^3" XXX SG_ StopReq : 184|1@0+ (1,0) [0|1] "" XXX SG_ NEW_SIGNAL_15 : 192|11@1+ (0.1,0) [0|204.7] "m" XXX diff --git a/tesla_can.dbc b/tesla_can.dbc index db8d67e0bc..56624c3e54 100644 --- a/tesla_can.dbc +++ b/tesla_can.dbc @@ -131,6 +131,19 @@ BO_ 880 EPAS_sysStatus: 8 EPAS SG_ EPAS_sysStatusCounter : 51|4@0+ (1,0) [0|15] "" NEO SG_ EPAS_torsionBarTorque : 19|12@0+ (0.01,-20.5) [0|0] "Nm" NEO +BO_ 305 EPAS3P_sysStatus: 8 NEO + SG_ EPAS_currentTuneMode : 7|4@0+ (1,0) [0|0] "" NEO + SG_ EPAS_eacErrorCode : 23|4@0+ (1,0) [0|15] "" NEO + SG_ EPAS_eacStatus : 55|3@0+ (1,0) [0|7] "" NEO + SG_ EPAS_handsOnLevel : 39|2@0+ (1,0) [0|3] "" NEO + SG_ EPAS_internalSAS : 37|14@0+ (0.1,-819.2) [-819.2|819] "deg" NEO + SG_ EPAS_steeringFault : 2|1@0+ (1,0) [0|1] "" NEO + SG_ EPAS_steeringRackForce : 1|10@0+ (50,-25575) [-25575|25575] "N" NEO + SG_ EPAS_steeringReduced : 3|1@0+ (1,0) [0|1] "" NEO + SG_ EPAS_sysStatusChecksum : 63|8@0+ (1,0) [0|255] "" NEO + SG_ EPAS_sysStatusCounter : 51|4@0+ (1,0) [0|15] "" NEO + SG_ EPAS_torsionBarTorque : 19|12@0+ (0.01,-20.5) [-20.5|20.45] "Nm" NEO + BO_ 3 STW_ANGL_STAT: 8 STW SG_ StW_Angl : 5|14@0+ (0.5,-2048) [0|0] "deg" NEO SG_ StW_AnglSpd : 21|14@0+ (0.5,-2048) [0|0] "/s" NEO @@ -708,6 +721,10 @@ BO_ 1001 DAS_bodyControls: 8 XXX SG_ DAS_bodyControlsCounter : 52|4@1+ (1,0) [0|15] "" XXX SG_ DAS_bodyControlsChecksum : 56|8@1+ (1,0) [0|255] "" XXX +BO_ 780 DriverSeat: 8 XXX + SG_ occupancyStatus : 16|3@1+ (1,0) [0|7] "" XXX + SG_ buckleStatus : 19|2@1+ (1,0) [0|3] "" XXX + VAL_ 3 StW_Angl 16383 "SNA" ; VAL_ 3 StW_AnglSens_Id 2 "MUST" 0 "PSBL" 1 "SELF" ; VAL_ 3 StW_AnglSens_Stat 2 "ERR" 3 "ERR_INI" 1 "INI" 0 "OK" ; @@ -802,6 +819,8 @@ VAL_ 697 DAS_jerkMin 511 "SNA" ; VAL_ 697 DAS_jerkMax 255 "SNA" ; VAL_ 697 DAS_accelMin 511 "SNA" ; VAL_ 697 DAS_accelMax 511 "SNA" ; +VAL_ 780 occupancyStatus 1 "OCCUPIED" 0 "UNOCCUPIED" ; +VAL_ 780 buckleStatus 1 "LATCHED" 0 "UNLATCHED" ; VAL_ 792 BOOT_STATE 2 "Init" 3 "SNA" 0 "closed" 1 "open" ; VAL_ 792 CERRD 1 "CAN error detect" 0 "no Can error detected" ; VAL_ 792 DAY 1 "Init" 0 "SNA" ; diff --git a/tesla_model3_party.dbc b/tesla_model3_party.dbc new file mode 100644 index 0000000000..20e30e6aaf --- /dev/null +++ b/tesla_model3_party.dbc @@ -0,0 +1,361 @@ +VERSION "" + + +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_ + SG_MUL_VAL_ + +BS_: + +BU_: CH DIPF DIPR ETH FC HVI HVS PARTY SDCV VEH VIRT + + +BO_ 962 VCLEFT_switchStatus: 8 PARTY + SG_ VCLEFT_rearHVACButtonPressed m0 : 61|1@1+ (1,0) [0|1] "" X + SG_ VCLEFT_brakePressed m0 : 60|1@1+ (1,0) [0|1] "" X + SG_ VCLEFT_rearRightOccupancySwitch m0 : 58|2@1+ (1,0) [0|3] "" X + SG_ VCLEFT_rearLeftOccupancySwitch m0 : 56|2@1+ (1,0) [0|3] "" X + SG_ VCLEFT_rearCenterOccupancySwitch m0 : 54|2@1+ (1,0) [0|3] "" X + SG_ VCLEFT_rearLeftBuckleSwitch m0 : 52|2@1+ (1,0) [0|3] "" X + SG_ VCLEFT_frontOccupancySwitch m0 : 50|2@1+ (1,0) [0|3] "" X + SG_ VCLEFT_frontBuckleSwitch m0 : 48|2@1+ (1,0) [0|3] "" ocs1p + SG_ VCLEFT_btnWindowSwPackAutoDownRR m0 : 47|1@1+ (1,0) [0|1] "" X + SG_ VCLEFT_btnWindowSwPackDownRR m0 : 46|1@1+ (1,0) [0|1] "" X + SG_ VCLEFT_btnWindowSwPackAutoUpRR m0 : 45|1@1+ (1,0) [0|1] "" X + SG_ VCLEFT_btnWindowSwPackUpRR m0 : 44|1@1+ (1,0) [0|1] "" X + SG_ VCLEFT_btnWindowSwPackAutoDownRF m0 : 43|1@1+ (1,0) [0|1] "" X + SG_ VCLEFT_btnWindowSwPackDownRF m0 : 42|1@1+ (1,0) [0|1] "" X + SG_ VCLEFT_btnWindowSwPackAutoUpRF m0 : 41|1@1+ (1,0) [0|1] "" X + SG_ VCLEFT_btnWindowSwPackUpRF m0 : 40|1@1+ (1,0) [0|1] "" X + SG_ VCLEFT_btnWindowSwPackAutoDownLR m0 : 39|1@1+ (1,0) [0|1] "" X + SG_ VCLEFT_btnWindowSwPackDownLR m0 : 38|1@1+ (1,0) [0|1] "" X + SG_ VCLEFT_btnWindowSwPackAutoUpLR m0 : 37|1@1+ (1,0) [0|1] "" X + SG_ VCLEFT_btnWindowSwPackUpLR m0 : 36|1@1+ (1,0) [0|1] "" X + SG_ VCLEFT_btnWindowAutoDownLR m1 : 35|1@1+ (1,0) [0|1] "" X + SG_ VCLEFT_btnWindowSwPackAutoDownLF m0 : 35|1@1+ (1,0) [0|1] "" X + SG_ VCLEFT_btnWindowDownLR m1 : 34|1@1+ (1,0) [0|1] "" X + SG_ VCLEFT_btnWindowSwPackDownLF m0 : 34|1@1+ (1,0) [0|1] "" X + SG_ VCLEFT_btnWindowAutoUpLR m1 : 33|1@1+ (1,0) [0|1] "" X + SG_ VCLEFT_btnWindowSwPackAutoUpLF m0 : 33|1@1+ (1,0) [0|1] "" X + SG_ VCLEFT_btnWindowUpLR m1 : 32|1@1+ (1,0) [0|1] "" X + SG_ VCLEFT_btnWindowSwPackUpLF m0 : 32|1@1+ (1,0) [0|1] "" X + SG_ VCLEFT_frontSeatLumbarOut m0 : 30|2@1+ (1,0) [0|3] "" X + SG_ VCLEFT_frontSeatLumbarIn m0 : 28|2@1+ (1,0) [0|3] "" X + SG_ VCLEFT_frontSeatLumbarUp m0 : 26|2@1+ (1,0) [0|3] "" X + SG_ VCLEFT_swcRightScrollTicks m1 : 24|6@1- (1,0) [-32|31] "" X + SG_ VCLEFT_frontSeatLumbarDown m0 : 24|2@1+ (1,0) [0|3] "" X + SG_ VCLEFT_frontSeatBackrestForward m0 : 22|2@1+ (1,0) [0|3] "" X + SG_ VCLEFT_frontSeatBackrestBack m0 : 20|2@1+ (1,0) [0|3] "" X + SG_ VCLEFT_frontSeatLiftUp m0 : 18|2@1+ (1,0) [0|3] "" X + SG_ VCLEFT_frontSeatLiftDown m0 : 16|2@1+ (1,0) [0|3] "" X + SG_ VCLEFT_swcLeftScrollTicks m1 : 16|6@1- (1,0) [-32|31] "" X + SG_ VCLEFT_frontSeatTiltUp m0 : 14|2@1+ (1,0) [0|3] "" X + SG_ VCLEFT_swcLeftTiltLeft m1 : 14|2@1+ (1,0) [0|3] "" X + SG_ VCLEFT_swcRightPressed m1 : 12|2@1+ (1,0) [0|3] "" X + SG_ VCLEFT_frontSeatTiltDown m0 : 12|2@1+ (1,0) [0|3] "" X + SG_ VCLEFT_frontSeatTrackForward m0 : 10|2@1+ (1,0) [0|3] "" X + SG_ VCLEFT_swcRightTiltRight m1 : 10|2@1+ (1,0) [0|3] "" X + SG_ VCLEFT_swcRightTiltLeft m1 : 8|2@1+ (1,0) [0|3] "" X + SG_ VCLEFT_frontSeatTrackBack m0 : 8|2@1+ (1,0) [0|3] "" X + SG_ VCLEFT_swcLeftPressed m1 : 5|2@1+ (1,0) [0|3] "" X + SG_ VCLEFT_rightMirrorTilt m0 : 5|3@1+ (1,0) [0|4] "" X + SG_ VCLEFT_driverPresent m0 : 4|1@1+ (1,0) [0|1] "" das + SG_ VCLEFT_hazardButtonPressed m0 : 3|1@1+ (1,0) [0|1] "" X + SG_ VCLEFT_swcLeftTiltRight m1 : 3|2@1+ (1,0) [0|3] "" X + SG_ VCLEFT_hornSwitchPressed m0 : 2|1@1+ (1,0) [0|1] "" X + SG_ VCLEFT_switchStatusIndex M : 0|2@1+ (1,0) [0|2] "" X + +BO_ 905 DAS_status2: 8 PARTY + SG_ DAS_status2Checksum : 56|8@1+ (1,0) [0|255] "" aps + SG_ DAS_status2Counter : 52|4@1+ (1,0) [0|15] "" aps + SG_ DAS_longCollisionWarning : 48|4@1+ (1,0) [0|15] "" aps + SG_ DAS_ppOffsetDesiredRamp : 40|8@1+ (0.01,-1.28) [-1.28|1.27] "m" aps + SG_ DAS_driverInteractionLevel : 38|2@1+ (1,0) [0|2] "" aps + SG_ DAS_robState : 36|2@1+ (1,0) [0|3] "" aps + SG_ DAS_radarTelemetry : 34|2@1+ (1,0) [0|2] "" aps + SG_ DAS_lssState : 31|3@1+ (1,0) [0|7] "" aps + SG_ DAS_ACC_report : 26|5@1+ (1,0) [0|24] "" aps + SG_ DAS_pmmCameraFaultReason : 24|2@1+ (1,0) [0|2] "" aps + SG_ DAS_pmmSysFaultReason : 21|3@1+ (1,0) [0|7] "" aps + SG_ DAS_pmmRadarFaultReason : 19|2@1+ (1,0) [0|2] "" aps + SG_ DAS_pmmUltrasonicsFaultReason : 16|3@1+ (1,0) [0|4] "" aps + SG_ DAS_activationFailureStatus : 14|2@1+ (1,0) [0|2] "" aps + SG_ DAS_pmmLoggingRequest : 13|1@1+ (1,0) [0|1] "" aps + SG_ DAS_pmmObstacleSeverity : 10|3@1+ (1,0) [0|7] "" aps + SG_ DAS_accSpeedLimit : 0|10@1+ (0.2,0) [0|204.6] "mph" aps + +BO_ 264 DI_torque: 8 PARTY + SG_ DI_axleSpeed : 40|16@1- (0.1,0.0) [-2750|2750] "RPM" epas3s + SG_ DI_torqueActual : 27|13@1- (2,0) [-7500|7500] "Nm" X + SG_ DI_torqueCommand : 12|13@1- (2,0) [-7500|7500] "Nm" X + SG_ DI_torqueCounter : 8|4@1+ (1,0) [0|15] "" epas3s + SG_ DI_torqueChecksum : 0|8@1+ (1,0) [0|255] "" epas3s + +BO_ 585 SCCM_leftStalk: 3 PARTY + SG_ SCCM_leftStalkReserved1 : 19|5@1+ (1,0) [0|31] "" X + SG_ SCCM_turnIndicatorStalkStatus : 16|3@1+ (1,0) [0|5] "" park + SG_ SCCM_washWipeButtonStatus : 14|2@1+ (1,0) [0|3] "" X + SG_ SCCM_highBeamStalkStatus : 12|2@1+ (1,0) [0|3] "" X + SG_ SCCM_leftStalkCounter : 8|4@1+ (1,0) [0|15] "" X + SG_ SCCM_leftStalkCrc : 0|8@1+ (1,0) [0|255] "" X + +BO_ 280 DI_systemStatus: 8 PARTY + SG_ DI_trackModeState : 48|2@1+ (1,0) [0|2] "" X + SG_ DI_keepAliveRequest : 47|1@1+ (1,0) [0|1] "" X + SG_ DI_proximity : 46|1@1+ (1,0) [0|1] "" X + SG_ DI_epbRequest : 44|2@1+ (1,0) [0|2] "" X + SG_ DI_tractionControlMode : 40|3@1+ (1,0) [0|5] "" X + SG_ DI_accelPedalPos : 32|8@1+ (0.4,0) [0|100] "%" X + SG_ DI_immobilizerState : 27|3@1+ (1,0) [0|6] "" X + SG_ DI_regenLight : 26|1@1+ (1,0) [0|1] "" X + SG_ DI_gear : 21|3@1+ (1,0) [0|7] "" park + SG_ DI_brakePedalState : 19|2@1+ (1,0) [0|2] "" X + SG_ DI_systemState : 16|3@1+ (1,0) [0|5] "" X + SG_ DI_systemStatusCounter : 8|4@1+ (1,0) [0|15] "" X + SG_ DI_systemStatusChecksum : 0|8@1+ (1,0) [0|255] "" X + +BO_ 697 DAS_control: 8 PARTY + SG_ DAS_controlChecksum : 56|8@1+ (1,0) [0|255] "" aps + SG_ DAS_controlCounter : 53|3@1+ (1,0) [0|7] "" aps + SG_ DAS_accelMax : 44|9@1+ (0.04,-15) [-15|5.44] "m/s^2" aps + SG_ DAS_accelMin : 35|9@1+ (0.04,-15) [-15|5.44] "m/s^2" aps + SG_ DAS_jerkMax : 27|8@1+ (0.034,0) [0|8.67] "m/s^3" aps + SG_ DAS_jerkMin : 18|9@1+ (0.018,-9.1) [-9.1|0.097999999999999] "m/s^3" aps + SG_ DAS_aebEvent : 16|2@1+ (1,0) [0|3] "" aps + SG_ DAS_accState : 12|4@1+ (1,0) [0|15] "" aps + SG_ DAS_setSpeed : 0|12@1+ (0.1,0) [0|409.4] "kph" aps + +BO_ 341 ESP_B: 8 PARTY + SG_ ESP_wheelRotationChecksum : 56|8@1+ (1,0) [0|255] "" app + SG_ ESP_wheelRotationCounter : 52|4@1+ (1,0) [0|15] "" app + SG_ ESP_vehicleSpeed : 42|10@1+ (0.5,0) [0|511] "kph" app + SG_ ESP_vehicleStandstillSts : 41|1@1+ (1,0) [0|1] "" park + SG_ ESP_wheelSpeedsQF : 40|1@1+ (1,0) [0|1] "" epas3s + SG_ ESP_WheelRotationFrL : 38|2@1+ (1,0) [0|3] "" aps + SG_ ESP_WheelRotationFrR : 36|2@1+ (1,0) [0|3] "" aps + SG_ ESP_WheelRotationReL : 34|2@1+ (1,0) [0|3] "" aps + SG_ ESP_WheelRotationReR : 32|2@1+ (1,0) [0|3] "" aps + SG_ ESP_wheelPulseCountReR : 24|8@1+ (1,0) [0|254] "1" das + SG_ ESP_wheelPulseCountReL : 16|8@1+ (1,0) [0|254] "1" das + SG_ ESP_wheelPulseCountFrR : 8|8@1+ (1,0) [0|254] "1" app + SG_ ESP_wheelPulseCountFrL : 0|8@1+ (1,0) [0|254] "1" app + +BO_ 969 APS_status: 4 PARTY + SG_ APS_statusCounter : 22|4@1+ (1,0) [0|15] "" X + SG_ APS_apbGpioState : 20|2@1+ (1,0) [0|3] "" gtw + SG_ APS_apbStatusMonitorState : 16|3@1+ (1,0) [0|7] "" gtw + SG_ APS_switchState : 15|1@1+ (1,0) [0|1] "" X + SG_ APS_eacInternalState : 12|3@1+ (1,0) [0|7] "" gtw + SG_ APS_appGpioState : 10|2@1+ (1,0) [0|3] "" gtw + SG_ APS_canMaster : 8|2@1+ (1,0) [0|3] "" gtw + SG_ APS_vehBehaviorState : 4|3@1+ (1,0) [0|7] "" gtw + SG_ APS_appStatusMonitorState : 0|3@1+ (1,0) [0|7] "" gtw + +BO_ 925 IBST_status: 5 PARTY + SG_ IBST_sInputRodDriver : 21|12@1+ (0.015625,-5) [-5|47] "mm" gtw + SG_ IBST_internalState : 18|3@1+ (1,0) [0|6] "" gtw + SG_ IBST_driverBrakeApply : 16|2@1+ (1,0) [0|3] "" gtw + SG_ IBST_iBoosterStatus : 12|3@1+ (1,0) [0|6] "" gtw + SG_ IBST_statusCounter : 8|4@1+ (1,0) [0|15] "" X + SG_ IBST_statusChecksum : 0|8@1+ (1,0) [0|255] "" X + +BO_ 880 EPAS3S_sysStatus: 8 PARTY + SG_ EPAS3S_sysStatusChecksum : 63|8@0+ (1,0) [0|255] "" park + SG_ EPAS3S_sysStatusCounter : 51|4@0+ (1,0) [0|15] "" gtw + SG_ EPAS3S_eacStatus : 55|3@0+ (1,0) [0|7] "" das + SG_ EPAS3S_internalSAS : 37|14@0+ (0.1,-819.2) [-819.2|819] "deg" das + SG_ EPAS3S_handsOnLevel : 39|2@0+ (1,0) [0|3] "" das + SG_ EPAS3S_torsionBarTorque : 19|12@0+ (0.01,-20.5) [-20.5|20.45] "Nm" das + SG_ EPAS3S_eacErrorCode : 23|4@0+ (1,0) [0|15] "" das + SG_ EPAS3S_steeringRackForce : 1|10@0+ (50,-25575) [-25575|25575] "N" gtw + SG_ EPAS3S_steeringFault : 2|1@0+ (1,0) [0|1] "" das + SG_ EPAS3S_steeringReduced : 3|1@0+ (1,0) [0|1] "" das + SG_ EPAS3S_internalSASQF : 4|1@0+ (1,0) [0|1] "" gtw + SG_ EPAS3S_currentTuneMode : 7|3@0+ (1,0) [0|5] "" gtw + +BO_ 599 DI_speed: 8 PARTY + SG_ DI_uiSpeedUnits : 32|1@1+ (1,0) [0|1] "" das + SG_ DI_uiSpeed : 24|8@1+ (1,0) [0|254] "" das + SG_ DI_vehicleSpeed : 12|12@1+ (0.08,-40) [-40|285] "kph" park + SG_ DI_speedCounter : 8|4@1+ (1,0) [0|15] "" park + SG_ DI_speedChecksum : 0|8@1+ (1,0) [0|255] "" park + +BO_ 1160 DAS_steeringControl: 4 PARTY + SG_ DAS_steeringControlChecksum : 31|8@0+ (1,0) [0|255] "" aps + SG_ DAS_steeringControlCounter : 19|4@0+ (1,0) [0|15] "" aps + SG_ DAS_steeringControlType : 23|2@0+ (1,0) [0|3] "" aps + SG_ DAS_steeringAngleRequest : 6|15@0+ (0.1,-1638.35) [-1638.35|1638.35] "deg" aps + SG_ DAS_steeringHapticRequest : 7|1@0+ (1,0) [0|1] "" aps + +BO_ 297 SCCM_steeringAngleSensor: 8 PARTY + SG_ SCCM_steeringAngleSensorReservd3 : 56|8@1+ (1,0) [0|255] "" X + SG_ SCCM_steeringAngleSensorReservd2 : 48|8@1+ (1,0) [0|255] "" X + SG_ SCCM_steeringAngleSensorReservd1 : 46|2@1+ (1,0) [0|3] "" X + SG_ SCCM_steeringAngleSpeed : 32|14@1+ (0.5,-4096) [-4096|4095.5] "deg/s" park + SG_ SCCM_steeringAngleValidity : 30|2@1+ (1,0) [0|3] "" park + SG_ SCCM_steeringAngle : 16|14@1+ (0.1,-819.2) [-819.2|819] "deg" epas3s + SG_ SCCM_steeringAngleSensorStatus : 14|2@1+ (1,0) [0|3] "" epas3s + SG_ SCCM_supplierID : 12|2@1+ (1,0) [0|3] "" park + SG_ SCCM_steeringAngleCounter : 8|4@1+ (1,0) [0|15] "" epas3s + SG_ SCCM_steeringAngleCrc : 0|8@1+ (1,0) [0|255] "" epas3s + +BO_ 646 DI_state: 7 ETH + SG_ DI_summonInPanic : 48|1@1+ (1,0) [0|0] "" X + SG_ DI_rollPreventionState : 45|3@1+ (1,0) [0|0] "" X + SG_ DI_vehicleHoldState : 42|3@1+ (1,0) [0|0] "" X + SG_ DI_pmmStatus : 40|2@1+ (1,0) [0|0] "" X + SG_ DI_aebState : 37|3@1+ (1,0) [0|0] "" X + SG_ DI_autopilotRequest : 36|1@1+ (1,0) [0|0] "" X + SG_ DI_parkBrakeState : 32|4@1+ (1,0) [0|0] "" X + SG_ DI_autoparkState : 25|4@1+ (1,0) [0|0] "" X + SG_ DI_speedUnits : 24|1@1+ (1,0) [0|0] "" X + SG_ DI_digitalSpeed : 15|9@1+ (0.5,0) [0|0] "speed" X + SG_ DI_cruiseState : 12|3@1+ (1,0) [0|0] "" X + SG_ DI_locStatusCounter : 8|4@1+ (1,0) [0|0] "" X + SG_ DI_locStatusChecksum : 0|8@1+ (1,0) [0|0] "" X + + + + + + + + +VAL_ 962 VCLEFT_rearRightOccupancySwitch 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF" ; +VAL_ 962 VCLEFT_rearLeftOccupancySwitch 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF" ; +VAL_ 962 VCLEFT_rearCenterOccupancySwitch 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF" ; +VAL_ 962 VCLEFT_rearLeftBuckleSwitch 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF" ; +VAL_ 962 VCLEFT_frontOccupancySwitch 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF" ; +VAL_ 962 VCLEFT_frontBuckleSwitch 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF" ; +VAL_ 962 VCLEFT_frontSeatLumbarOut 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF" ; +VAL_ 962 VCLEFT_frontSeatLumbarIn 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF" ; +VAL_ 962 VCLEFT_frontSeatLumbarUp 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF" ; +VAL_ 962 VCLEFT_frontSeatLumbarDown 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF" ; +VAL_ 962 VCLEFT_frontSeatBackrestForward 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF" ; +VAL_ 962 VCLEFT_frontSeatBackrestBack 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF" ; +VAL_ 962 VCLEFT_frontSeatLiftUp 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF" ; +VAL_ 962 VCLEFT_frontSeatLiftDown 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF" ; +VAL_ 962 VCLEFT_frontSeatTiltUp 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF" ; +VAL_ 962 VCLEFT_swcLeftTiltLeft 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF" ; +VAL_ 962 VCLEFT_swcRightPressed 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF" ; +VAL_ 962 VCLEFT_frontSeatTiltDown 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF" ; +VAL_ 962 VCLEFT_frontSeatTrackForward 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF" ; +VAL_ 962 VCLEFT_swcRightTiltRight 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF" ; +VAL_ 962 VCLEFT_swcRightTiltLeft 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF" ; +VAL_ 962 VCLEFT_frontSeatTrackBack 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF" ; +VAL_ 962 VCLEFT_swcLeftPressed 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF" ; +VAL_ 962 VCLEFT_rightMirrorTilt 4 "MIRROR_TILT_LEFT" 2 "MIRROR_TILT_UP" 3 "MIRROR_TILT_RIGHT" 0 "MIRROR_TILT_STOP" 1 "MIRROR_TILT_DOWN" ; +VAL_ 962 VCLEFT_swcLeftTiltRight 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF" ; +VAL_ 962 VCLEFT_switchStatusIndex 1 "VCLEFT_SWITCH_STATUS_INDEX_1" 2 "VCLEFT_SWITCH_STATUS_INDEX_INVALID" 0 "VCLEFT_SWITCH_STATUS_INDEX_0" ; +VAL_ 905 DAS_longCollisionWarning 7 "FCM_LONG_COLLISION_WARNING_VEHICLE_CUTIN" 0 "FCM_LONG_COLLISION_WARNING_NONE" 4 "FCM_LONG_COLLISION_WARNING_STOPSIGN_STOPLINE" 9 "FCM_LONG_COLLISION_WARNING_VEHICLE_MCVL2" 15 "FCM_LONG_COLLISION_WARNING_SNA" 8 "FCM_LONG_COLLISION_WARNING_VEHICLE_MCVL" 5 "FCM_LONG_COLLISION_WARNING_TFL_STOPLINE" 2 "FCM_LONG_COLLISION_WARNING_PEDESTRIAN" 12 "FCM_LONG_COLLISION_WARNING_VEHICLE_CIPV2" 6 "FCM_LONG_COLLISION_WARNING_VEHICLE_CIPV" 10 "FCM_LONG_COLLISION_WARNING_VEHICLE_MCVR" 3 "FCM_LONG_COLLISION_WARNING_IPSO" 1 "FCM_LONG_COLLISION_WARNING_VEHICLE_UNKNOWN" 11 "FCM_LONG_COLLISION_WARNING_VEHICLE_MCVR2" ; +VAL_ 905 DAS_ppOffsetDesiredRamp 128 "PP_NO_OFFSET" ; +VAL_ 905 DAS_driverInteractionLevel 0 "DRIVER_INTERACTING" 1 "DRIVER_NOT_INTERACTING" 2 "CONTINUED_DRIVER_NOT_INTERACTING" ; +VAL_ 905 DAS_robState 0 "ROB_STATE_INHIBITED" 2 "ROB_STATE_ACTIVE" 3 "ROB_STATE_MAPLESS" 1 "ROB_STATE_MEASURE" ; +VAL_ 905 DAS_radarTelemetry 0 "RADAR_TELEMETRY_IDLE" 1 "RADAR_TELEMETRY_NORMAL" 2 "RADAR_TELEMETRY_URGENT" ; +VAL_ 905 DAS_lssState 7 "LSS_STATE_OFF" 1 "LSS_STATE_LDW" 4 "LSS_STATE_MONITOR" 2 "LSS_STATE_LKA" 3 "LSS_STATE_ELK" 0 "LSS_STATE_FAULT" 5 "LSS_STATE_BLINDSPOT" 6 "LSS_STATE_ABORT" ; +VAL_ 905 DAS_ACC_report 12 "ACC_REPORT_LC_EXTERNAL_STATE_ABORTING" 17 "ACC_REPORT_TARGET_MCP" 11 "ACC_REPORT_LC_HANDS_ON_REQD_STRUCK_OUT" 19 "ACC_REPORT_MCVLR_DPP" 1 "ACC_REPORT_TARGET_CIPV" 15 "ACC_REPORT_RADAR_OBJ_ONE" 16 "ACC_REPORT_RADAR_OBJ_TWO" 14 "ACC_REPORT_LC_EXTERNAL_STATE_ACTIVE_RESTRICTED" 4 "ACC_REPORT_TARGET_MCVR" 20 "ACC_REPORT_MCVLR_IN_PATH" 10 "ACC_REPORT_CSA" 5 "ACC_REPORT_TARGET_CUTIN" 9 "ACC_REPORT_TARGET_TYPE_FAULT" 7 "ACC_REPORT_TARGET_TYPE_TRAFFIC_LIGHT" 6 "ACC_REPORT_TARGET_TYPE_STOP_SIGN" 24 "ACC_REPORT_BEHAVIOR_REPORT" 18 "ACC_REPORT_FLEET_SPEEDS" 2 "ACC_REPORT_TARGET_IN_FRONT_OF_CIPV" 23 "ACC_REPORT_CAMERA_ONLY" 3 "ACC_REPORT_TARGET_MCVL" 22 "ACC_REPORT_RADAR_OBJ_FIVE" 0 "ACC_REPORT_TARGET_NONE" 8 "ACC_REPORT_TARGET_TYPE_IPSO" 21 "ACC_REPORT_CIPV_CUTTING_OUT" 13 "ACC_REPORT_LC_EXTERNAL_STATE_ABORTED" ; +VAL_ 905 DAS_pmmCameraFaultReason 1 "PMM_CAMERA_BLOCKED_FRONT" 2 "PMM_CAMERA_INVALID_MIA" 0 "PMM_CAMERA_NO_FAULT" ; +VAL_ 905 DAS_pmmSysFaultReason 4 "PMM_FAULT_STEERING_ANGLE_RATE" 6 "PMM_FAULT_ROAD_TYPE" 5 "PMM_FAULT_DISABLED_BY_USER" 0 "PMM_FAULT_NONE" 1 "PMM_FAULT_DAS_DISABLED" 3 "PMM_FAULT_DI_FAULT" 2 "PMM_FAULT_SPEED" 7 "PMM_FAULT_BRAKE_PEDAL_INHIBIT" ; +VAL_ 905 DAS_pmmRadarFaultReason 2 "PMM_RADAR_INVALID_MIA" 1 "PMM_RADAR_BLOCKED_FRONT" 0 "PMM_RADAR_NO_FAULT" ; +VAL_ 905 DAS_pmmUltrasonicsFaultReason 2 "PMM_ULTRASONICS_BLOCKED_REAR" 0 "PMM_ULTRASONICS_NO_FAULT" 1 "PMM_ULTRASONICS_BLOCKED_FRONT" 3 "PMM_ULTRASONICS_BLOCKED_BOTH" 4 "PMM_ULTRASONICS_INVALID_MIA" ; +VAL_ 905 DAS_activationFailureStatus 0 "LC_ACTIVATION_IDLE" 2 "LC_ACTIVATION_FAILED_2" 1 "LC_ACTIVATION_FAILED_1" ; +VAL_ 905 DAS_pmmLoggingRequest 0 "FALSE" 1 "TRUE" ; +VAL_ 905 DAS_pmmObstacleSeverity 5 "PMM_CRASH_FRONT" 0 "PMM_NONE" 2 "PMM_IMMINENT_FRONT" 4 "PMM_CRASH_REAR" 1 "PMM_IMMINENT_REAR" 6 "PMM_ACCEL_LIMIT" 7 "PMM_SNA" 3 "PMM_BRAKE_REQUEST" ; +VAL_ 905 DAS_accSpeedLimit 1023 "SNA" 0 "NONE" ; +VAL_ 264 DI_axleSpeed -32768 "SNA" ; +VAL_ 264 DI_torqueActual -4096 "SNA" ; +VAL_ 264 DI_torqueCommand -4096 "SNA" ; +VAL_ 585 SCCM_turnIndicatorStalkStatus 3 "DOWN_1" 5 "SNA" 0 "IDLE" 1 "UP_1" 4 "DOWN_2" 2 "UP_2" ; +VAL_ 585 SCCM_washWipeButtonStatus 3 "SNA" 0 "NOT_PRESSED" 2 "2ND_DETENT" 1 "1ST_DETENT" ; +VAL_ 585 SCCM_highBeamStalkStatus 3 "SNA" 0 "IDLE" 1 "PULL" 2 "PUSH" ; +VAL_ 280 DI_trackModeState 0 "TRACK_MODE_UNAVAILABLE" 1 "TRACK_MODE_AVAILABLE" 2 "TRACK_MODE_ON" ; +VAL_ 280 DI_keepAliveRequest 1 "KEEP_ALIVE" 0 "NO_REQUEST" ; +VAL_ 280 DI_epbRequest 0 "DI_EPBREQUEST_NO_REQUEST" 1 "DI_EPBREQUEST_PARK" 2 "DI_EPBREQUEST_UNPARK" ; +VAL_ 280 DI_tractionControlMode 0 "TC_NORMAL" 1 "TC_SLIP_START" 4 "TC_ROLLS_MODE" 2 "TC_DEV_MODE_1" 5 "TC_DYNO_MODE" 3 "TC_DEV_MODE_2" ; +VAL_ 280 DI_accelPedalPos 255 "SNA" ; +VAL_ 280 DI_immobilizerState 2 "DI_IMM_STATE_AUTHENTICATING" 0 "DI_IMM_STATE_INIT_SNA" 3 "DI_IMM_STATE_DISARMED" 4 "DI_IMM_STATE_IDLE" 6 "DI_IMM_STATE_FAULT" 1 "DI_IMM_STATE_REQUEST" 5 "DI_IMM_STATE_RESET" ; +VAL_ 280 DI_gear 1 "DI_GEAR_P" 0 "DI_GEAR_INVALID" 7 "DI_GEAR_SNA" 2 "DI_GEAR_R" 3 "DI_GEAR_N" 4 "DI_GEAR_D" ; +VAL_ 280 DI_brakePedalState 2 "INVALID" 0 "OFF" 1 "ON" ; +VAL_ 280 DI_systemState 5 "DI_SYS_ENABLE" 1 "DI_SYS_IDLE" 2 "DI_SYS_STANDBY" 0 "DI_SYS_UNAVAILABLE" 3 "DI_SYS_FAULT" 4 "DI_SYS_ABORT" ; +VAL_ 697 DAS_accelMax 511 "SNA" ; +VAL_ 697 DAS_accelMin 511 "SNA" ; +VAL_ 697 DAS_jerkMax 255 "SNA" ; +VAL_ 697 DAS_jerkMin 511 "SNA" ; +VAL_ 697 DAS_aebEvent 2 "AEB_FAULT" 0 "AEB_NOT_ACTIVE" 3 "AEB_SNA" 1 "AEB_ACTIVE" ; +VAL_ 697 DAS_accState 4 "ACC_ON" 9 "APC_PAUSE" 14 "ACC_CANCEL_OUT_OF_CALIBRATION" 10 "APC_UNPARK_COMPLETE" 6 "APC_FORWARD" 3 "ACC_HOLD" 2 "ACC_CANCEL_RADAR_BLIND" 7 "APC_COMPLETE" 1 "ACC_CANCEL_CAMERA_BLIND" 8 "APC_ABORT" 13 "ACC_CANCEL_GENERIC_SILENT" 5 "APC_BACKWARD" 11 "APC_SELFPARK_START" 0 "ACC_CANCEL_GENERIC" 12 "ACC_CANCEL_PATH_NOT_CLEAR" 15 "FAULT_SNA" ; +VAL_ 697 DAS_setSpeed 4095 "SNA" ; +VAL_ 341 ESP_vehicleSpeed 1023 "ESP_VEHICLE_SPEED_SNA" ; +VAL_ 341 ESP_vehicleStandstillSts 1 "STANDSTILL" 0 "NOT_STANDSTILL" ; +VAL_ 341 ESP_wheelSpeedsQF 0 "ONE_OR_MORE_WSS_INVALID" 1 "ALL_WSS_VALID" ; +VAL_ 341 ESP_WheelRotationFrL 1 "WR_BACKWARD" 0 "WR_FORWARD" 3 "WR_NOT_DEFINABLE" 2 "WR_STANDSTILL" ; +VAL_ 341 ESP_WheelRotationFrR 1 "WR_BACKWARD" 0 "WR_FORWARD" 3 "WR_NOT_DEFINABLE" 2 "WR_STANDSTILL" ; +VAL_ 341 ESP_WheelRotationReL 1 "WR_BACKWARD" 0 "WR_FORWARD" 3 "WR_NOT_DEFINABLE" 2 "WR_STANDSTILL" ; +VAL_ 341 ESP_WheelRotationReR 1 "WR_BACKWARD" 0 "WR_FORWARD" 3 "WR_NOT_DEFINABLE" 2 "WR_STANDSTILL" ; +VAL_ 341 ESP_wheelPulseCountReR 255 "SNA" ; +VAL_ 341 ESP_wheelPulseCountReL 255 "SNA" ; +VAL_ 341 ESP_wheelPulseCountFrR 255 "SNA" ; +VAL_ 341 ESP_wheelPulseCountFrL 255 "SNA" ; +VAL_ 969 APS_apbGpioState 0 "AP_GPIO_STATE_PWR_DOWN_REBOOT" 3 "AP_GPIO_STATE_HEALTHY" 1 "AP_GPIO_STATE_DISABLED" 2 "AP_GPIO_STATE_CRITICAL" ; +VAL_ 969 APS_apbStatusMonitorState 1 "STATUS_MONITOR_STATE_PWR_OFF" 2 "STATUS_MONITOR_STATE_INIT" 7 "STATUS_MONITOR_NUM_STATES" 0 "STATUS_MONITOR_STATE_UNKNOWN" 4 "STATUS_MONITOR_STATE_CRITICAL" 6 "STATUS_MONITOR_STATE_RECOVERY" 5 "STATUS_MONITOR_STATE_SHUTTING_DOWN" 3 "STATUS_MONITOR_STATE_NOMINAL" ; +VAL_ 969 APS_eacInternalState 1 "APS_EAC_STATE_MOMENTARY" 3 "APS_EAC_STATE_AUTOPARK" 5 "APS_EAC_STATE_OVERRIDE" 4 "APS_EAC_STATE_INHIBIT" 0 "APS_EAC_STATE_INIT" 2 "APS_EAC_STATE_CONTINUOUS" 7 "APS_EAC_NUM_STATES" 6 "APS_EAC_STATE_LSS" ; +VAL_ 969 APS_appGpioState 0 "AP_GPIO_STATE_PWR_DOWN_REBOOT" 3 "AP_GPIO_STATE_HEALTHY" 1 "AP_GPIO_STATE_DISABLED" 2 "AP_GPIO_STATE_CRITICAL" ; +VAL_ 969 APS_canMaster 0 "CAN_MASTER_APS" 2 "CAN_MASTER_APB" 3 "CAN_MASTER_SNA" 1 "CAN_MASTER_APP" ; +VAL_ 969 APS_vehBehaviorState 0 "VEH_BEHAVIOR_STATE_UNKNOWN" 3 "VEH_BEHAVIOR_STATE_APS_BRIDGE_APP" 1 "VEH_BEHAVIOR_STATE_APS_AVAILABLE" 5 "VEH_BEHAVIOR_STATE_APS_FAIL_SAFE" 7 "VEH_BEHAVIOR_NUM_STATES" 2 "VEH_BEHAVIOR_STATE_APS_CONTROL" 6 "VEH_BEHAVIOR_STATE_APS_OVERRIDE" 4 "VEH_BEHAVIOR_STATE_APS_BRIDGE_APB" ; +VAL_ 969 APS_appStatusMonitorState 1 "STATUS_MONITOR_STATE_PWR_OFF" 2 "STATUS_MONITOR_STATE_INIT" 7 "STATUS_MONITOR_NUM_STATES" 0 "STATUS_MONITOR_STATE_UNKNOWN" 4 "STATUS_MONITOR_STATE_CRITICAL" 6 "STATUS_MONITOR_STATE_RECOVERY" 5 "STATUS_MONITOR_STATE_SHUTTING_DOWN" 3 "STATUS_MONITOR_STATE_NOMINAL" ; +VAL_ 925 IBST_internalState 5 "TRANSITION_TO_IDLE" 0 "NO_MODE_ACTIVE" 4 "DIAGNOSTIC" 6 "POST_DRIVE_CHECK" 1 "PRE_DRIVE_CHECK" 3 "EXTERNAL_BRAKE_REQUEST" 2 "LOCAL_BRAKE_REQUEST" ; +VAL_ 925 IBST_driverBrakeApply 1 "BRAKES_NOT_APPLIED" 2 "DRIVER_APPLYING_BRAKES" 3 "FAULT" 0 "NOT_INIT_OR_OFF" ; +VAL_ 925 IBST_iBoosterStatus 6 "IBOOSTER_ACTUATION" 4 "IBOOSTER_ACTIVE_GOOD_CHECK" 2 "IBOOSTER_FAILURE" 5 "IBOOSTER_READY" 3 "IBOOSTER_DIAGNOSTIC" 0 "IBOOSTER_OFF" 1 "IBOOSTER_INIT" ; +VAL_ 880 EPAS3S_eacStatus 7 "SNA" 2 "EAC_ACTIVE" 4 "LANE_KEEP_ASSIST" 3 "EAC_FAULT" 1 "EAC_AVAILABLE" 5 "EMERGENCY_LANE_KEEP" 0 "EAC_INHIBITED" ; +VAL_ 880 EPAS3S_handsOnLevel 1 "LEVEL_1" 0 "LEVEL_0" 3 "LEVEL_3" 2 "LEVEL_2" ; +VAL_ 880 EPAS3S_torsionBarTorque 4095 "SNA" 4094 "UNDEFINABLE_DATA" ; +VAL_ 880 EPAS3S_eacErrorCode 15 "SNA" 11 "EAC_ERROR_HIGH_TORSION_SAFETY" 4 "EAC_ERROR_TMP_FAULT" 2 "EAC_ERROR_MAX_SPEED" 7 "EAC_ERROR_HIGH_ANGLE_RATE_REQ" 0 "EAC_ERROR_IDLE" 10 "EAC_ERROR_HIGH_MMOT_SAFETY" 6 "EAC_ERROR_HIGH_ANGLE_REQ" 8 "EAC_ERROR_HIGH_ANGLE_SAFETY" 5 "EAR_ERROR_MAX_STEER_DELTA" 13 "EAC_ERROR_PINION_VEL_DIFF" 1 "EAC_ERROR_MIN_SPEED" 14 "EAC_EXTERNAL_MONITOR_INHIBIT" 12 "EAC_ERROR_LOW_ASSIST" 9 "EAC_ERROR_HIGH_ANGLE_RATE_SAFETY" 3 "EAC_ERROR_HANDS_ON" ; +VAL_ 880 EPAS3S_steeringRackForce 1023 "SNA" 1022 "NOT_IN_SPEC" ; +VAL_ 880 EPAS3S_steeringFault 0 "NO_FAULT" 1 "FAULT" ; +VAL_ 880 EPAS3S_steeringReduced 0 "NORMAL_ASSIST" 1 "REDUCED_ASSIST" ; +VAL_ 880 EPAS3S_internalSASQF 1 "IN_SPEC" 0 "UNDEFINABLE_ACCURACY" ; +VAL_ 880 EPAS3S_currentTuneMode 3 "STEERING_TUNE_RWD_COMFORT" 1 "STEERING_TUNE_DM_STANDARD" 5 "STEERING_TUNE_RWD_SPORT" 0 "STEERING_TUNE_DM_COMFORT" 4 "STEERING_TUNE_RWD_STANDARD" 2 "STEERING_TUNE_DM_SPORT" ; +VAL_ 599 DI_uiSpeedUnits 0 "DI_SPEED_MPH" 1 "DI_SPEED_KPH" ; +VAL_ 599 DI_uiSpeed 255 "DI_UI_SPEED_SNA" ; +VAL_ 599 DI_vehicleSpeed 4095 "SNA" ; +VAL_ 1160 DAS_steeringControlType 2 "LANE_KEEP_ASSIST" 0 "NONE" 1 "ANGLE_CONTROL" 3 "EMERGENCY_LANE_KEEP" ; +VAL_ 1160 DAS_steeringAngleRequest 16384 "ZERO_ANGLE" ; +VAL_ 297 SCCM_steeringAngleValidity 3 "SNA" 2 "INIT" 0 "INVALID" 1 "VALID" ; +VAL_ 297 SCCM_steeringAngleSensorStatus 0 "OK" 1 "INIT" 2 "ERROR" 3 "ERROR_INIT" ; +VAL_ 646 DI_rollPreventionState 0 "UNAVAILABLE" 1 "STANDBY" 2 "READY" 3 "BUILD" 4 "HOLD" 5 "PARK" 6 "FAULT" 7 "INIT" ; +VAL_ 646 DI_vehicleHoldState 0 "UNAVAILABLE" 1 "STANDBY" 2 "BLEND_IN" 3 "STANDSTILL" 4 "BLEND_OUT" 5 "PARK" 6 "FAULT" 7 "INIT" ; +VAL_ 646 DI_pmmStatus 0 "INACTIVE" 1 "ACTIVE" 2 "LOGGING_ACTIVE" 3 "SNA" ; +VAL_ 646 DI_aebState 0 "UNAVAILABLE" 1 "STANDBY" 2 "ENABLED" 3 "STANDSTILL" 4 "FAULT" 7 "SNA" ; +VAL_ 646 DI_autopilotRequest 0 "IDLE" 1 "ACTIVATE" ; +VAL_ 646 DI_parkBrakeState 0 "UNAVAILABLE" 1 "RELEASED" 2 "REQUESTED" 3 "APPLIED" 4 "FAULTED" 5 "PANIC_EPB" 6 "PANIC_SKID" 7 "RELEASING" 15 "SNA" ; +VAL_ 646 DI_autoparkState 0 "UNAVAILABLE" 1 "STANDBY" 2 "STARTED" 3 "ACTIVE" 4 "COMPLETE" 5 "PAUSED" 6 "ABORTED" 7 "RESUMED" 8 "UNPARK_COMPLETE" 9 "SELFPARK_STARTED" 15 "SNA" ; +VAL_ 646 DI_speedUnits 0 "MPH" 1 "KPH" ; +VAL_ 646 DI_cruiseState 0 "UNAVAILABLE" 1 "STANDBY" 2 "ENABLED" 3 "STANDSTILL" 4 "OVERRIDE" 5 "FAULT" 6 "PRE_FAULT" 7 "PRE_CANCEL" ; + + + diff --git a/tesla_model3_vehicle.dbc b/tesla_model3_vehicle.dbc new file mode 100644 index 0000000000..604db8fe27 --- /dev/null +++ b/tesla_model3_vehicle.dbc @@ -0,0 +1,339 @@ +VERSION "" + + +BU_: CH DIPF DIPR ETH FC HVI HVS PARTY SDCV VEH VIRT + + +BO_ 962 VCLEFT_switchStatus: 8 VEH + SG_ VCLEFT_frontBuckleSwitch m0: 48|2@1+ (1,0) [0|3] "" gtw + SG_ VCLEFT_btnWindowSwPackUpLF m0: 32|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_frontSeatTrackBack m0: 8|2@1+ (1,0) [0|3] "" gtw + SG_ VCLEFT_btnWindowSwPackAutoDownLF m0: 35|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_btnWindowSwPackDownRR m0: 46|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_btnWindowSwPackAutoUpRR m0: 45|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_btnWindowSwPackAutoDownRR m0: 47|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_rightMirrorTilt m0: 5|3@1+ (1,0) [0|4] "" vcright + SG_ VCLEFT_btnWindowSwPackUpRR m0: 44|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_frontOccupancySwitch m0: 50|2@1+ (1,0) [0|3] "" gtw + SG_ VCLEFT_swcRightTiltLeft m1: 8|2@1+ (1,0) [0|3] "" das + SG_ VCLEFT_rearRightOccupancySwitch m0: 58|2@1+ (1,0) [0|3] "" gtw + SG_ VCLEFT_btnWindowSwPackDownLF m0: 34|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_btnWindowSwPackAutoUpLF m0: 33|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_swcLeftTiltRight m1: 3|2@1+ (1,0) [0|3] "" das + SG_ VCLEFT_frontSeatBackrestForward m0: 22|2@1+ (1,0) [0|3] "" gtw + SG_ VCLEFT_swcRightTiltRight m1: 10|2@1+ (1,0) [0|3] "" das + SG_ VCLEFT_swcLeftScrollTicks m1: 16|6@1- (1,0) [-32|31] "" das + SG_ VCLEFT_btnWindowUpLR m1: 32|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_btnWindowAutoDownLR m1: 35|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_btnWindowSwPackDownRF m0: 42|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_btnWindowSwPackAutoUpRF m0: 41|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_frontSeatLumbarIn m0: 28|2@1+ (1,0) [0|3] "" gtw + SG_ VCLEFT_frontSeatLiftUp m0: 18|2@1+ (1,0) [0|3] "" gtw + SG_ VCLEFT_btnWindowSwPackDownLR m0: 38|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_btnWindowSwPackAutoUpLR m0: 37|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_frontSeatLumbarDown m0: 24|2@1+ (1,0) [0|3] "" gtw + SG_ VCLEFT_driverPresent m0: 4|1@1+ (1,0) [0|1] "" das + SG_ VCLEFT_frontSeatTiltDown m0: 12|2@1+ (1,0) [0|3] "" gtw + SG_ VCLEFT_frontSeatTrackForward m0: 10|2@1+ (1,0) [0|3] "" gtw + SG_ VCLEFT_rearLeftBuckleSwitch m0: 52|2@1+ (1,0) [0|3] "" gtw + SG_ VCLEFT_hazardButtonPressed m0: 3|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_swcRightScrollTicks m1: 24|6@1- (1,0) [-32|31] "" das + SG_ VCLEFT_swcRightPressed m1: 12|2@1+ (1,0) [0|3] "" das + SG_ VCLEFT_frontSeatLumbarOut m0: 30|2@1+ (1,0) [0|3] "" gtw + SG_ VCLEFT_brakePressed m0: 60|1@1+ (1,0) [0|1] "" di + SG_ VCLEFT_swcLeftTiltLeft m1: 14|2@1+ (1,0) [0|3] "" das + SG_ VCLEFT_swcLeftPressed m1: 5|2@1+ (1,0) [0|3] "" das + SG_ VCLEFT_btnWindowSwPackUpLR m0: 36|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_frontSeatTiltUp m0: 14|2@1+ (1,0) [0|3] "" gtw + SG_ VCLEFT_rearLeftOccupancySwitch m0: 56|2@1+ (1,0) [0|3] "" gtw + SG_ VCLEFT_frontSeatBackrestBack m0: 20|2@1+ (1,0) [0|3] "" gtw + SG_ VCLEFT_btnWindowSwPackAutoDownLR m0: 39|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_rearCenterOccupancySwitch m0: 54|2@1+ (1,0) [0|3] "" gtw + SG_ VCLEFT_frontSeatLumbarUp m0: 26|2@1+ (1,0) [0|3] "" gtw + SG_ VCLEFT_frontSeatLiftDown m0: 16|2@1+ (1,0) [0|3] "" gtw + SG_ VCLEFT_hornSwitchPressed m0: 2|1@1+ (1,0) [0|1] "" app + SG_ VCLEFT_btnWindowSwPackUpRF m0: 40|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_btnWindowAutoUpLR m1: 33|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_btnWindowSwPackAutoDownRF m0: 43|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_switchStatusIndex M: 0|2@1+ (1,0) [0|2] "" X + SG_ VCLEFT_btnWindowDownLR m1: 34|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_rearHVACButtonPressed m0: 61|1@1+ (1,0) [0|1] "" gtw + +BO_ 259 VCRIGHT_doorStatus: 8 VEH + SG_ VCRIGHT_reservedForBackCompat : 28|2@1+ (1,0) [0|3] "" X + SG_ VCRIGHT_trunkLatchStatus : 56|4@1+ (1,0) [0|8] "" di + SG_ VCRIGHT_mirrorFoldState : 52|3@1+ (1,0) [0|4] "" gtw + SG_ VCRIGHT_rearLatchStatus : 4|4@1+ (1,0) [0|8] "" aps + SG_ VCRIGHT_mirrorTiltYPosition : 41|8@1+ (0.02,0) [0|5] "V" gtw + SG_ VCRIGHT_frontRelActuatorSwitch : 12|1@1+ (1,0) [0|1] "" gtw + SG_ VCRIGHT_mirrorRecallState : 60|3@1+ (1,0) [0|5] "" gtw + SG_ VCRIGHT_frontIntSwitchPressed : 31|1@1+ (1,0) [0|1] "" aps + SG_ VCRIGHT_mirrorState : 49|3@1+ (1,0) [0|4] "" gtw + SG_ VCRIGHT_rearRelActuatorSwitch : 13|1@1+ (1,0) [0|1] "" gtw + SG_ VCRIGHT_frontHandlePulledPersist : 30|1@1+ (1,0) [0|1] "" gtw + SG_ VCRIGHT_mirrorTiltXPosition : 33|8@1+ (0.02,0) [0|5] "V" gtw + SG_ VCRIGHT_mirrorDipped : 63|1@1+ (1,0) [0|1] "" X + SG_ VCRIGHT_frontHandlePulled : 10|1@1+ (1,0) [0|1] "" aps + SG_ VCRIGHT_frontLatchStatus : 0|4@1+ (1,0) [0|8] "" aps + SG_ VCRIGHT_rearHandlePulled : 11|1@1+ (1,0) [0|1] "" aps + SG_ VCRIGHT_frontHandlePWM : 14|7@1+ (1,0) [0|100] "%" X + SG_ VCRIGHT_frontLatchSwitch : 8|1@1+ (1,0) [0|1] "" gtw + SG_ VCRIGHT_rearLatchSwitch : 9|1@1+ (1,0) [0|1] "" gtw + SG_ VCRIGHT_rearHandlePWM : 21|7@1+ (1,0) [0|100] "%" X + SG_ VCRIGHT_rearIntSwitchPressed : 32|1@1+ (1,0) [0|1] "" aps + +BO_ 585 SCCM_leftStalk: 3 VEH + SG_ SCCM_leftStalkCounter : 8|4@1+ (1,0) [0|15] "" X + SG_ SCCM_washWipeButtonStatus : 14|2@1+ (1,0) [0|3] "" das + SG_ SCCM_turnIndicatorStalkStatus : 16|3@1+ (1,0) [0|5] "" das + SG_ SCCM_leftStalkCrc : 0|8@1+ (1,0) [0|255] "" X + SG_ SCCM_leftStalkReserved1 : 19|5@1+ (1,0) [0|31] "" X + SG_ SCCM_highBeamStalkStatus : 12|2@1+ (1,0) [0|3] "" das + +BO_ 280 DI_systemStatus: 8 VEH + SG_ DI_epbRequest : 44|2@1+ (1,0) [0|2] "" epbl + SG_ DI_systemStatusCounter : 8|4@1+ (1,0) [0|15] "" X + SG_ DI_proximity : 46|1@1+ (1,0) [0|1] "" bms + SG_ DI_keepAliveRequest : 47|1@1+ (1,0) [0|1] "" bms + SG_ DI_accelPedalPos : 32|8@1+ (0.4,0) [0|100] "%" vcfront + SG_ DI_gear : 21|3@1+ (1,0) [0|7] "" gtw + SG_ DI_tractionControlMode : 40|3@1+ (1,0) [0|5] "" X + SG_ DI_trackModeState : 48|2@1+ (1,0) [0|2] "" gtw + SG_ DI_regenLight : 26|1@1+ (1,0) [0|1] "" vcleft + SG_ DI_systemState : 16|3@1+ (1,0) [0|5] "" epbl + SG_ DI_immobilizerState : 27|3@1+ (1,0) [0|6] "" X + SG_ DI_systemStatusChecksum : 0|8@1+ (1,0) [0|255] "" X + SG_ DI_brakePedalState : 19|2@1+ (1,0) [0|2] "" vcleft + +BO_ 835 VCRIGHT_status: 8 VEH + SG_ VCRIGHT_5AVoltage : 18|10@1+ (0.005443676098,0) [0|5.56888] "V" gtw + SG_ VCRIGHT_loadShedPriority : 0|8@1+ (1,0) [0|255] "" X + SG_ VCRIGHT_rearDefrostState : 11|3@1+ (1,0) [0|4] "" gtw + SG_ VCRIGHT_vbatProt : 28|12@1+ (0.005443676098,0) [0|22.29185] "V" gtw + SG_ VCRIGHT_vehiclePowerStateDBG : 8|2@1+ (1,0) [0|3] "" gtw + SG_ VCRIGHT_swEnStatus : 10|1@1+ (1,0) [0|1] "" gtw + SG_ VCRIGHT_mirrorHeatState : 14|3@1+ (1,0) [0|4] "" X + SG_ VCRIGHT_OTAState : 17|1@1+ (1,0) [0|1] "" gtw + SG_ VCRIGHT_footwellLightCurrent : 40|12@1- (0.1,0) [-204.8|204.7] "mA" X + SG_ VCRIGHT_pcbaTemperature : 52|11@1+ (0.125,-40) [-40|150] "degC" gtw + +BO_ 553 SCCM_rightStalk: 3 VEH + SG_ SCCM_rightStalkCounter : 8|4@1+ (1,0) [0|15] "" X + SG_ SCCM_rightStalkCrc : 0|8@1+ (1,0) [0|255] "" X + SG_ SCCM_rightStalkReserved1 : 15|1@1+ (1,0) [0|1] "" X + SG_ SCCM_parkButtonStatus : 16|2@1+ (1,0) [0|3] "" das + SG_ SCCM_rightStalkReserved2 : 18|6@1+ (1,0) [0|63] "" X + SG_ SCCM_rightStalkStatus : 12|3@1+ (1,0) [0|6] "" das + +BO_ 297 SCCM_steeringAngleSensor: 8 VEH + SG_ SCCM_steeringAngleValidity : 30|2@1+ (1,0) [0|3] "" gtw + SG_ SCCM_supplierID : 12|2@1+ (1,0) [0|3] "" gtw + SG_ SCCM_steeringAngleSensorReservd1 : 46|2@1+ (1,0) [0|3] "" X + SG_ SCCM_steeringAngleCrc : 0|8@1+ (1,0) [0|255] "" gtw + SG_ SCCM_steeringAngleSensorStatus : 14|2@1+ (1,0) [0|3] "" aps + SG_ SCCM_steeringAngleSpeed : 32|14@1+ (0.5,-4096) [-4096|4095.5] "deg/s" das + SG_ SCCM_steeringAngle : 16|14@1+ (0.1,-819.2) [-819.2|819] "deg" aps + SG_ SCCM_steeringAngleSensorReservd2 : 48|8@1+ (1,0) [0|255] "" X + SG_ SCCM_steeringAngleCounter : 8|4@1+ (1,0) [0|15] "" gtw + SG_ SCCM_steeringAngleSensorReservd3 : 56|8@1+ (1,0) [0|255] "" X + +BO_ 258 VCLEFT_doorStatus: 8 VEH + SG_ VCLEFT_mirrorDipped : 61|1@1+ (1,0) [0|1] "" X + SG_ VCLEFT_frontHandlePulledPersist : 62|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_mirrorRecallState : 55|3@1+ (1,0) [0|5] "" gtw + SG_ VCLEFT_rearIntSwitchPressed : 32|1@1+ (1,0) [0|1] "" aps + SG_ VCLEFT_rearLatchSwitch : 9|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_rearHandlePWM : 24|7@1+ (1,0) [0|100] "%" X + SG_ VCLEFT_frontLatchSwitch : 8|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_frontHandlePWM : 16|7@1+ (1,0) [0|100] "%" X + SG_ VCLEFT_rearHandlePulled : 11|1@1+ (1,0) [0|1] "" aps + SG_ VCLEFT_rearLatchStatus : 4|4@1+ (1,0) [0|8] "" aps + SG_ VCLEFT_frontHandlePulled : 10|1@1+ (1,0) [0|1] "" aps + SG_ VCLEFT_mirrorTiltXPosition : 33|8@1+ (0.02,0) [0|5] "V" gtw + SG_ VCLEFT_mirrorState : 49|3@1+ (1,0) [0|4] "" gtw + SG_ VCLEFT_frontIntSwitchPressed : 31|1@1+ (1,0) [0|1] "" aps + SG_ VCLEFT_rearRelActuatorSwitch : 13|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_mirrorHeatState : 58|3@1+ (1,0) [0|4] "" X + SG_ VCLEFT_frontRelActuatorSwitch : 12|1@1+ (1,0) [0|1] "" gtw + SG_ VCLEFT_mirrorTiltYPosition : 41|8@1+ (0.02,0) [0|5] "V" gtw + SG_ VCLEFT_frontLatchStatus : 0|4@1+ (1,0) [0|8] "" aps + SG_ VCLEFT_mirrorFoldState : 52|3@1+ (1,0) [0|4] "" gtw + + +BO_ 568 STW_ACTN_RQ: 8 STW + SG_ SpdCtrlLvr_Stat : 0|6@1+ (1,0) [0|0] "" NEO + SG_ VSL_Enbl_Rq : 6|1@1+ (1,0) [0|0] "" NEO + SG_ SpdCtrlLvrStat_Inv : 7|1@1+ (1,0) [0|0] "" NEO + SG_ DTR_Dist_Rq : 8|8@1+ (1,0) [0|200] "" NEO + SG_ TurnIndLvr_Stat : 16|2@1+ (1,0) [0|0] "" NEO + SG_ HiBmLvr_Stat : 18|2@1+ (1,0) [0|0] "" NEO + SG_ WprWashSw_Psd : 20|2@1+ (1,0) [0|0] "" NEO + SG_ WprWash_R_Sw_Posn_V2 : 22|2@1+ (1,0) [0|0] "" NEO + SG_ StW_Lvr_Stat : 24|3@1+ (1,0) [0|0] "" NEO + SG_ StW_Cond_Flt : 27|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Cond_Psd : 28|2@1+ (1,0) [0|0] "" NEO + SG_ HrnSw_Psd : 30|2@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw00_Psd : 32|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw01_Psd : 33|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw02_Psd : 34|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw03_Psd : 35|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw04_Psd : 36|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw05_Psd : 37|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw06_Psd : 38|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw07_Psd : 39|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw08_Psd : 40|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw09_Psd : 41|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw10_Psd : 42|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw11_Psd : 43|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw12_Psd : 44|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw13_Psd : 45|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw14_Psd : 46|1@1+ (1,0) [0|0] "" NEO + SG_ StW_Sw15_Psd : 47|1@1+ (1,0) [0|0] "" NEO + SG_ WprSw6Posn : 48|3@1+ (1,0) [0|0] "" NEO + SG_ MC_STW_ACTN_RQ : 52|4@1+ (1,0) [0|15] "" NEO + SG_ CRC_STW_ACTN_RQ : 56|8@1+ (1,0) [0|0] "" NEO + +BO_ 1001 DAS_bodyControls: 8 VEH + SG_ DAS_headlightRequest : 0|2@1+ (1,0) [0|3] "" aps + SG_ DAS_hazardLightRequest : 2|2@1+ (1,0) [0|3] "" aps + SG_ DAS_wiperSpeed : 4|4@1+ (1,0) [0|15] "" aps + SG_ DAS_turnIndicatorRequest : 8|2@1+ (1,0) [0|3] "" aps + SG_ DAS_highLowBeamDecision : 10|2@1+ (1,0) [0|3] "" aps + SG_ DAS_heaterRequest : 12|2@1+ (1,0) [0|2] "" aps + SG_ DAS_turnIndicatorRequestReason : 17|4@1+ (1,0) [0|8] "" aps + SG_ DAS_autopilotActive : 24|1@1+ (1,0) [0|1] "" XXX + SG_ DAS_accActive : 29|1@1+ (1,0) [0|1] "" XXX + SG_ DAS_bodyControlsCounter : 52|4@1+ (1,0) [0|15] "" aps + SG_ DAS_bodyControlsChecksum : 56|8@1+ (1,0) [0|255] "" aps + +BO_ 1013 ID3F5VCFRONT_lighting: 8 VEH + SG_ VCFRONT_lowBeamsCalibrated : 62|1@1+ (1,0) [0|1] "" Receiver + SG_ VCFRONT_lowBeamsOnForDRL : 61|1@1+ (1,0) [0|1] "" Receiver + SG_ VCFRONT_simLatchingStalk : 59|2@1+ (1,0) [0|3] "" Receiver + SG_ VCFRONT_highBeamSwitchActive : 58|1@1+ (1,0) [0|1] "" Receiver + SG_ VCFRONT_parkRightStatus : 56|2@1+ (1,0) [0|3] "" Receiver + SG_ VCFRONT_parkLeftStatus : 54|2@1+ (1,0) [0|3] "" Receiver + SG_ VCFRONT_turnSignalRightStatus : 52|2@1+ (1,0) [0|3] "" Receiver + SG_ VCFRONT_turnSignalLeftStatus : 50|2@1+ (1,0) [0|3] "" Receiver + SG_ VCFRONT_sideRepeaterRightStatus : 48|2@1+ (1,0) [0|3] "" Receiver + SG_ VCFRONT_sideRepeaterLeftStatus : 46|2@1+ (1,0) [0|3] "" Receiver + SG_ VCFRONT_sideMarkersStatus : 44|2@1+ (1,0) [0|3] "" Receiver + SG_ VCFRONT_fogRightStatus : 42|2@1+ (1,0) [0|3] "" Receiver + SG_ VCFRONT_fogLeftStatus : 40|2@1+ (1,0) [0|3] "" Receiver + SG_ VCFRONT_DRLRightStatus : 38|2@1+ (1,0) [0|3] "" Receiver + SG_ VCFRONT_DRLLeftStatus : 36|2@1+ (1,0) [0|3] "" Receiver + SG_ VCFRONT_highBeamRightStatus : 34|2@1+ (1,0) [0|3] "" Receiver + SG_ VCFRONT_highBeamLeftStatus : 32|2@1+ (1,0) [0|3] "" Receiver + SG_ VCFRONT_lowBeamRightStatus : 30|2@1+ (1,0) [0|3] "" Receiver + SG_ VCFRONT_lowBeamLeftStatus : 28|2@1+ (1,0) [0|3] "" Receiver + SG_ VCFRONT_hazardSwitchBacklight : 27|1@1+ (1,0) [0|1] "" Receiver + SG_ VCFRONT_seeYouHomeLightingReq : 26|1@1+ (1,0) [0|1] "" Receiver + SG_ VCFRONT_approachLightingRequest : 25|1@1+ (1,0) [0|1] "" Receiver + SG_ VCFRONT_courtesyLightingRequest : 24|1@1+ (1,0) [0|1] "" Receiver + SG_ VCFRONT_switchLightingBrightness : 16|8@1+ (0.5,0) [0|127] "%" Receiver + SG_ VCFRONT_ambientLightingBrightnes : 8|8@1+ (0.5,0) [0|127] "%" Receiver + SG_ VCFRONT_hazardLightRequest : 4|4@1+ (1,0) [0|8] "" Receiver + SG_ VCFRONT_indicatorRightRequest : 2|2@1+ (1,0) [0|2] "" Receiver + SG_ VCFRONT_indicatorLeftRequest : 0|2@1+ (1,0) [0|2] "" Receiver + +VAL_ 568 SpdCtrlLvr_Stat 32 "DN_1ST" 16 "UP_1ST" 8 "DN_2ND" 4 "UP_2ND" 2 "RWD" 1 "FWD" 0 "IDLE" ; +VAL_ 568 DTR_Dist_Rq 255 "SNA" 200 "ACC_DIST_7" 166 "ACC_DIST_6" 133 "ACC_DIST_5" 100 "ACC_DIST_4" 66 "ACC_DIST_3" 33 "ACC_DIST_2" 0 "ACC_DIST_1" ; +VAL_ 568 TurnIndLvr_Stat 3 "SNA" 2 "RIGHT" 1 "LEFT" 0 "IDLE" ; +VAL_ 568 HiBmLvr_Stat 3 "SNA" 2 "HIBM_FLSH_ON_PSD" 1 "HIBM_ON_PSD" 0 "IDLE" ; +VAL_ 568 WprWashSw_Psd 3 "SNA" 2 "WASH" 1 "TIPWIPE" 0 "NPSD" ; +VAL_ 568 WprWash_R_Sw_Posn_V2 3 "SNA" 2 "WASH" 1 "INTERVAL" 0 "OFF" ; +VAL_ 568 StW_Lvr_Stat 4 "STW_BACK" 3 "STW_FWD" 2 "STW_DOWN" 1 "STW_UP" 0 "NPSD" ; +VAL_ 568 StW_Cond_Psd 3 "SNA" 2 "DOWN" 1 "UP" 0 "NPSD" ; +VAL_ 568 HrnSw_Psd 3 "SNA" 2 "NDEF2" 1 "PSD" 0 "NPSD" ; +VAL_ 568 StW_Sw00_Psd 1 "PRESSED" 0 "NOT_PRESSED_SNA" ; +VAL_ 568 StW_Sw01_Psd 1 "PRESSED" 0 "NOT_PRESSED_SNA" ; +VAL_ 568 StW_Sw03_Psd 1 "PRESSED" 0 "NOT_PRESSED_SNA" ; +VAL_ 568 StW_Sw04_Psd 1 "PRESSED" 0 "NOT_PRESSED_SNA" ; +VAL_ 568 WprSw6Posn 7 "SNA" 6 "STAGE2" 5 "STAGE1" 4 "INTERVAL4" 3 "INTERVAL3" 2 "INTERVAL2" 1 "INTERVAL1" 0 "OFF" ; + +VAL_ 1001 DAS_headlightRequest 3 "DAS_HEADLIGHT_REQUEST_INVALID" 1 "DAS_HEADLIGHT_REQUEST_ON" 0 "DAS_HEADLIGHT_REQUEST_OFF"; +VAL_ 1001 DAS_hazardLightRequest 3 "DAS_REQUEST_HAZARDS_SNA" 2 "DAS_REQUEST_HAZARDS_UNUSED" 0 "DAS_REQUEST_HAZARDS_OFF" 1 "DAS_REQUEST_HAZARDS_ON"; +VAL_ 1001 DAS_wiperSpeed 3 "DAS_WIPER_SPEED_3" 12 "DAS_WIPER_SPEED_12" 8 "DAS_WIPER_SPEED_8" 14 "DAS_WIPER_SPEED_14" 5 "DAS_WIPER_SPEED_5" 13 "DAS_WIPER_SPEED_13" 2 "DAS_WIPER_SPEED_2" 0 "DAS_WIPER_SPEED_OFF" 4 "DAS_WIPER_SPEED_4" 1 "DAS_WIPER_SPEED_1" 15 "DAS_WIPER_SPEED_INVALID" 10 "DAS_WIPER_SPEED_10" 11 "DAS_WIPER_SPEED_11" 7 "DAS_WIPER_SPEED_7" 9 "DAS_WIPER_SPEED_9" 6 "DAS_WIPER_SPEED_6"; +VAL_ 1001 DAS_turnIndicatorRequest 0 "DAS_TURN_INDICATOR_NONE" 2 "DAS_TURN_INDICATOR_RIGHT" 3 "DAS_TURN_INDICATOR_CANCEL" 1 "DAS_TURN_INDICATOR_LEFT"; +VAL_ 1001 DAS_highLowBeamDecision 2 "DAS_HIGH_BEAM_ON" 1 "DAS_HIGH_BEAM_OFF" 3 "DAS_HIGH_BEAM_SNA" 0 "DAS_HIGH_BEAM_UNDECIDED"; +VAL_ 1001 DAS_heaterRequest 0 "DAS_HEATER_SNA" 2 "DAS_HEATER_ON" 1 "DAS_HEATER_OFF"; +VAL_ 1001 DAS_turnIndicatorRequestReason 8 "DAS_ACTIVE_COMMANDED_LANE_CHANGE" 4 "DAS_CANCEL_LANE_CHANGE" 6 "DAS_ACTIVE_MERGE" 2 "DAS_ACTIVE_SPEED_LANE_CHANGE" 5 "DAS_CANCEL_FORK" 0 "DAS_NONE" 3 "DAS_ACTIVE_FORK" 7 "DAS_CANCEL_MERGE" 1 "DAS_ACTIVE_NAV_LANE_CHANGE"; + +VAL_ 1013 VCFRONT_DRLLeftStatus 2 "LIGHT_FAULT" 0 "LIGHT_OFF" 1 "LIGHT_ON" 3 "LIGHT_SNA" ; +VAL_ 1013 VCFRONT_DRLRightStatus 2 "LIGHT_FAULT" 0 "LIGHT_OFF" 1 "LIGHT_ON" 3 "LIGHT_SNA" ; +VAL_ 1013 VCFRONT_ambientLightingBrightnes 255 "SNA" ; +VAL_ 1013 VCFRONT_fogLeftStatus 2 "LIGHT_FAULT" 0 "LIGHT_OFF" 1 "LIGHT_ON" 3 "LIGHT_SNA" ; +VAL_ 1013 VCFRONT_fogRightStatus 2 "LIGHT_FAULT" 0 "LIGHT_OFF" 1 "LIGHT_ON" 3 "LIGHT_SNA" ; +VAL_ 1013 VCFRONT_hazardLightRequest 1 "HAZARD_REQUEST_BUTTON" 6 "HAZARD_REQUEST_CAR_ALARM" 5 "HAZARD_REQUEST_CRASH" 7 "HAZARD_REQUEST_DAS" 2 "HAZARD_REQUEST_LOCK" 4 "HAZARD_REQUEST_MISLOCK" 0 "HAZARD_REQUEST_NONE" 8 "HAZARD_REQUEST_UDS" 3 "HAZARD_REQUEST_UNLOCK" ; +VAL_ 1013 VCFRONT_highBeamLeftStatus 2 "LIGHT_FAULT" 0 "LIGHT_OFF" 1 "LIGHT_ON" 3 "LIGHT_SNA" ; +VAL_ 1013 VCFRONT_highBeamRightStatus 2 "LIGHT_FAULT" 0 "LIGHT_OFF" 1 "LIGHT_ON" 3 "LIGHT_SNA" ; +VAL_ 1013 VCFRONT_indicatorLeftRequest 2 "TURN_SIGNAL_ACTIVE_HIGH" 1 "TURN_SIGNAL_ACTIVE_LOW" 0 "TURN_SIGNAL_OFF" ; +VAL_ 1013 VCFRONT_indicatorRightRequest 2 "TURN_SIGNAL_ACTIVE_HIGH" 1 "TURN_SIGNAL_ACTIVE_LOW" 0 "TURN_SIGNAL_OFF" ; +VAL_ 1013 VCFRONT_lowBeamLeftStatus 2 "LIGHT_FAULT" 0 "LIGHT_OFF" 1 "LIGHT_ON" 3 "LIGHT_SNA" ; +VAL_ 1013 VCFRONT_lowBeamRightStatus 2 "LIGHT_FAULT" 0 "LIGHT_OFF" 1 "LIGHT_ON" 3 "LIGHT_SNA" ; +VAL_ 1013 VCFRONT_parkLeftStatus 2 "LIGHT_FAULT" 0 "LIGHT_OFF" 1 "LIGHT_ON" 3 "LIGHT_SNA" ; +VAL_ 1013 VCFRONT_parkRightStatus 2 "LIGHT_FAULT" 0 "LIGHT_OFF" 1 "LIGHT_ON" 3 "LIGHT_SNA" ; +VAL_ 1013 VCFRONT_sideMarkersStatus 2 "LIGHT_FAULT" 0 "LIGHT_OFF" 1 "LIGHT_ON" 3 "LIGHT_SNA" ; +VAL_ 1013 VCFRONT_sideRepeaterLeftStatus 2 "LIGHT_FAULT" 0 "LIGHT_OFF" 1 "LIGHT_ON" 3 "LIGHT_SNA" ; +VAL_ 1013 VCFRONT_sideRepeaterRightStatus 2 "LIGHT_FAULT" 0 "LIGHT_OFF" 1 "LIGHT_ON" 3 "LIGHT_SNA" ; +VAL_ 1013 VCFRONT_simLatchingStalk 0 "SIMULATED_LATCHING_STALK_IDLE" 1 "SIMULATED_LATCHING_STALK_LEFT" 2 "SIMULATED_LATCHING_STALK_RIGHT" 3 "SIMULATED_LATCHING_STALK_SNA" ; +VAL_ 1013 VCFRONT_switchLightingBrightness 255 "SNA" ; +VAL_ 1013 VCFRONT_turnSignalLeftStatus 2 "LIGHT_FAULT" 0 "LIGHT_OFF" 1 "LIGHT_ON" 3 "LIGHT_SNA" ; +VAL_ 1013 VCFRONT_turnSignalRightStatus 2 "LIGHT_FAULT" 0 "LIGHT_OFF" 1 "LIGHT_ON" 3 "LIGHT_SNA" ; +VAL_ 962 VCLEFT_frontBuckleSwitch 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF"; +VAL_ 962 VCLEFT_frontSeatTrackBack 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF"; +VAL_ 962 VCLEFT_rightMirrorTilt 4 "MIRROR_TILT_LEFT" 2 "MIRROR_TILT_UP" 3 "MIRROR_TILT_RIGHT" 0 "MIRROR_TILT_STOP" 1 "MIRROR_TILT_DOWN"; +VAL_ 962 VCLEFT_frontOccupancySwitch 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF"; +VAL_ 962 VCLEFT_swcRightTiltLeft 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF"; +VAL_ 962 VCLEFT_rearRightOccupancySwitch 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF"; +VAL_ 962 VCLEFT_swcLeftTiltRight 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF"; +VAL_ 962 VCLEFT_frontSeatBackrestForward 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF"; +VAL_ 962 VCLEFT_swcRightTiltRight 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF"; +VAL_ 962 VCLEFT_frontSeatLumbarIn 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF"; +VAL_ 962 VCLEFT_frontSeatLiftUp 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF"; +VAL_ 962 VCLEFT_frontSeatLumbarDown 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF"; +VAL_ 962 VCLEFT_frontSeatTiltDown 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF"; +VAL_ 962 VCLEFT_frontSeatTrackForward 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF"; +VAL_ 962 VCLEFT_rearLeftBuckleSwitch 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF"; +VAL_ 962 VCLEFT_swcRightPressed 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF"; +VAL_ 962 VCLEFT_frontSeatLumbarOut 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF"; +VAL_ 962 VCLEFT_swcLeftTiltLeft 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF"; +VAL_ 962 VCLEFT_swcLeftPressed 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF"; +VAL_ 962 VCLEFT_frontSeatTiltUp 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF"; +VAL_ 962 VCLEFT_rearLeftOccupancySwitch 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF"; +VAL_ 962 VCLEFT_frontSeatBackrestBack 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF"; +VAL_ 962 VCLEFT_rearCenterOccupancySwitch 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF"; +VAL_ 962 VCLEFT_frontSeatLumbarUp 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF"; +VAL_ 962 VCLEFT_frontSeatLiftDown 2 "SWITCH_ON" 0 "SWITCH_SNA" 3 "SWITCH_FAULT" 1 "SWITCH_OFF"; +VAL_ 962 VCLEFT_switchStatusIndex 1 "VCLEFT_SWITCH_STATUS_INDEX_1" 2 "VCLEFT_SWITCH_STATUS_INDEX_INVALID" 0 "VCLEFT_SWITCH_STATUS_INDEX_0"; +VAL_ 259 VCRIGHT_trunkLatchStatus 8 "LATCH_FAULT" 2 "LATCH_CLOSED" 1 "LATCH_OPENED" 3 "LATCH_CLOSING" 7 "LATCH_DEFAULT" 4 "LATCH_OPENING" 5 "LATCH_AJAR" 6 "LATCH_TIMEOUT" 0 "LATCH_SNA"; +VAL_ 259 VCRIGHT_mirrorFoldState 4 "MIRROR_FOLD_STATE_UNFOLDING" 1 "MIRROR_FOLD_STATE_FOLDED" 3 "MIRROR_FOLD_STATE_FOLDING" 0 "MIRROR_FOLD_STATE_UNKNOWN" 2 "MIRROR_FOLD_STATE_UNFOLDED"; +VAL_ 259 VCRIGHT_rearLatchStatus 8 "LATCH_FAULT" 2 "LATCH_CLOSED" 1 "LATCH_OPENED" 3 "LATCH_CLOSING" 7 "LATCH_DEFAULT" 4 "LATCH_OPENING" 5 "LATCH_AJAR" 6 "LATCH_TIMEOUT" 0 "LATCH_SNA"; +VAL_ 259 VCRIGHT_mirrorRecallState 5 "MIRROR_RECALL_STATE_RECALLING_STOPPED" 2 "MIRROR_RECALL_STATE_RECALLING_AXIS_2" 0 "MIRROR_RECALL_STATE_INIT" 3 "MIRROR_RECALL_STATE_RECALLING_COMPLETE" 4 "MIRROR_RECALL_STATE_RECALLING_FAILED" 1 "MIRROR_RECALL_STATE_RECALLING_AXIS_1"; +VAL_ 259 VCRIGHT_mirrorState 3 "MIRROR_STATE_FOLD_UNFOLD" 1 "MIRROR_STATE_TILT_X" 0 "MIRROR_STATE_IDLE" 2 "MIRROR_STATE_TILT_Y" 4 "MIRROR_STATE_RECALL"; +VAL_ 259 VCRIGHT_frontLatchStatus 8 "LATCH_FAULT" 2 "LATCH_CLOSED" 1 "LATCH_OPENED" 3 "LATCH_CLOSING" 7 "LATCH_DEFAULT" 4 "LATCH_OPENING" 5 "LATCH_AJAR" 6 "LATCH_TIMEOUT" 0 "LATCH_SNA"; +VAL_ 585 SCCM_washWipeButtonStatus 3 "SNA" 0 "NOT_PRESSED" 2 "2ND_DETENT" 1 "1ST_DETENT"; +VAL_ 585 SCCM_turnIndicatorStalkStatus 3 "DOWN_1" 5 "SNA" 0 "IDLE" 1 "UP_1" 4 "DOWN_2" 2 "UP_2"; +VAL_ 585 SCCM_highBeamStalkStatus 3 "SNA" 0 "IDLE" 1 "PULL" 2 "PUSH"; +VAL_ 280 DI_epbRequest 0 "DI_EPBREQUEST_NO_REQUEST" 1 "DI_EPBREQUEST_PARK" 2 "DI_EPBREQUEST_UNPARK"; +VAL_ 280 DI_keepAliveRequest 1 "KEEP_ALIVE" 0 "NO_REQUEST"; +VAL_ 280 DI_accelPedalPos 255 "SNA"; +VAL_ 280 DI_gear 1 "DI_GEAR_P" 0 "DI_GEAR_INVALID" 7 "DI_GEAR_SNA" 2 "DI_GEAR_R" 3 "DI_GEAR_N" 4 "DI_GEAR_D"; +VAL_ 280 DI_tractionControlMode 0 "TC_NORMAL" 1 "TC_SLIP_START" 4 "TC_ROLLS_MODE" 2 "TC_DEV_MODE_1" 5 "TC_DYNO_MODE" 3 "TC_DEV_MODE_2"; +VAL_ 280 DI_trackModeState 0 "TRACK_MODE_UNAVAILABLE" 1 "TRACK_MODE_AVAILABLE" 2 "TRACK_MODE_ON"; +VAL_ 280 DI_systemState 5 "DI_SYS_ENABLE" 1 "DI_SYS_IDLE" 2 "DI_SYS_STANDBY" 0 "DI_SYS_UNAVAILABLE" 3 "DI_SYS_FAULT" 4 "DI_SYS_ABORT"; +VAL_ 280 DI_immobilizerState 2 "DI_IMM_STATE_AUTHENTICATING" 0 "DI_IMM_STATE_INIT_SNA" 3 "DI_IMM_STATE_DISARMED" 4 "DI_IMM_STATE_IDLE" 6 "DI_IMM_STATE_FAULT" 1 "DI_IMM_STATE_REQUEST" 5 "DI_IMM_STATE_RESET"; +VAL_ 280 DI_brakePedalState 2 "INVALID" 0 "OFF" 1 "ON"; +VAL_ 835 VCRIGHT_rearDefrostState 2 "HEATER_STATE_OFF" 4 "HEATER_STATE_FAULT" 1 "HEATER_STATE_ON" 0 "HEATER_STATE_SNA" 3 "HEATER_STATE_OFF_UNAVAILABLE"; +VAL_ 835 VCRIGHT_vehiclePowerStateDBG 3 "VEHICLE_POWER_STATE_DRIVE" 1 "VEHICLE_POWER_STATE_CONDITIONING" 2 "VEHICLE_POWER_STATE_ACCESSORY" 0 "VEHICLE_POWER_STATE_OFF"; +VAL_ 835 VCRIGHT_mirrorHeatState 2 "HEATER_STATE_OFF" 4 "HEATER_STATE_FAULT" 1 "HEATER_STATE_ON" 0 "HEATER_STATE_SNA" 3 "HEATER_STATE_OFF_UNAVAILABLE"; +VAL_ 553 SCCM_parkButtonStatus 3 "SNA" 0 "NOT_PRESSED" 2 "INIT" 1 "PRESSED"; +VAL_ 553 SCCM_rightStalkStatus 3 "DOWN_1" 6 "SNA" 0 "IDLE" 5 "INIT" 1 "UP_1" 4 "DOWN_2" 2 "UP_2"; +VAL_ 297 SCCM_steeringAngleValidity 3 "SNA" 2 "INIT" 0 "INVALID" 1 "VALID"; +VAL_ 297 SCCM_steeringAngleSensorStatus 0 "OK" 1 "INIT" 2 "ERROR" 3 "ERROR_INIT"; +VAL_ 258 VCLEFT_mirrorRecallState 5 "MIRROR_RECALL_STATE_RECALLING_STOPPED" 2 "MIRROR_RECALL_STATE_RECALLING_AXIS_2" 0 "MIRROR_RECALL_STATE_INIT" 3 "MIRROR_RECALL_STATE_RECALLING_COMPLETE" 4 "MIRROR_RECALL_STATE_RECALLING_FAILED" 1 "MIRROR_RECALL_STATE_RECALLING_AXIS_1"; +VAL_ 258 VCLEFT_rearLatchStatus 8 "LATCH_FAULT" 2 "LATCH_CLOSED" 1 "LATCH_OPENED" 3 "LATCH_CLOSING" 7 "LATCH_DEFAULT" 4 "LATCH_OPENING" 5 "LATCH_AJAR" 6 "LATCH_TIMEOUT" 0 "LATCH_SNA"; +VAL_ 258 VCLEFT_mirrorState 3 "MIRROR_STATE_FOLD_UNFOLD" 1 "MIRROR_STATE_TILT_X" 0 "MIRROR_STATE_IDLE" 2 "MIRROR_STATE_TILT_Y" 4 "MIRROR_STATE_RECALL"; +VAL_ 258 VCLEFT_mirrorHeatState 2 "HEATER_STATE_OFF" 4 "HEATER_STATE_FAULT" 1 "HEATER_STATE_ON" 0 "HEATER_STATE_SNA" 3 "HEATER_STATE_OFF_UNAVAILABLE"; +VAL_ 258 VCLEFT_frontLatchStatus 8 "LATCH_FAULT" 2 "LATCH_CLOSED" 1 "LATCH_OPENED" 3 "LATCH_CLOSING" 7 "LATCH_DEFAULT" 4 "LATCH_OPENING" 5 "LATCH_AJAR" 6 "LATCH_TIMEOUT" 0 "LATCH_SNA"; +VAL_ 258 VCLEFT_mirrorFoldState 4 "MIRROR_FOLD_STATE_UNFOLDING" 1 "MIRROR_FOLD_STATE_FOLDED" 3 "MIRROR_FOLD_STATE_FOLDING" 0 "MIRROR_FOLD_STATE_UNKNOWN" 2 "MIRROR_FOLD_STATE_UNFOLDED"; diff --git a/tesla_radar.dbc b/tesla_radar.dbc deleted file mode 100644 index e7b9cbc055..0000000000 --- a/tesla_radar.dbc +++ /dev/null @@ -1,1371 +0,0 @@ -VERSION "" - - -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_ - SG_MUL_VAL_ - -BS_: - -BU_: FrontCamera Radar - - -BO_ 769 TeslaRadarSguInfo: 8 Radar - SG_ RADC_VerticalMisalignment : 0|8@1+ (1,0) [0|255] "" FrontCamera - SG_ RADC_SCUTemperature : 8|8@1+ (1,-128) [-128|127] "" FrontCamera - SG_ RADC_VMA_Plaus : 16|8@1+ (1,0) [0|255] "" FrontCamera - SG_ RADC_SGU_ITC : 24|8@1+ (1,0) [0|255] "" FrontCamera - SG_ RADC_HorizontMisalignment : 32|12@1+ (1,0) [0|4096] "" FrontCamera - SG_ RADC_SensorDirty : 44|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_HWFail : 45|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_SGUFail : 46|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_SGUInfoConsistBit : 47|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 770 TeslaRadarTguInfo: 8 Radar - SG_ RADC_ACCTargObj1_sguIndex : 0|6@1+ (1,0) [0|63] "" FrontCamera - SG_ RADC_ACCTargObj2_sguIndex : 6|6@1+ (1,0) [0|63] "" FrontCamera - SG_ RADC_ACCTargObj3_sguIndex : 12|6@1+ (1,0) [0|63] "" FrontCamera - SG_ RADC_ACCTargObj4_sguIndex : 18|6@1+ (1,0) [0|63] "" FrontCamera - SG_ RADC_ACCTargObj5_sguIndex : 24|6@1+ (1,0) [0|63] "" FrontCamera - SG_ unused30 : 30|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_TGUInfoConsistBit : 31|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_ACCTargObj1_dBPower : 32|16@1+ (1,0) [0|65535] "" FrontCamera - SG_ RADC_ACCTargObj5_dBPower : 48|16@1+ (1,0) [0|65535] "" FrontCamera - -BO_ 1281 TeslaRadarAlertMatrix: 8 Radar - SG_ RADC_a001_ecuInternalPerf : 0|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a002_flashPerformance : 1|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a003_vBatHigh : 2|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a004_adjustmentNotDone : 3|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a005_adjustmentReq : 4|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a006_adjustmentNotOk : 5|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a007_sensorBlinded : 6|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a008_plantModeActive : 7|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a009_configMismatch : 8|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a010_canBusOff : 9|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a011_bdyMIA : 10|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a012_espMIA : 11|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a013_gtwMIA : 12|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a014_sccmMIA : 13|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a015_adasMIA : 14|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a016_bdyInvalidCount : 15|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a017_adasInvalidCount : 16|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a018_espInvalidCount : 17|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a019_sccmInvalidCount : 18|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a020_bdyInvalidChkSm : 19|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a021_espInvalidChkSm : 20|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a022_sccmInvalidChkSm : 21|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a023_sccmInvalidChkSm : 22|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a024_absValidity : 23|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a025_ambTValidity : 24|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a026_brakeValidity : 25|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a027_CntryCdValidity : 26|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a028_espValidity : 27|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a029_longAccOffValidity : 28|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a030_longAccValidity : 29|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a031_odoValidity : 30|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a032_gearValidity : 31|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a033_steerAngValidity : 32|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a034_steerAngSpdValidity : 33|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a035_indctrValidity : 34|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a036_vehStandStillValidity : 35|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a037_vinValidity : 36|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a038_whlRotValidity : 37|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a039_whlSpdValidity : 38|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a040_whlStandStillValidity : 39|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a041_wiperValidity : 40|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a042_xwdValidity : 41|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a043_yawOffValidity : 42|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a044_yawValidity : 43|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a045_bsdSanity : 44|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a046_rctaSanity : 45|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a047_lcwSanity : 46|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a048_steerAngOffSanity : 47|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a049_tireSizeSanity : 48|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a050_velocitySanity : 49|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a051_yawSanity : 50|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a052_radomeHtrInop : 51|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a053_espmodValidity : 52|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a054_gtwmodValidity : 53|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a055_stwmodValidity : 54|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a056_bcmodValidity : 55|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a057_dimodValidity : 56|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a058_opmodValidity : 57|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a059_drmiInvalidChkSm : 58|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a060_drmiInvalidCount : 59|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a061_radPositionMismatch : 60|1@1+ (1,0) [0|1] "" FrontCamera - SG_ RADC_a062_strRackMismatch : 61|1@1+ (1,0) [0|1] "" FrontCamera - SG_ unused62 : 62|2@1+ (1,0) [0|3] "" FrontCamera - -BO_ 784 M_310hex: 8 Radar - SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" FrontCamera - SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" FrontCamera - SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" FrontCamera - SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" FrontCamera - SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Valid : 55|1@1+ (1,0) [0|1] "" FrontCamera - SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Meas : 61|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Tracked : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 785 M_310hex2: 8 Radar - SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" FrontCamera - SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" FrontCamera - SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" FrontCamera - SG_ MovingState : 22|2@1+ (1,0) [0|3] "" FrontCamera - SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" FrontCamera - SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" FrontCamera - SG_ axSigma : 36|6@1+ (1,0) [0|63] "" FrontCamera - SG_ dySigma : 42|6@1+ (1,0) [0|63] "" FrontCamera - SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Class : 53|3@1+ (1,0) [0|7] "" FrontCamera - SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" FrontCamera - SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index2 : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 787 M_313hex: 8 Radar - SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" FrontCamera - SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" FrontCamera - SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" FrontCamera - SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" FrontCamera - SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Valid : 55|1@1+ (1,0) [0|1] "" FrontCamera - SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Meas : 61|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Tracked : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 788 M_313hex2: 8 Radar - SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" FrontCamera - SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" FrontCamera - SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" FrontCamera - SG_ MovingState : 22|2@1+ (1,0) [0|3] "" FrontCamera - SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" FrontCamera - SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" FrontCamera - SG_ axSigma : 36|6@1+ (1,0) [0|63] "" FrontCamera - SG_ dySigma : 42|6@1+ (1,0) [0|63] "" FrontCamera - SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Class : 53|3@1+ (1,0) [0|7] "" FrontCamera - SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" FrontCamera - SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index2 : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 790 M_316hex: 8 Radar - SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" FrontCamera - SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" FrontCamera - SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" FrontCamera - SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" FrontCamera - SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Valid : 55|1@1+ (1,0) [0|1] "" FrontCamera - SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Meas : 61|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Tracked : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 791 M_316hex2: 8 Radar - SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" FrontCamera - SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" FrontCamera - SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" FrontCamera - SG_ MovingState : 22|2@1+ (1,0) [0|3] "" FrontCamera - SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" FrontCamera - SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" FrontCamera - SG_ axSigma : 36|6@1+ (1,0) [0|63] "" FrontCamera - SG_ dySigma : 42|6@1+ (1,0) [0|63] "" FrontCamera - SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Class : 53|3@1+ (1,0) [0|7] "" FrontCamera - SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" FrontCamera - SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index2 : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 793 M_319hex: 8 Radar - SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" FrontCamera - SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" FrontCamera - SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" FrontCamera - SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" FrontCamera - SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Valid : 55|1@1+ (1,0) [0|1] "" FrontCamera - SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Meas : 61|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Tracked : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 794 M_319hex2: 8 Radar - SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" FrontCamera - SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" FrontCamera - SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" FrontCamera - SG_ MovingState : 22|2@1+ (1,0) [0|3] "" FrontCamera - SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" FrontCamera - SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" FrontCamera - SG_ axSigma : 36|6@1+ (1,0) [0|63] "" FrontCamera - SG_ dySigma : 42|6@1+ (1,0) [0|63] "" FrontCamera - SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Class : 53|3@1+ (1,0) [0|7] "" FrontCamera - SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" FrontCamera - SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index2 : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 796 M_31Chex: 8 Radar - SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" FrontCamera - SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" FrontCamera - SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" FrontCamera - SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" FrontCamera - SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Valid : 55|1@1+ (1,0) [0|1] "" FrontCamera - SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Meas : 61|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Tracked : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 797 M_31Chex2: 8 Radar - SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" FrontCamera - SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" FrontCamera - SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" FrontCamera - SG_ MovingState : 22|2@1+ (1,0) [0|3] "" FrontCamera - SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" FrontCamera - SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" FrontCamera - SG_ axSigma : 36|6@1+ (1,0) [0|63] "" FrontCamera - SG_ dySigma : 42|6@1+ (1,0) [0|63] "" FrontCamera - SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Class : 53|3@1+ (1,0) [0|7] "" FrontCamera - SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" FrontCamera - SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index2 : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 799 M_31Fhex: 8 Radar - SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" FrontCamera - SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" FrontCamera - SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" FrontCamera - SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" FrontCamera - SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Valid : 55|1@1+ (1,0) [0|1] "" FrontCamera - SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Meas : 61|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Tracked : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 800 M_31Fhex2: 8 Radar - SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" FrontCamera - SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" FrontCamera - SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" FrontCamera - SG_ MovingState : 22|2@1+ (1,0) [0|3] "" FrontCamera - SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" FrontCamera - SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" FrontCamera - SG_ axSigma : 36|6@1+ (1,0) [0|63] "" FrontCamera - SG_ dySigma : 42|6@1+ (1,0) [0|63] "" FrontCamera - SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Class : 53|3@1+ (1,0) [0|7] "" FrontCamera - SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" FrontCamera - SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index2 : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 802 M_322hex: 8 Radar - SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" FrontCamera - SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" FrontCamera - SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" FrontCamera - SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" FrontCamera - SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Valid : 55|1@1+ (1,0) [0|1] "" FrontCamera - SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Meas : 61|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Tracked : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 803 M_322hex2: 8 Radar - SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" FrontCamera - SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" FrontCamera - SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" FrontCamera - SG_ MovingState : 22|2@1+ (1,0) [0|3] "" FrontCamera - SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" FrontCamera - SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" FrontCamera - SG_ axSigma : 36|6@1+ (1,0) [0|63] "" FrontCamera - SG_ dySigma : 42|6@1+ (1,0) [0|63] "" FrontCamera - SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Class : 53|3@1+ (1,0) [0|7] "" FrontCamera - SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" FrontCamera - SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index2 : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 805 M_325hex: 8 Radar - SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" FrontCamera - SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" FrontCamera - SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" FrontCamera - SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" FrontCamera - SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Valid : 55|1@1+ (1,0) [0|1] "" FrontCamera - SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Meas : 61|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Tracked : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 806 M_325hex2: 8 Radar - SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" FrontCamera - SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" FrontCamera - SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" FrontCamera - SG_ MovingState : 22|2@1+ (1,0) [0|3] "" FrontCamera - SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" FrontCamera - SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" FrontCamera - SG_ axSigma : 36|6@1+ (1,0) [0|63] "" FrontCamera - SG_ dySigma : 42|6@1+ (1,0) [0|63] "" FrontCamera - SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Class : 53|3@1+ (1,0) [0|7] "" FrontCamera - SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" FrontCamera - SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index2 : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 808 M_328hex: 8 Radar - SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" FrontCamera - SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" FrontCamera - SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" FrontCamera - SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" FrontCamera - SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Valid : 55|1@1+ (1,0) [0|1] "" FrontCamera - SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Meas : 61|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Tracked : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 809 M_328hex2: 8 Radar - SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" FrontCamera - SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" FrontCamera - SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" FrontCamera - SG_ MovingState : 22|2@1+ (1,0) [0|3] "" FrontCamera - SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" FrontCamera - SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" FrontCamera - SG_ axSigma : 36|6@1+ (1,0) [0|63] "" FrontCamera - SG_ dySigma : 42|6@1+ (1,0) [0|63] "" FrontCamera - SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Class : 53|3@1+ (1,0) [0|7] "" FrontCamera - SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" FrontCamera - SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index2 : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 811 M_32Bhex: 8 Radar - SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" FrontCamera - SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" FrontCamera - SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" FrontCamera - SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" FrontCamera - SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Valid : 55|1@1+ (1,0) [0|1] "" FrontCamera - SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Meas : 61|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Tracked : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 812 M_32Bhex2: 8 Radar - SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" FrontCamera - SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" FrontCamera - SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" FrontCamera - SG_ MovingState : 22|2@1+ (1,0) [0|3] "" FrontCamera - SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" FrontCamera - SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" FrontCamera - SG_ axSigma : 36|6@1+ (1,0) [0|63] "" FrontCamera - SG_ dySigma : 42|6@1+ (1,0) [0|63] "" FrontCamera - SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Class : 53|3@1+ (1,0) [0|7] "" FrontCamera - SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" FrontCamera - SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index2 : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 814 M_32Ehex: 8 Radar - SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" FrontCamera - SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" FrontCamera - SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" FrontCamera - SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" FrontCamera - SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Valid : 55|1@1+ (1,0) [0|1] "" FrontCamera - SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Meas : 61|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Tracked : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 815 M_32Ehex2: 8 Radar - SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" FrontCamera - SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" FrontCamera - SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" FrontCamera - SG_ MovingState : 22|2@1+ (1,0) [0|3] "" FrontCamera - SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" FrontCamera - SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" FrontCamera - SG_ axSigma : 36|6@1+ (1,0) [0|63] "" FrontCamera - SG_ dySigma : 42|6@1+ (1,0) [0|63] "" FrontCamera - SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Class : 53|3@1+ (1,0) [0|7] "" FrontCamera - SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" FrontCamera - SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index2 : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 817 M_331hex: 8 Radar - SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" FrontCamera - SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" FrontCamera - SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" FrontCamera - SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" FrontCamera - SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Valid : 55|1@1+ (1,0) [0|1] "" FrontCamera - SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Meas : 61|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Tracked : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 818 M_331hex2: 8 Radar - SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" FrontCamera - SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" FrontCamera - SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" FrontCamera - SG_ MovingState : 22|2@1+ (1,0) [0|3] "" FrontCamera - SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" FrontCamera - SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" FrontCamera - SG_ axSigma : 36|6@1+ (1,0) [0|63] "" FrontCamera - SG_ dySigma : 42|6@1+ (1,0) [0|63] "" FrontCamera - SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Class : 53|3@1+ (1,0) [0|7] "" FrontCamera - SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" FrontCamera - SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index2 : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 820 M_334hex: 8 Radar - SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" FrontCamera - SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" FrontCamera - SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" FrontCamera - SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" FrontCamera - SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Valid : 55|1@1+ (1,0) [0|1] "" FrontCamera - SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Meas : 61|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Tracked : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 821 M_334hex2: 8 Radar - SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" FrontCamera - SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" FrontCamera - SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" FrontCamera - SG_ MovingState : 22|2@1+ (1,0) [0|3] "" FrontCamera - SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" FrontCamera - SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" FrontCamera - SG_ axSigma : 36|6@1+ (1,0) [0|63] "" FrontCamera - SG_ dySigma : 42|6@1+ (1,0) [0|63] "" FrontCamera - SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Class : 53|3@1+ (1,0) [0|7] "" FrontCamera - SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" FrontCamera - SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index2 : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 823 M_337hex: 8 Radar - SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" FrontCamera - SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" FrontCamera - SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" FrontCamera - SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" FrontCamera - SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Valid : 55|1@1+ (1,0) [0|1] "" FrontCamera - SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Meas : 61|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Tracked : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 824 M_337hex2: 8 Radar - SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" FrontCamera - SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" FrontCamera - SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" FrontCamera - SG_ MovingState : 22|2@1+ (1,0) [0|3] "" FrontCamera - SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" FrontCamera - SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" FrontCamera - SG_ axSigma : 36|6@1+ (1,0) [0|63] "" FrontCamera - SG_ dySigma : 42|6@1+ (1,0) [0|63] "" FrontCamera - SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Class : 53|3@1+ (1,0) [0|7] "" FrontCamera - SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" FrontCamera - SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index2 : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 826 M_33Ahex: 8 Radar - SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" FrontCamera - SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" FrontCamera - SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" FrontCamera - SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" FrontCamera - SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Valid : 55|1@1+ (1,0) [0|1] "" FrontCamera - SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Meas : 61|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Tracked : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 827 M_33Ahex2: 8 Radar - SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" FrontCamera - SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" FrontCamera - SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" FrontCamera - SG_ MovingState : 22|2@1+ (1,0) [0|3] "" FrontCamera - SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" FrontCamera - SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" FrontCamera - SG_ axSigma : 36|6@1+ (1,0) [0|63] "" FrontCamera - SG_ dySigma : 42|6@1+ (1,0) [0|63] "" FrontCamera - SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Class : 53|3@1+ (1,0) [0|7] "" FrontCamera - SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" FrontCamera - SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index2 : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 829 M_33Dhex: 8 Radar - SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" FrontCamera - SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" FrontCamera - SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" FrontCamera - SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" FrontCamera - SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Valid : 55|1@1+ (1,0) [0|1] "" FrontCamera - SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Meas : 61|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Tracked : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 830 M_33Dhex2: 8 Radar - SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" FrontCamera - SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" FrontCamera - SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" FrontCamera - SG_ MovingState : 22|2@1+ (1,0) [0|3] "" FrontCamera - SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" FrontCamera - SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" FrontCamera - SG_ axSigma : 36|6@1+ (1,0) [0|63] "" FrontCamera - SG_ dySigma : 42|6@1+ (1,0) [0|63] "" FrontCamera - SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Class : 53|3@1+ (1,0) [0|7] "" FrontCamera - SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" FrontCamera - SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index2 : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 832 M_340hex: 8 Radar - SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" FrontCamera - SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" FrontCamera - SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" FrontCamera - SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" FrontCamera - SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Valid : 55|1@1+ (1,0) [0|1] "" FrontCamera - SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Meas : 61|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Tracked : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 833 M_340hex2: 8 Radar - SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" FrontCamera - SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" FrontCamera - SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" FrontCamera - SG_ MovingState : 22|2@1+ (1,0) [0|3] "" FrontCamera - SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" FrontCamera - SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" FrontCamera - SG_ axSigma : 36|6@1+ (1,0) [0|63] "" FrontCamera - SG_ dySigma : 42|6@1+ (1,0) [0|63] "" FrontCamera - SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Class : 53|3@1+ (1,0) [0|7] "" FrontCamera - SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" FrontCamera - SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index2 : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 835 M_343hex: 8 Radar - SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" FrontCamera - SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" FrontCamera - SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" FrontCamera - SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" FrontCamera - SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Valid : 55|1@1+ (1,0) [0|1] "" FrontCamera - SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Meas : 61|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Tracked : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 836 M_343hex2: 8 Radar - SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" FrontCamera - SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" FrontCamera - SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" FrontCamera - SG_ MovingState : 22|2@1+ (1,0) [0|3] "" FrontCamera - SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" FrontCamera - SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" FrontCamera - SG_ axSigma : 36|6@1+ (1,0) [0|63] "" FrontCamera - SG_ dySigma : 42|6@1+ (1,0) [0|63] "" FrontCamera - SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Class : 53|3@1+ (1,0) [0|7] "" FrontCamera - SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" FrontCamera - SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index2 : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 838 M_346hex: 8 Radar - SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" FrontCamera - SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" FrontCamera - SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" FrontCamera - SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" FrontCamera - SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Valid : 55|1@1+ (1,0) [0|1] "" FrontCamera - SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Meas : 61|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Tracked : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 839 M_346hex2: 8 Radar - SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" FrontCamera - SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" FrontCamera - SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" FrontCamera - SG_ MovingState : 22|2@1+ (1,0) [0|3] "" FrontCamera - SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" FrontCamera - SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" FrontCamera - SG_ axSigma : 36|6@1+ (1,0) [0|63] "" FrontCamera - SG_ dySigma : 42|6@1+ (1,0) [0|63] "" FrontCamera - SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Class : 53|3@1+ (1,0) [0|7] "" FrontCamera - SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" FrontCamera - SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index2 : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 841 M_349hex: 8 Radar - SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" FrontCamera - SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" FrontCamera - SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" FrontCamera - SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" FrontCamera - SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Valid : 55|1@1+ (1,0) [0|1] "" FrontCamera - SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Meas : 61|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Tracked : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 842 M_349hex2: 8 Radar - SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" FrontCamera - SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" FrontCamera - SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" FrontCamera - SG_ MovingState : 22|2@1+ (1,0) [0|3] "" FrontCamera - SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" FrontCamera - SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" FrontCamera - SG_ axSigma : 36|6@1+ (1,0) [0|63] "" FrontCamera - SG_ dySigma : 42|6@1+ (1,0) [0|63] "" FrontCamera - SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Class : 53|3@1+ (1,0) [0|7] "" FrontCamera - SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" FrontCamera - SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index2 : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 844 M_34Chex: 8 Radar - SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" FrontCamera - SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" FrontCamera - SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" FrontCamera - SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" FrontCamera - SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Valid : 55|1@1+ (1,0) [0|1] "" FrontCamera - SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Meas : 61|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Tracked : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 845 M_34Chex2: 8 Radar - SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" FrontCamera - SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" FrontCamera - SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" FrontCamera - SG_ MovingState : 22|2@1+ (1,0) [0|3] "" FrontCamera - SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" FrontCamera - SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" FrontCamera - SG_ axSigma : 36|6@1+ (1,0) [0|63] "" FrontCamera - SG_ dySigma : 42|6@1+ (1,0) [0|63] "" FrontCamera - SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Class : 53|3@1+ (1,0) [0|7] "" FrontCamera - SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" FrontCamera - SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index2 : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 847 M_34Fhex: 8 Radar - SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" FrontCamera - SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" FrontCamera - SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" FrontCamera - SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" FrontCamera - SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Valid : 55|1@1+ (1,0) [0|1] "" FrontCamera - SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Meas : 61|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Tracked : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 848 M_34Fhex2: 8 Radar - SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" FrontCamera - SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" FrontCamera - SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" FrontCamera - SG_ MovingState : 22|2@1+ (1,0) [0|3] "" FrontCamera - SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" FrontCamera - SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" FrontCamera - SG_ axSigma : 36|6@1+ (1,0) [0|63] "" FrontCamera - SG_ dySigma : 42|6@1+ (1,0) [0|63] "" FrontCamera - SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Class : 53|3@1+ (1,0) [0|7] "" FrontCamera - SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" FrontCamera - SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index2 : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 850 M_352hex: 8 Radar - SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" FrontCamera - SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" FrontCamera - SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" FrontCamera - SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" FrontCamera - SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Valid : 55|1@1+ (1,0) [0|1] "" FrontCamera - SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Meas : 61|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Tracked : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 851 M_352hex2: 8 Radar - SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" FrontCamera - SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" FrontCamera - SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" FrontCamera - SG_ MovingState : 22|2@1+ (1,0) [0|3] "" FrontCamera - SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" FrontCamera - SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" FrontCamera - SG_ axSigma : 36|6@1+ (1,0) [0|63] "" FrontCamera - SG_ dySigma : 42|6@1+ (1,0) [0|63] "" FrontCamera - SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Class : 53|3@1+ (1,0) [0|7] "" FrontCamera - SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" FrontCamera - SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index2 : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 853 M_355hex: 8 Radar - SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" FrontCamera - SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" FrontCamera - SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" FrontCamera - SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" FrontCamera - SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Valid : 55|1@1+ (1,0) [0|1] "" FrontCamera - SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Meas : 61|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Tracked : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 854 M_355hex2: 8 Radar - SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" FrontCamera - SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" FrontCamera - SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" FrontCamera - SG_ MovingState : 22|2@1+ (1,0) [0|3] "" FrontCamera - SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" FrontCamera - SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" FrontCamera - SG_ axSigma : 36|6@1+ (1,0) [0|63] "" FrontCamera - SG_ dySigma : 42|6@1+ (1,0) [0|63] "" FrontCamera - SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Class : 53|3@1+ (1,0) [0|7] "" FrontCamera - SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" FrontCamera - SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index2 : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 856 M_358hex: 8 Radar - SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" FrontCamera - SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" FrontCamera - SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" FrontCamera - SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" FrontCamera - SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Valid : 55|1@1+ (1,0) [0|1] "" FrontCamera - SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Meas : 61|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Tracked : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 857 M_358hex2: 8 Radar - SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" FrontCamera - SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" FrontCamera - SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" FrontCamera - SG_ MovingState : 22|2@1+ (1,0) [0|3] "" FrontCamera - SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" FrontCamera - SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" FrontCamera - SG_ axSigma : 36|6@1+ (1,0) [0|63] "" FrontCamera - SG_ dySigma : 42|6@1+ (1,0) [0|63] "" FrontCamera - SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Class : 53|3@1+ (1,0) [0|7] "" FrontCamera - SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" FrontCamera - SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index2 : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 859 M_35Bhex: 8 Radar - SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" FrontCamera - SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" FrontCamera - SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" FrontCamera - SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" FrontCamera - SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Valid : 55|1@1+ (1,0) [0|1] "" FrontCamera - SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Meas : 61|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Tracked : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 860 M_35Bhex2: 8 Radar - SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" FrontCamera - SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" FrontCamera - SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" FrontCamera - SG_ MovingState : 22|2@1+ (1,0) [0|3] "" FrontCamera - SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" FrontCamera - SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" FrontCamera - SG_ axSigma : 36|6@1+ (1,0) [0|63] "" FrontCamera - SG_ dySigma : 42|6@1+ (1,0) [0|63] "" FrontCamera - SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Class : 53|3@1+ (1,0) [0|7] "" FrontCamera - SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" FrontCamera - SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index2 : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 862 M_35Ehex: 8 Radar - SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" FrontCamera - SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" FrontCamera - SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" FrontCamera - SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" FrontCamera - SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Valid : 55|1@1+ (1,0) [0|1] "" FrontCamera - SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Meas : 61|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Tracked : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 863 M_35Ehex2: 8 Radar - SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" FrontCamera - SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" FrontCamera - SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" FrontCamera - SG_ MovingState : 22|2@1+ (1,0) [0|3] "" FrontCamera - SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" FrontCamera - SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" FrontCamera - SG_ axSigma : 36|6@1+ (1,0) [0|63] "" FrontCamera - SG_ dySigma : 42|6@1+ (1,0) [0|63] "" FrontCamera - SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Class : 53|3@1+ (1,0) [0|7] "" FrontCamera - SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" FrontCamera - SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index2 : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 865 M_361hex: 8 Radar - SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" FrontCamera - SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" FrontCamera - SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" FrontCamera - SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" FrontCamera - SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Valid : 55|1@1+ (1,0) [0|1] "" FrontCamera - SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Meas : 61|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Tracked : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 866 M_361hex2: 8 Radar - SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" FrontCamera - SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" FrontCamera - SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" FrontCamera - SG_ MovingState : 22|2@1+ (1,0) [0|3] "" FrontCamera - SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" FrontCamera - SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" FrontCamera - SG_ axSigma : 36|6@1+ (1,0) [0|63] "" FrontCamera - SG_ dySigma : 42|6@1+ (1,0) [0|63] "" FrontCamera - SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Class : 53|3@1+ (1,0) [0|7] "" FrontCamera - SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" FrontCamera - SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index2 : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 868 M_364hex: 8 Radar - SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" FrontCamera - SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" FrontCamera - SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" FrontCamera - SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" FrontCamera - SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Valid : 55|1@1+ (1,0) [0|1] "" FrontCamera - SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Meas : 61|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Tracked : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 869 M_364hex2: 8 Radar - SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" FrontCamera - SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" FrontCamera - SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" FrontCamera - SG_ MovingState : 22|2@1+ (1,0) [0|3] "" FrontCamera - SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" FrontCamera - SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" FrontCamera - SG_ axSigma : 36|6@1+ (1,0) [0|63] "" FrontCamera - SG_ dySigma : 42|6@1+ (1,0) [0|63] "" FrontCamera - SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Class : 53|3@1+ (1,0) [0|7] "" FrontCamera - SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" FrontCamera - SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index2 : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 871 M_367hex: 8 Radar - SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" FrontCamera - SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" FrontCamera - SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" FrontCamera - SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" FrontCamera - SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Valid : 55|1@1+ (1,0) [0|1] "" FrontCamera - SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Meas : 61|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Tracked : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 872 M_367hex2: 8 Radar - SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" FrontCamera - SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" FrontCamera - SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" FrontCamera - SG_ MovingState : 22|2@1+ (1,0) [0|3] "" FrontCamera - SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" FrontCamera - SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" FrontCamera - SG_ axSigma : 36|6@1+ (1,0) [0|63] "" FrontCamera - SG_ dySigma : 42|6@1+ (1,0) [0|63] "" FrontCamera - SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Class : 53|3@1+ (1,0) [0|7] "" FrontCamera - SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" FrontCamera - SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index2 : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 874 M_36Ahex: 8 Radar - SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" FrontCamera - SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" FrontCamera - SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" FrontCamera - SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" FrontCamera - SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Valid : 55|1@1+ (1,0) [0|1] "" FrontCamera - SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Meas : 61|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Tracked : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 875 M_36Ahex2: 8 Radar - SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" FrontCamera - SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" FrontCamera - SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" FrontCamera - SG_ MovingState : 22|2@1+ (1,0) [0|3] "" FrontCamera - SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" FrontCamera - SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" FrontCamera - SG_ axSigma : 36|6@1+ (1,0) [0|63] "" FrontCamera - SG_ dySigma : 42|6@1+ (1,0) [0|63] "" FrontCamera - SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Class : 53|3@1+ (1,0) [0|7] "" FrontCamera - SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" FrontCamera - SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index2 : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 877 M_36Dhex: 8 Radar - SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" FrontCamera - SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" FrontCamera - SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" FrontCamera - SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" FrontCamera - SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Valid : 55|1@1+ (1,0) [0|1] "" FrontCamera - SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Meas : 61|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Tracked : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 878 M_36Dhex2: 8 Radar - SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" FrontCamera - SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" FrontCamera - SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" FrontCamera - SG_ MovingState : 22|2@1+ (1,0) [0|3] "" FrontCamera - SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" FrontCamera - SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" FrontCamera - SG_ axSigma : 36|6@1+ (1,0) [0|63] "" FrontCamera - SG_ dySigma : 42|6@1+ (1,0) [0|63] "" FrontCamera - SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Class : 53|3@1+ (1,0) [0|7] "" FrontCamera - SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" FrontCamera - SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index2 : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 881 L_1_371hex: 8 Radar - SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" FrontCamera - SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" FrontCamera - SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" FrontCamera - SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" FrontCamera - SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Valid : 55|1@1+ (1,0) [0|1] "" FrontCamera - SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Meas : 61|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Tracked : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 882 L_1_371hex2: 8 Radar - SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" FrontCamera - SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" FrontCamera - SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" FrontCamera - SG_ MovingState : 22|2@1+ (1,0) [0|3] "" FrontCamera - SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" FrontCamera - SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" FrontCamera - SG_ axSigma : 36|6@1+ (1,0) [0|63] "" FrontCamera - SG_ dySigma : 42|6@1+ (1,0) [0|63] "" FrontCamera - SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Class : 53|3@1+ (1,0) [0|7] "" FrontCamera - SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" FrontCamera - SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index2 : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 884 L_2_374hex: 8 Radar - SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" FrontCamera - SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" FrontCamera - SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" FrontCamera - SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" FrontCamera - SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Valid : 55|1@1+ (1,0) [0|1] "" FrontCamera - SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Meas : 61|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Tracked : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 885 L_2_375hex2: 8 Radar - SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" FrontCamera - SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" FrontCamera - SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" FrontCamera - SG_ MovingState : 22|2@1+ (1,0) [0|3] "" FrontCamera - SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" FrontCamera - SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" FrontCamera - SG_ axSigma : 36|6@1+ (1,0) [0|63] "" FrontCamera - SG_ dySigma : 42|6@1+ (1,0) [0|63] "" FrontCamera - SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Class : 53|3@1+ (1,0) [0|7] "" FrontCamera - SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" FrontCamera - SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index2 : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 887 L_3_377hex: 8 Radar - SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" FrontCamera - SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" FrontCamera - SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" FrontCamera - SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" FrontCamera - SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Valid : 55|1@1+ (1,0) [0|1] "" FrontCamera - SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Meas : 61|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Tracked : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 888 L_3_378hex2: 8 Radar - SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" FrontCamera - SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" FrontCamera - SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" FrontCamera - SG_ MovingState : 22|2@1+ (1,0) [0|3] "" FrontCamera - SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" FrontCamera - SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" FrontCamera - SG_ axSigma : 36|6@1+ (1,0) [0|63] "" FrontCamera - SG_ dySigma : 42|6@1+ (1,0) [0|63] "" FrontCamera - SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Class : 53|3@1+ (1,0) [0|7] "" FrontCamera - SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" FrontCamera - SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index2 : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 890 L_4_37ahex: 8 Radar - SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" FrontCamera - SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" FrontCamera - SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" FrontCamera - SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" FrontCamera - SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Valid : 55|1@1+ (1,0) [0|1] "" FrontCamera - SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Meas : 61|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Tracked : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 891 L_4_37ahex2: 8 Radar - SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" FrontCamera - SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" FrontCamera - SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" FrontCamera - SG_ MovingState : 22|2@1+ (1,0) [0|3] "" FrontCamera - SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" FrontCamera - SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" FrontCamera - SG_ axSigma : 36|6@1+ (1,0) [0|63] "" FrontCamera - SG_ dySigma : 42|6@1+ (1,0) [0|63] "" FrontCamera - SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Class : 53|3@1+ (1,0) [0|7] "" FrontCamera - SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" FrontCamera - SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index2 : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 893 L_5_37dhex: 8 Radar - SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" FrontCamera - SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" FrontCamera - SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" FrontCamera - SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" FrontCamera - SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Valid : 55|1@1+ (1,0) [0|1] "" FrontCamera - SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Meas : 61|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Tracked : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 894 L_5_37dhex2: 8 Radar - SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" FrontCamera - SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" FrontCamera - SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" FrontCamera - SG_ MovingState : 22|2@1+ (1,0) [0|3] "" FrontCamera - SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" FrontCamera - SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" FrontCamera - SG_ axSigma : 36|6@1+ (1,0) [0|63] "" FrontCamera - SG_ dySigma : 42|6@1+ (1,0) [0|63] "" FrontCamera - SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" FrontCamera - SG_ Class : 53|3@1+ (1,0) [0|7] "" FrontCamera - SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" FrontCamera - SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" FrontCamera - SG_ Index2 : 63|1@1+ (1,0) [0|1] "" FrontCamera - -BO_ 697 VIN_VIP_405HS: 8 FrontCamera - SG_ VIN_MuxID M : 0|8@1+ (1,0) [0|0] "" Radar - SG_ VIN_Part1 m16 : 47|24@0+ (1,0) [0|16777215] "" Radar - SG_ VIN_Part2 m17 : 15|56@0+ (1,0) [0|7.2057594038E+16] "" Radar - SG_ VIN_Part3 m18 : 15|56@0+ (1,0) [0|7.2057594038E+16] "" Radar - -BO_ 681 Msg2A9_GTW_carConfig: 8 FrontCamera - SG_ Msg2A9_Always0x02 : 48|8@1+ (1,0) [0|0] "" Radar - SG_ Msg2A9_Always0x10 : 56|8@1+ (1,0) [0|0] "" Radar - SG_ Msg2A9_Always0x16 : 8|8@1+ (1,0) [0|0] "" Radar - SG_ Msg2A9_Always0x41 : 24|8@1+ (1,0) [0|0] "" Radar - SG_ Msg2A9_Value1_0x02 : 0|3@1+ (1,0) [0|0] "" Radar - SG_ Msg2A9_FourWheelDrive : 3|2@1+ (1,0) [0|0] "" Radar - SG_ Msg2A9_Value2_0x02 : 5|3@1+ (1,0) [0|0] "" Radar - SG_ Msg2A9_Always0x43 : 16|8@1+ (1,0) [0|0] "" Radar - -BO_ 409 Msg199_STW_ANGLHP_STAT: 8 FrontCamera - SG_ Msg199Always0x04 : 32|8@1+ (1,0) [0|0] "" Radar - SG_ Msg199Always0x20 : 16|8@1+ (1,0) [0|0] "" Radar - SG_ Msg199Always0x2F : 0|8@1+ (1,0) [0|0] "" Radar - SG_ Msg199Always0x67 : 8|8@1+ (1,0) [0|0] "" Radar - SG_ Msg199Always0xFF : 40|8@1+ (1,0) [0|0] "" Radar - SG_ Msg199Checksum : 56|8@1+ (1,0) [0|0] "" Radar - SG_ Msg199Counter : 52|4@1+ (1,0) [0|0] "" Radar - -BO_ 361 Msg169_ESP_wheelSpeeds: 8 FrontCamera - SG_ ESP_wheelSpeedFrL_HS : 0|13@1+ (0.04,0) [0|327.64] "km/h" Radar - SG_ ESP_wheelSpeedFrR_HS : 13|13@1+ (0.04,0) [0|327.64] "km/h" Radar - SG_ ESP_wheelSpeedReL_HS : 26|13@1+ (0.04,0) [0|327.64] "km/h" Radar - SG_ ESP_wheelSpeedReR_HS : 39|13@1+ (0.04,0) [0|327.64] "km/h" Radar - SG_ Msg169Checksum : 56|8@1+ (1,0) [0|0] "" Radar - SG_ Msg169Counter : 52|4@1+ (1,0) [0|0] "" Radar - -BO_ 345 Msg159_ESP_C: 8 FrontCamera - SG_ Msg159Always0x3A : 16|8@1+ (1,0) [0|0] "" Radar - SG_ Msg159Always0xA5 : 0|8@1+ (1,0) [0|0] "" Radar - SG_ Msg159Always0xCF : 32|8@1+ (1,0) [0|0] "" Radar - SG_ Msg159Always0xF4 : 8|8@1+ (1,0) [0|0] "" Radar - SG_ Msg159Counter : 44|4@1+ (1,0) [0|0] "" Radar - SG_ Msg159Checksum : 24|8@1+ (1,0) [0|0] "" Radar - -BO_ 329 Msg149_ESP_145h: 8 FrontCamera - SG_ Msg149Always0x02 : 16|8@1+ (1,0) [0|0] "" Radar - SG_ Msg149Always0x04 : 40|8@1+ (1,0) [0|0] "" Radar - SG_ Msg149Always0x26 : 8|8@1+ (1,0) [0|0] "" Radar - SG_ Msg149Always0x6A : 24|8@1+ (1,0) [0|0] "" Radar - SG_ Msg149Always0xAA : 32|8@1+ (1,0) [0|0] "" Radar - SG_ Msg149Always0xF : 48|4@1+ (1,0) [0|0] "" Radar - SG_ Msg149Checksum : 56|8@1+ (1,0) [0|0] "" Radar - SG_ Msg149Counter : 52|4@1+ (1,0) [0|0] "" Radar - -BO_ 297 Msg129_ESP_115h: 6 FrontCamera - SG_ Msg129Always0x20 : 24|8@1+ (1,0) [0|0] "" Radar - SG_ Msg129Checksum : 40|8@1+ (1,0) [0|0] "" Radar - SG_ Msg129Counter : 36|4@1+ (1,0) [0|0] "" Radar - -BO_ 281 Msg119_DI_torque2: 6 FrontCamera - SG_ Msg119Always0x11 : 24|8@1+ (1,0) [0|0] "" Radar - SG_ Msg119Always0x1F : 8|8@1+ (1,0) [0|0] "" Radar - SG_ Msg119Always0x8 : 36|4@1+ (1,0) [0|0] "" Radar - SG_ Msg119Always0xF4 : 16|8@1+ (1,0) [0|0] "" Radar - SG_ Msg119Always0xFF : 0|8@1+ (1,0) [0|0] "" Radar - SG_ Msg119Checksum : 40|8@1+ (1,0) [0|0] "" Radar - SG_ Msg119Counter : 32|4@1+ (1,0) [0|0] "" Radar - -BO_ 265 Msg109_DI_torque1: 8 FrontCamera - SG_ Msg109Always0x80 : 24|8@1+ (1,0) [0|0] "" Radar - SG_ Msg109Checksum : 56|8@1+ (1,0) [0|0] "" Radar - SG_ Msg109Counter : 13|3@1+ (1,0) [0|0] "" Radar - -BO_ 521 Msg209_GTW_odo: 8 FrontCamera - SG_ Msg209Always0x61 : 8|8@1+ (1,0) [0|0] "" Radar - SG_ Msg209Always0x94 : 16|8@1+ (1,0) [0|0] "" Radar - SG_ Msg209Always0x52 : 24|8@1+ (1,0) [0|0] "" Radar - SG_ Msg209Always0x13 : 32|8@1+ (1,0) [0|0] "" Radar - SG_ Msg209Always0x03 : 40|8@1+ (1,0) [0|0] "" Radar - SG_ Msg209Always0x80 : 48|8@1+ (1,0) [0|0] "" Radar - -BO_ 537 Msg219_STW_ACTN_RQ: 8 FrontCamera - SG_ Msg219Counter : 52|4@1+ (1,0) [0|15] "" Radar - SG_ Msg219CRC : 56|8@1+ (1,0) [0|0] "" Radar - -BO_ 425 Msg1A9_DI_espControl: 5 FrontCamera - SG_ Msg1A9Always0x0C : 16|8@1+ (1,0) [0|0] "" Radar - SG_ Msg1A9Counter : 28|4@1+ (1,0) [0|0] "" Radar - SG_ Msg1A9Checksum : 32|8@1+ (1,0) [0|0] "" Radar - -BO_ 729 Msg2D9_BC_status : 8 FrontCamera - SG_ Msg2D9Always0x80 : 0|8@1+ (1,0) [0|0] "" Radar - SG_ Msg2D9Always0x40 : 8|8@1+ (1,0) [0|0] "" Radar - SG_ Msg2D9Always0x83 : 16|8@1+ (1,0) [0|0] "" Radar - -BO_ 1601 UDS_radarRequest: 8 FrontCamera - SG_ UDS_radarRequestData : 7|64@0+ (1,0) [0|0] "" Radar - -BO_ 1617 Radar_udsResponse: 8 Radar - SG_ Radar_udsResponseData : 7|64@0+ (1,0) [0|0] "" FrontCamera - -CM_ BO_ 697 "Start with MuxID 0x12, then 0x11 and finally 0x10 (VIN is then transmitted in the reverse order)"; -CM_ BO_ 681 "Message sent every 1000 ms. All fixed bytes, no checksum, the byte for RWD or AWD needs to match VIN config"; -CM_ BO_ 409 "Message sent every 10ms. Checksum : use all first 7 bytes with the SAE J1850 CRC algo"; -CM_ BO_ 361 "Message sent every 10ms. Checksum : Sum of all first 7 bytes + 0x76"; -CM_ BO_ 345 "Message sent every 20ms. Checksum : Sum of all first bytes + 0xc; place checksum in 4th octet"; -CM_ BO_ 329 "Message sent every 20ms. Checksum : Sum of all first 7 bytes + 0x46"; -CM_ BO_ 297 "Message sent every 20ms. Checksum : Sum of all first 5 bytes + 0x16"; -CM_ BO_ 281 "Message sent every 10ms. Checksum : Sum of all first 5 bytes + 0x17"; -CM_ BO_ 265 "Message sent every 10ms. Checksum : Sum of all first 7 bytes + 0x7"; -CM_ BO_ 521 "Message sent every 100ms. All fixed bytes, no checksum."; -CM_ BO_ 537 "Message sent every 100ms. Checksum : use all first 7 bytes with the SAE J1850 CRC algo"; -CM_ BO_ 425 "Message sent every 20ms. Checksum : Sum of all first 4 bytes + 0x38"; -CM_ BO_ 729 "Message sent every 1000ms. All fixed bytes, no checksum."; - -BA_DEF_ "BusType" STRING ; -BA_DEF_ BO_ "GenMsgCycleTime" INT 0 0; -BA_DEF_ SG_ "FieldType" STRING ; - -BA_DEF_DEF_ "BusType" "CAN"; -BA_DEF_DEF_ "FieldType" ""; -BA_DEF_DEF_ "GenMsgCycleTime" 0; - -BA_ "GenMsgCycleTime" BO_ 697 250; -BA_ "GenMsgCycleTime" BO_ 681 1000; -BA_ "GenMsgCycleTime" BO_ 409 10; -BA_ "GenMsgCycleTime" BO_ 361 10; -BA_ "GenMsgCycleTime" BO_ 345 20; -BA_ "GenMsgCycleTime" BO_ 329 20; -BA_ "GenMsgCycleTime" BO_ 297 20; -BA_ "GenMsgCycleTime" BO_ 281 10; -BA_ "GenMsgCycleTime" BO_ 265 10; -BA_ "GenMsgCycleTime" BO_ 521 100; -BA_ "GenMsgCycleTime" BO_ 537 100; -BA_ "GenMsgCycleTime" BO_ 425 20; -BA_ "GenMsgCycleTime" BO_ 729 1000; - -VAL_ 681 Msg2A9_FourWheelDrive 3 "SNA" 2 "UNUSED" 1 "4WD" 0 "2WD" ; -VAL_ 785 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; -VAL_ 785 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; -VAL_ 788 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; -VAL_ 788 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; -VAL_ 791 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; -VAL_ 791 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; -VAL_ 794 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; -VAL_ 794 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; -VAL_ 797 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; -VAL_ 797 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; -VAL_ 800 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; -VAL_ 800 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; -VAL_ 803 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; -VAL_ 803 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; -VAL_ 806 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; -VAL_ 806 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; -VAL_ 809 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; -VAL_ 809 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; -VAL_ 812 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; -VAL_ 812 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; -VAL_ 815 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; -VAL_ 815 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; -VAL_ 818 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; -VAL_ 818 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; -VAL_ 821 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; -VAL_ 821 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; -VAL_ 824 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; -VAL_ 824 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; -VAL_ 827 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; -VAL_ 827 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; -VAL_ 830 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; -VAL_ 830 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; -VAL_ 833 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; -VAL_ 833 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; -VAL_ 836 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; -VAL_ 836 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; -VAL_ 839 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; -VAL_ 839 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; -VAL_ 842 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; -VAL_ 842 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; -VAL_ 845 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; -VAL_ 845 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; -VAL_ 848 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; -VAL_ 848 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; -VAL_ 851 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; -VAL_ 851 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; -VAL_ 854 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; -VAL_ 854 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; -VAL_ 857 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; -VAL_ 857 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; -VAL_ 860 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; -VAL_ 860 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; -VAL_ 863 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; -VAL_ 863 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; -VAL_ 866 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; -VAL_ 866 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; -VAL_ 869 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; -VAL_ 869 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; -VAL_ 872 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; -VAL_ 872 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; -VAL_ 875 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; -VAL_ 875 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; -VAL_ 878 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; -VAL_ 878 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; -VAL_ 882 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; -VAL_ 882 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; -VAL_ 885 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; -VAL_ 885 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; -VAL_ 888 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; -VAL_ 888 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; -VAL_ 891 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; -VAL_ 891 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; -VAL_ 894 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; -VAL_ 894 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; - diff --git a/tesla_radar_bosch_generated.dbc b/tesla_radar_bosch_generated.dbc new file mode 100644 index 0000000000..cdd03908a5 --- /dev/null +++ b/tesla_radar_bosch_generated.dbc @@ -0,0 +1,1373 @@ +CM_ "AUTOGENERATED FILE, DO NOT EDIT"; + +CM_ "tesla_radar_bosch.dbc starts here"; + +VERSION "" + +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_ + SG_MUL_VAL_ + +BS_: + +BU_: Autopilot Radar Diag + + +BO_ 769 TeslaRadarSguInfo: 8 Radar + SG_ RADC_VerticalMisalignment : 0|8@1+ (1,0) [0|255] "" Autopilot + SG_ RADC_SCUTemperature : 8|8@1+ (1,-128) [-128|127] "" Autopilot + SG_ RADC_VMA_Plaus : 16|8@1+ (1,0) [0|255] "" Autopilot + SG_ RADC_SGU_ITC : 24|8@1+ (1,0) [0|255] "" Autopilot + SG_ RADC_HorizontMisalignment : 32|12@1+ (1,0) [0|4096] "" Autopilot + SG_ RADC_SensorDirty : 44|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_HWFail : 45|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_SGUFail : 46|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_SGUInfoConsistBit : 47|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 770 TeslaRadarTguInfo: 8 Radar + SG_ RADC_ACCTargObj1_sguIndex : 0|6@1+ (1,0) [0|63] "" Autopilot + SG_ RADC_ACCTargObj2_sguIndex : 6|6@1+ (1,0) [0|63] "" Autopilot + SG_ RADC_ACCTargObj3_sguIndex : 12|6@1+ (1,0) [0|63] "" Autopilot + SG_ RADC_ACCTargObj4_sguIndex : 18|6@1+ (1,0) [0|63] "" Autopilot + SG_ RADC_ACCTargObj5_sguIndex : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ unused30 : 30|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_TGUInfoConsistBit : 31|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_ACCTargObj1_dBPower : 32|16@1+ (1,0) [0|65535] "" Autopilot + SG_ RADC_ACCTargObj5_dBPower : 48|16@1+ (1,0) [0|65535] "" Autopilot + +BO_ 1281 TeslaRadarAlertMatrix: 8 Radar + SG_ RADC_a001_ecuInternalPerf : 0|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a002_flashPerformance : 1|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a003_vBatHigh : 2|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a004_adjustmentNotDone : 3|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a005_adjustmentReq : 4|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a006_adjustmentNotOk : 5|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a007_sensorBlinded : 6|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a008_plantModeActive : 7|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a009_configMismatch : 8|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a010_canBusOff : 9|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a011_bdyMIA : 10|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a012_espMIA : 11|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a013_gtwMIA : 12|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a014_sccmMIA : 13|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a015_adasMIA : 14|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a016_bdyInvalidCount : 15|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a017_adasInvalidCount : 16|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a018_espInvalidCount : 17|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a019_sccmInvalidCount : 18|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a020_bdyInvalidChkSm : 19|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a021_espInvalidChkSm : 20|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a022_sccmInvalidChkSm : 21|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a023_sccmInvalidChkSm : 22|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a024_absValidity : 23|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a025_ambTValidity : 24|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a026_brakeValidity : 25|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a027_CntryCdValidity : 26|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a028_espValidity : 27|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a029_longAccOffValidity : 28|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a030_longAccValidity : 29|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a031_odoValidity : 30|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a032_gearValidity : 31|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a033_steerAngValidity : 32|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a034_steerAngSpdValidity : 33|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a035_indctrValidity : 34|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a036_vehStandStillValidity : 35|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a037_vinValidity : 36|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a038_whlRotValidity : 37|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a039_whlSpdValidity : 38|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a040_whlStandStillValidity : 39|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a041_wiperValidity : 40|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a042_xwdValidity : 41|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a043_yawOffValidity : 42|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a044_yawValidity : 43|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a045_bsdSanity : 44|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a046_rctaSanity : 45|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a047_lcwSanity : 46|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a048_steerAngOffSanity : 47|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a049_tireSizeSanity : 48|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a050_velocitySanity : 49|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a051_yawSanity : 50|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a052_radomeHtrInop : 51|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a053_espmodValidity : 52|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a054_gtwmodValidity : 53|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a055_stwmodValidity : 54|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a056_bcmodValidity : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a057_dimodValidity : 56|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a058_opmodValidity : 57|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a059_drmiInvalidChkSm : 58|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a060_drmiInvalidCount : 59|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a061_radPositionMismatch : 60|1@1+ (1,0) [0|1] "" Autopilot + SG_ RADC_a062_strRackMismatch : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ unused62 : 62|2@1+ (1,0) [0|3] "" Autopilot + +BO_ 784 RadarPoint0_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 785 RadarPoint0_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 787 RadarPoint1_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 788 RadarPoint1_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 790 RadarPoint2_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 791 RadarPoint2_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 793 RadarPoint3_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 794 RadarPoint3_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 796 RadarPoint4_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 797 RadarPoint4_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 799 RadarPoint5_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 800 RadarPoint5_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 802 RadarPoint6_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 803 RadarPoint6_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 805 RadarPoint7_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 806 RadarPoint7_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 808 RadarPoint8_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 809 RadarPoint8_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 811 RadarPoint9_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 812 RadarPoint9_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 814 RadarPoint10_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 815 RadarPoint10_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 817 RadarPoint11_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 818 RadarPoint11_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 820 RadarPoint12_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 821 RadarPoint12_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 823 RadarPoint13_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 824 RadarPoint13_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 826 RadarPoint14_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 827 RadarPoint14_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 829 RadarPoint15_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 830 RadarPoint15_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 832 RadarPoint16_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 833 RadarPoint16_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 835 RadarPoint17_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 836 RadarPoint17_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 838 RadarPoint18_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 839 RadarPoint18_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 841 RadarPoint19_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 842 RadarPoint19_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 844 RadarPoint20_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 845 RadarPoint20_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 847 RadarPoint21_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 848 RadarPoint21_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 850 RadarPoint22_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 851 RadarPoint22_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 853 RadarPoint23_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 854 RadarPoint23_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 856 RadarPoint24_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 857 RadarPoint24_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 859 RadarPoint25_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 860 RadarPoint25_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 862 RadarPoint26_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 863 RadarPoint26_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 865 RadarPoint27_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 866 RadarPoint27_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 868 RadarPoint28_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 869 RadarPoint28_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 871 RadarPoint29_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 872 RadarPoint29_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 874 RadarPoint30_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 875 RadarPoint30_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 877 RadarPoint31_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 878 RadarPoint31_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 881 ProcessedRadarPoint1_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 882 ProcessedRadarPoint1_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 884 ProcessedRadarPoint2_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 885 ProcessedRadarPoint2_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 887 ProcessedRadarPoint3_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 888 ProcessedRadarPoint3_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 890 ProcessedRadarPoint4_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 891 ProcessedRadarPoint4_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 893 ProcessedRadarPoint5_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 894 ProcessedRadarPoint5_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 697 VIN_VIP_405HS: 8 Autopilot + SG_ VIN_MuxID M : 0|8@1+ (1,0) [0|0] "" Radar + SG_ VIN_Part1 m16 : 47|24@0+ (1,0) [0|16777215] "" Radar + SG_ VIN_Part2 m17 : 15|56@0+ (1,0) [0|7.2057594038E+16] "" Radar + SG_ VIN_Part3 m18 : 15|56@0+ (1,0) [0|7.2057594038E+16] "" Radar + +BO_ 681 Msg2A9_GTW_carConfig: 8 Autopilot + SG_ Msg2A9_Always0x02 : 48|8@1+ (1,0) [0|0] "" Radar + SG_ Msg2A9_Always0x10 : 56|8@1+ (1,0) [0|0] "" Radar + SG_ Msg2A9_Always0x16 : 8|8@1+ (1,0) [0|0] "" Radar + SG_ Msg2A9_Always0x41 : 24|8@1+ (1,0) [0|0] "" Radar + SG_ Msg2A9_Value1_0x02 : 0|3@1+ (1,0) [0|0] "" Radar + SG_ Msg2A9_FourWheelDrive : 3|2@1+ (1,0) [0|0] "" Radar + SG_ Msg2A9_Value2_0x02 : 5|3@1+ (1,0) [0|0] "" Radar + SG_ Msg2A9_Always0x43 : 16|8@1+ (1,0) [0|0] "" Radar + +BO_ 409 Msg199_STW_ANGLHP_STAT: 8 Autopilot + SG_ Msg199Always0x04 : 32|8@1+ (1,0) [0|0] "" Radar + SG_ Msg199Always0x20 : 16|8@1+ (1,0) [0|0] "" Radar + SG_ Msg199Always0x2F : 0|8@1+ (1,0) [0|0] "" Radar + SG_ Msg199Always0x67 : 8|8@1+ (1,0) [0|0] "" Radar + SG_ Msg199Always0xFF : 40|8@1+ (1,0) [0|0] "" Radar + SG_ Msg199Checksum : 56|8@1+ (1,0) [0|0] "" Radar + SG_ Msg199Counter : 52|4@1+ (1,0) [0|0] "" Radar + +BO_ 361 Msg169_ESP_wheelSpeeds: 8 Autopilot + SG_ ESP_wheelSpeedFrL_HS : 0|13@1+ (0.04,0) [0|327.64] "km/h" Radar + SG_ ESP_wheelSpeedFrR_HS : 13|13@1+ (0.04,0) [0|327.64] "km/h" Radar + SG_ ESP_wheelSpeedReL_HS : 26|13@1+ (0.04,0) [0|327.64] "km/h" Radar + SG_ ESP_wheelSpeedReR_HS : 39|13@1+ (0.04,0) [0|327.64] "km/h" Radar + SG_ Msg169Checksum : 56|8@1+ (1,0) [0|0] "" Radar + SG_ Msg169Counter : 52|4@1+ (1,0) [0|0] "" Radar + +BO_ 345 Msg159_ESP_C: 8 Autopilot + SG_ Msg159Always0x3A : 16|8@1+ (1,0) [0|0] "" Radar + SG_ Msg159Always0xA5 : 0|8@1+ (1,0) [0|0] "" Radar + SG_ Msg159Always0xCF : 32|8@1+ (1,0) [0|0] "" Radar + SG_ Msg159Always0xF4 : 8|8@1+ (1,0) [0|0] "" Radar + SG_ Msg159Counter : 44|4@1+ (1,0) [0|0] "" Radar + SG_ Msg159Checksum : 24|8@1+ (1,0) [0|0] "" Radar + +BO_ 329 Msg149_ESP_145h: 8 Autopilot + SG_ Msg149Always0x02 : 16|8@1+ (1,0) [0|0] "" Radar + SG_ Msg149Always0x04 : 40|8@1+ (1,0) [0|0] "" Radar + SG_ Msg149Always0x26 : 8|8@1+ (1,0) [0|0] "" Radar + SG_ Msg149Always0x6A : 24|8@1+ (1,0) [0|0] "" Radar + SG_ Msg149Always0xAA : 32|8@1+ (1,0) [0|0] "" Radar + SG_ Msg149Always0xF : 48|4@1+ (1,0) [0|0] "" Radar + SG_ Msg149Checksum : 56|8@1+ (1,0) [0|0] "" Radar + SG_ Msg149Counter : 52|4@1+ (1,0) [0|0] "" Radar + +BO_ 297 Msg129_ESP_115h: 6 Autopilot + SG_ Msg129Always0x20 : 24|8@1+ (1,0) [0|0] "" Radar + SG_ Msg129Checksum : 40|8@1+ (1,0) [0|0] "" Radar + SG_ Msg129Counter : 36|4@1+ (1,0) [0|0] "" Radar + +BO_ 281 Msg119_DI_torque2: 6 Autopilot + SG_ Msg119Always0x11 : 24|8@1+ (1,0) [0|0] "" Radar + SG_ Msg119Always0x1F : 8|8@1+ (1,0) [0|0] "" Radar + SG_ Msg119Always0x8 : 36|4@1+ (1,0) [0|0] "" Radar + SG_ Msg119Always0xF4 : 16|8@1+ (1,0) [0|0] "" Radar + SG_ Msg119Always0xFF : 0|8@1+ (1,0) [0|0] "" Radar + SG_ Msg119Checksum : 40|8@1+ (1,0) [0|0] "" Radar + SG_ Msg119Counter : 32|4@1+ (1,0) [0|0] "" Radar + +BO_ 265 Msg109_DI_torque1: 8 Autopilot + SG_ Msg109Always0x80 : 24|8@1+ (1,0) [0|0] "" Radar + SG_ Msg109Checksum : 56|8@1+ (1,0) [0|0] "" Radar + SG_ Msg109Counter : 13|3@1+ (1,0) [0|0] "" Radar + +BO_ 521 Msg209_GTW_odo: 8 Autopilot + SG_ Msg209Always0x61 : 8|8@1+ (1,0) [0|0] "" Radar + SG_ Msg209Always0x94 : 16|8@1+ (1,0) [0|0] "" Radar + SG_ Msg209Always0x52 : 24|8@1+ (1,0) [0|0] "" Radar + SG_ Msg209Always0x13 : 32|8@1+ (1,0) [0|0] "" Radar + SG_ Msg209Always0x03 : 40|8@1+ (1,0) [0|0] "" Radar + SG_ Msg209Always0x80 : 48|8@1+ (1,0) [0|0] "" Radar + +BO_ 537 Msg219_STW_ACTN_RQ: 8 Autopilot + SG_ Msg219Counter : 52|4@1+ (1,0) [0|15] "" Radar + SG_ Msg219CRC : 56|8@1+ (1,0) [0|0] "" Radar + +BO_ 425 Msg1A9_DI_espControl: 5 Autopilot + SG_ Msg1A9Always0x0C : 16|8@1+ (1,0) [0|0] "" Radar + SG_ Msg1A9Counter : 28|4@1+ (1,0) [0|0] "" Radar + SG_ Msg1A9Checksum : 32|8@1+ (1,0) [0|0] "" Radar + +BO_ 729 Msg2D9_BC_status : 8 Autopilot + SG_ Msg2D9Always0x80 : 0|8@1+ (1,0) [0|0] "" Radar + SG_ Msg2D9Always0x40 : 8|8@1+ (1,0) [0|0] "" Radar + SG_ Msg2D9Always0x83 : 16|8@1+ (1,0) [0|0] "" Radar + +BO_ 1601 UDS_radarRequest: 8 Diag + SG_ UDS_radarRequestData : 7|64@0+ (1,0) [0|0] "" Radar + +BO_ 1617 Radar_udsResponse: 8 Radar + SG_ Radar_udsResponseData : 7|64@0+ (1,0) [0|0] "" Diag + +CM_ BO_ 697 "Start with MuxID 0x12, then 0x11 and finally 0x10 (VIN is then transmitted in the reverse order)"; +CM_ BO_ 681 "Message sent every 1000 ms. All fixed bytes, no checksum, the byte for RWD or AWD needs to match VIN config"; +CM_ BO_ 409 "Message sent every 10ms. Checksum : use all first 7 bytes with the SAE J1850 CRC algo"; +CM_ BO_ 361 "Message sent every 10ms. Checksum : Sum of all first 7 bytes + 0x76"; +CM_ BO_ 345 "Message sent every 20ms. Checksum : Sum of all first bytes + 0xc; place checksum in 4th octet"; +CM_ BO_ 329 "Message sent every 20ms. Checksum : Sum of all first 7 bytes + 0x46"; +CM_ BO_ 297 "Message sent every 20ms. Checksum : Sum of all first 5 bytes + 0x16"; +CM_ BO_ 281 "Message sent every 10ms. Checksum : Sum of all first 5 bytes + 0x17"; +CM_ BO_ 265 "Message sent every 10ms. Checksum : Sum of all first 7 bytes + 0x7"; +CM_ BO_ 521 "Message sent every 100ms. All fixed bytes, no checksum."; +CM_ BO_ 537 "Message sent every 100ms. Checksum : use all first 7 bytes with the SAE J1850 CRC algo"; +CM_ BO_ 425 "Message sent every 20ms. Checksum : Sum of all first 4 bytes + 0x38"; +CM_ BO_ 729 "Message sent every 1000ms. All fixed bytes, no checksum."; + +BA_DEF_ "BusType" STRING ; +BA_DEF_ BO_ "GenMsgCycleTime" INT 0 0; +BA_DEF_ SG_ "FieldType" STRING ; + +BA_DEF_DEF_ "BusType" "CAN"; +BA_DEF_DEF_ "FieldType" ""; +BA_DEF_DEF_ "GenMsgCycleTime" 0; + +BA_ "GenMsgCycleTime" BO_ 697 250; +BA_ "GenMsgCycleTime" BO_ 681 1000; +BA_ "GenMsgCycleTime" BO_ 409 10; +BA_ "GenMsgCycleTime" BO_ 361 10; +BA_ "GenMsgCycleTime" BO_ 345 20; +BA_ "GenMsgCycleTime" BO_ 329 20; +BA_ "GenMsgCycleTime" BO_ 297 20; +BA_ "GenMsgCycleTime" BO_ 281 10; +BA_ "GenMsgCycleTime" BO_ 265 10; +BA_ "GenMsgCycleTime" BO_ 521 100; +BA_ "GenMsgCycleTime" BO_ 537 100; +BA_ "GenMsgCycleTime" BO_ 425 20; +BA_ "GenMsgCycleTime" BO_ 729 1000; + +VAL_ 681 Msg2A9_FourWheelDrive 3 "SNA" 2 "UNUSED" 1 "4WD" 0 "2WD" ; +VAL_ 785 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 785 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 788 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 788 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 791 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 791 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 794 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 794 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 797 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 797 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 800 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 800 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 803 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 803 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 806 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 806 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 809 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 809 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 812 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 812 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 815 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 815 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 818 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 818 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 821 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 821 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 824 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 824 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 827 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 827 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 830 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 830 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 833 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 833 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 836 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 836 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 839 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 839 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 842 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 842 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 845 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 845 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 848 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 848 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 851 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 851 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 854 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 854 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 857 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 857 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 860 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 860 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 863 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 863 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 866 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 866 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 869 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 869 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 872 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 872 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 875 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 875 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 878 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 878 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 882 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 882 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 885 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 885 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 888 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 888 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 891 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 891 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 894 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 894 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; \ No newline at end of file diff --git a/tesla_radar_continental_generated.dbc b/tesla_radar_continental_generated.dbc new file mode 100644 index 0000000000..9a543b3459 --- /dev/null +++ b/tesla_radar_continental_generated.dbc @@ -0,0 +1,1262 @@ +CM_ "AUTOGENERATED FILE, DO NOT EDIT"; + +CM_ "tesla_radar_continental.dbc starts here"; + +VERSION "" + +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_ + SG_MUL_VAL_ + +BS_: + +BU_: Autopilot Radar Diag + +BO_ 1025 RadarStatus: 8 Radar + SG_ carparkDetected : 29|1@1+ (1,0) [0|1] "" Autopilot + SG_ decreaseBlockage : 25|1@1+ (1,0) [0|1] "" Autopilot + SG_ horizontMisalignment : 8|12@1+ (0.00012207,-0.25) [-0.25|0.249878] "rad" Autopilot + SG_ increaseBlockage : 24|1@1+ (1,0) [0|1] "" Autopilot + SG_ lowPowerMode : 20|2@1+ (1,0) [0|3] "" Autopilot + SG_ powerOnSelfTest : 22|1@1+ (1,0) [0|1] "" Autopilot + SG_ sensorBlocked : 26|1@1+ (1,0) [0|1] "" Autopilot + SG_ sensorInfoConsistBit : 30|1@1+ (1,0) [0|1] "" Autopilot + SG_ sensorReplace : 31|1@1+ (1,0) [0|1] "" Autopilot + SG_ shortTermUnavailable : 23|1@1+ (1,0) [0|1] "" Autopilot + SG_ tunnelDetected : 28|1@1+ (1,0) [0|1] "" Autopilot + SG_ vehDynamicsError : 27|1@1+ (1,0) [0|1] "" Autopilot + SG_ verticalMisalignment : 0|8@1+ (0.00195313,-0.25) [-0.25|0.248047] "rad" Autopilot + +BO_ 1617 Radar_udsResponse: 8 Radar + SG_ Radar_udsResponseData : 7|64@0+ (1,0) [0|1.84467e+19] "" Diag + +BO_ 1601 UDS_radcRequest: 8 Diag + SG_ UDS_radcRequestData : 7|64@0+ (1,0) [0|1.84467e+19] "" Radar + +BO_ 1040 RadarPoint0_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1041 RadarPoint0_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1042 RadarPoint1_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1043 RadarPoint1_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1044 RadarPoint2_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1045 RadarPoint2_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1046 RadarPoint3_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1047 RadarPoint3_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1048 RadarPoint4_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1049 RadarPoint4_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1050 RadarPoint5_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1051 RadarPoint5_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1052 RadarPoint6_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1053 RadarPoint6_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1054 RadarPoint7_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1055 RadarPoint7_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1056 RadarPoint8_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1057 RadarPoint8_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1058 RadarPoint9_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1059 RadarPoint9_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1060 RadarPoint10_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1061 RadarPoint10_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1062 RadarPoint11_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1063 RadarPoint11_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1064 RadarPoint12_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1065 RadarPoint12_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1066 RadarPoint13_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1067 RadarPoint13_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1068 RadarPoint14_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1069 RadarPoint14_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1070 RadarPoint15_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1071 RadarPoint15_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1072 RadarPoint16_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1073 RadarPoint16_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1074 RadarPoint17_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1075 RadarPoint17_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1076 RadarPoint18_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1077 RadarPoint18_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1078 RadarPoint19_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1079 RadarPoint19_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1080 RadarPoint20_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1081 RadarPoint20_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1082 RadarPoint21_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1083 RadarPoint21_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1084 RadarPoint22_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1085 RadarPoint22_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1086 RadarPoint23_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1087 RadarPoint23_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1088 RadarPoint24_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1089 RadarPoint24_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1090 RadarPoint25_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1091 RadarPoint25_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1092 RadarPoint26_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1093 RadarPoint26_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1094 RadarPoint27_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1095 RadarPoint27_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1096 RadarPoint28_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1097 RadarPoint28_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1098 RadarPoint29_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1099 RadarPoint29_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1100 RadarPoint30_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1101 RadarPoint30_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1102 RadarPoint31_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1103 RadarPoint31_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1104 RadarPoint32_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1105 RadarPoint32_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1106 RadarPoint33_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1107 RadarPoint33_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1108 RadarPoint34_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1109 RadarPoint34_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1110 RadarPoint35_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1111 RadarPoint35_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1112 RadarPoint36_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1113 RadarPoint36_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1114 RadarPoint37_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1115 RadarPoint37_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1116 RadarPoint38_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1117 RadarPoint38_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1118 RadarPoint39_A: 8 Radar + SG_ LongDist : 0|12@1+ (0.0625,0) [0|255.9] "meters" Autopilot + SG_ LongSpeed : 12|12@1+ (0.0625,-128) [-128|128] "meters/sec" Autopilot + SG_ LatDist : 24|11@1+ (0.125,-128) [-128|128] "meters" Autopilot + SG_ ProbExist : 35|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ LongAccel : 40|10@1+ (0.03125,-16) [-16|16] "meters/sec/sec" Autopilot + SG_ ProbObstacle : 50|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Valid : 55|1@1+ (1,0) [0|1] "" Autopilot + SG_ ProbNonObstacle : 56|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Meas : 61|1@1+ (1,0) [0|1] "" Autopilot + SG_ Tracked : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index : 63|1@1+ (1,0) [0|1] "" Autopilot + +BO_ 1119 RadarPoint39_B: 8 Radar + SG_ LatSpeed : 0|10@1+ (0.125,-64) [-64|64] "meters/sec" Autopilot + SG_ Length : 10|6@1+ (0.125,0) [0|7.875] "m" Autopilot + SG_ dZ : 16|6@1+ (0.25,-5) [-5|10.75] "m" Autopilot + SG_ MovingState : 22|2@1+ (1,0) [0|3] "" Autopilot + SG_ dxSigma : 24|6@1+ (1,0) [0|63] "" Autopilot + SG_ vxSigma : 30|6@1+ (1,0) [0|63] "" Autopilot + SG_ axSigma : 36|6@1+ (1,0) [0|63] "" Autopilot + SG_ dySigma : 42|6@1+ (1,0) [0|63] "" Autopilot + SG_ ProbClass : 48|5@1+ (3.125,0) [0|96.875] "%" Autopilot + SG_ Class : 53|3@1+ (1,0) [0|7] "" Autopilot + SG_ dxRearEndLoss : 56|6@1+ (1,0) [0|63] "" Autopilot + SG_ NotUsed : 62|1@1+ (1,0) [0|1] "" Autopilot + SG_ Index2 : 63|1@1+ (1,0) [0|1] "" Autopilot + +VAL_ 1025 lowPowerMode 1 "COMMANDED_LOW_POWER" 0 "DEFAULT_LOW_POWER" 2 "NORMAL_POWER" 3 "SNA"; +VAL_ 1041 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 1041 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 1043 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 1043 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 1045 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 1045 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 1047 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 1047 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 1049 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 1049 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 1051 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 1051 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 1053 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 1053 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 1055 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 1055 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 1057 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 1057 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 1059 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 1059 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 1061 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 1061 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 1063 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 1063 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 1065 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 1065 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 1067 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 1067 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 1069 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 1069 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 1071 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 1071 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 1073 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 1073 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 1075 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 1075 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 1077 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 1077 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 1079 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 1079 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 1081 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 1081 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 1083 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 1083 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 1085 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 1085 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 1087 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 1087 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 1089 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 1089 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 1091 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 1091 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 1093 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 1093 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 1095 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 1095 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 1097 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 1097 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 1099 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 1099 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 1101 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 1101 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 1103 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 1103 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 1105 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 1105 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 1107 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 1107 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 1109 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 1109 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 1111 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 1111 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 1113 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 1113 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 1115 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 1115 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 1117 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 1117 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; +VAL_ 1119 MovingState 3 "RADAR_MOVESTATE_STANDING" 2 "RADAR_MOVESTATE_STOPPED" 1 "RADAR_MOVESTATE_MOVING" 0 "RADAR_MOVESTATE_INDETERMINATE" ; +VAL_ 1119 Class 4 "RADAR_CLASS_CONSTRUCTION_ELEMENT" 3 "RADAR_CLASS_MOVING_PEDESTRIAN" 2 "RADAR_CLASS_MOVING_TWO_WHEEL_VEHICLE" 1 "RADAR_CLASS_MOVING_FOUR_WHEEL_VEHICLE" 0 "RADAR_CLASS_UNKNOWN" ; \ No newline at end of file diff --git a/toyota_new_mc_pt_generated.dbc b/toyota_new_mc_pt_generated.dbc index e7eaba8536..230d6e1c55 100644 --- a/toyota_new_mc_pt_generated.dbc +++ b/toyota_new_mc_pt_generated.dbc @@ -1,7 +1,7 @@ CM_ "AUTOGENERATED FILE, DO NOT EDIT"; -CM_ "Imported file _comma.dbc starts here"; +CM_ "Imported file _community.dbc starts here"; BO_ 359 STEERING_IPAS_COMMA: 8 IPAS SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX @@ -28,6 +28,12 @@ BO_ 513 GAS_SENSOR: 6 INTERCEPTOR SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON +BO_ 1880 DEBUG: 8 XXX + SG_ BLINDSPOTSIDE : 7|8@0+ (1,0) [0|255] "" XXX + SG_ BLINDSPOT : 38|1@0+ (1,0) [0|15] "" XXX + SG_ BLINDSPOTD1 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ BLINDSPOTD2 : 55|8@0+ (1,0) [0|255] "" XXX + VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX @@ -37,15 +43,13 @@ CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor th BO_ 767 SDSU: 8 XXX SG_ FD_BUTTON : 7|1@0+ (1,0) [0|1] "" XXX + SG_ STATE : 23|4@0+ (1,0) [0|15] "" XXX -CM_ "BO_ SDSU: The sDSU is a modified DSU for use in TSS1 Toyotas. Learn more: https://github.com/wocsor/panda/tree/smart_dsu"; +CM_ "BO_ SDSU: The sDSU is a modified DSU for use in TSS-P Toyotas. Learn more: https://github.com/RetroPilot/ocelot/tree/main/firmware/smart_dsu"; CM_ SG_ 767 FD_BUTTON "The follow distance button signal as forwarded by the sdsu"; -BO_ 1880 DEBUG: 8 XXX - SG_ BLINDSPOTSIDE : 7|8@0+ (1,0) [0|255] "" XXX - SG_ BLINDSPOT : 38|1@0+ (1,0) [0|15] "" XXX - SG_ BLINDSPOTD1 : 47|8@0+ (1,0) [0|255] "" XXX - SG_ BLINDSPOTD2 : 55|8@0+ (1,0) [0|255] "" XXX +VAL_ 767 STATE 7 "STATE_AEB_CTRL" 6 "FAULT_INVALID" 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; + CM_ "Imported file _toyota_2017.dbc starts here"; VERSION "" @@ -207,6 +211,7 @@ BO_ 835 ACC_CONTROL: 8 DSU SG_ ACC_TYPE : 23|2@0+ (1,0) [0|3] "" HCU SG_ CANCEL_REQ : 24|1@0+ (1,0) [0|1] "" HCU SG_ ACC_CUT_IN : 25|1@0+ (1,0) [0|1] "" XXX + SG_ LEAD_VEHICLE_STOPPED : 29|1@0+ (1,0) [0|0] "" DSU SG_ PERMIT_BRAKING : 30|1@0+ (1,0) [0|1] "" HCU SG_ RELEASE_STANDSTILL : 31|1@0+ (1,0) [0|1] "" HCU SG_ ITS_CONNECT_LEAD : 39|8@0+ (1,0) [0|1] "" Vector__XXX @@ -455,6 +460,7 @@ CM_ SG_ 835 ACC_MALFUNCTION "display ACC fault on dash if set to 1"; CM_ SG_ 835 ACC_CUT_IN "Display blinking yellow lead if set to 1"; CM_ SG_ 835 DISTANCE "Cycle through ACC following distance from long, mid, short when set to 1"; CM_ SG_ 835 ITS_CONNECT_LEAD "Displayed when lead car is capable of ITS Connect"; +CM_ SG_ 835 LEAD_VEHICLE_STOPPED "Set to 1 when lead is stopped, likely only used in older TSS-P vehicles"; CM_ SG_ 835 ALLOW_LONG_PRESS "Enable Toyota's factory set speed increment behaviour, available on both metrics cars and imperial unit cars"; CM_ SG_ 835 PERMIT_BRAKING "Original ACC has this going high when a car in front is detected. In openpilot and before the PERMIT_BRAKING name, this was 'SET_ME_1' and is hardcoded to be high. Unsure if only informational or has an effect though existing usage in openpilot is to always set it to 1. Originally 'PMTBRKG' in the leaked toyota_2017_ref_pt.dbc file and name expansion speculated to be PerMiT BRaKinG."; CM_ SG_ 835 ACCEL_CMD_ALT "Copy of main ACCEL_CMD, but across 8 bits instead of 16 bits like ACCEL_CMD. Unsure if only informational or has an effect. Likely informational as existing openpilot sets this to 0 and no loss of functionality observed. Originally 'AT_RAW' in leaked toyota_2017_ref_pt.dbc file."; @@ -525,6 +531,7 @@ VAL_ 835 ACC_CUT_IN 1 "CUT-IN Detected" 0 "clear"; VAL_ 835 ALLOW_LONG_PRESS 2 "set speed increase by 5 speed units regardless" 1 "set speed increase by 1 speed unit on short press, 5 speed units on long press"; VAL_ 865 CLUTCH_RELEASED 0 "clutch pressed any amount" 1 "clutch released" VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted"; +VAL_ 921 DISTANCE_LINES 0 "not displayed" 1 "close" 2 "medium" 3 "far"; VAL_ 956 SPORT_ON 0 "off" 1 "on"; VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; VAL_ 956 SPORT_GEAR_ON 0 "off" 1 "on"; diff --git a/toyota_nodsu_pt_generated.dbc b/toyota_nodsu_pt_generated.dbc index 83a1309260..7f4d80fdb9 100644 --- a/toyota_nodsu_pt_generated.dbc +++ b/toyota_nodsu_pt_generated.dbc @@ -1,7 +1,7 @@ CM_ "AUTOGENERATED FILE, DO NOT EDIT"; -CM_ "Imported file _comma.dbc starts here"; +CM_ "Imported file _community.dbc starts here"; BO_ 359 STEERING_IPAS_COMMA: 8 IPAS SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX @@ -28,6 +28,12 @@ BO_ 513 GAS_SENSOR: 6 INTERCEPTOR SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON +BO_ 1880 DEBUG: 8 XXX + SG_ BLINDSPOTSIDE : 7|8@0+ (1,0) [0|255] "" XXX + SG_ BLINDSPOT : 38|1@0+ (1,0) [0|15] "" XXX + SG_ BLINDSPOTD1 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ BLINDSPOTD2 : 55|8@0+ (1,0) [0|255] "" XXX + VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX @@ -37,15 +43,12 @@ CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor th BO_ 767 SDSU: 8 XXX SG_ FD_BUTTON : 7|1@0+ (1,0) [0|1] "" XXX + SG_ STATE : 23|4@0+ (1,0) [0|15] "" XXX -CM_ "BO_ SDSU: The sDSU is a modified DSU for use in TSS1 Toyotas. Learn more: https://github.com/wocsor/panda/tree/smart_dsu"; +CM_ "BO_ SDSU: The sDSU is a modified DSU for use in TSS-P Toyotas. Learn more: https://github.com/RetroPilot/ocelot/tree/main/firmware/smart_dsu"; CM_ SG_ 767 FD_BUTTON "The follow distance button signal as forwarded by the sdsu"; -BO_ 1880 DEBUG: 8 XXX - SG_ BLINDSPOTSIDE : 7|8@0+ (1,0) [0|255] "" XXX - SG_ BLINDSPOT : 38|1@0+ (1,0) [0|15] "" XXX - SG_ BLINDSPOTD1 : 47|8@0+ (1,0) [0|255] "" XXX - SG_ BLINDSPOTD2 : 55|8@0+ (1,0) [0|255] "" XXX +VAL_ 767 STATE 7 "STATE_AEB_CTRL" 6 "FAULT_INVALID" 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; CM_ "Imported file _toyota_2017.dbc starts here"; @@ -208,6 +211,7 @@ BO_ 835 ACC_CONTROL: 8 DSU SG_ ACC_TYPE : 23|2@0+ (1,0) [0|3] "" HCU SG_ CANCEL_REQ : 24|1@0+ (1,0) [0|1] "" HCU SG_ ACC_CUT_IN : 25|1@0+ (1,0) [0|1] "" XXX + SG_ LEAD_VEHICLE_STOPPED : 29|1@0+ (1,0) [0|0] "" DSU SG_ PERMIT_BRAKING : 30|1@0+ (1,0) [0|1] "" HCU SG_ RELEASE_STANDSTILL : 31|1@0+ (1,0) [0|1] "" HCU SG_ ITS_CONNECT_LEAD : 39|8@0+ (1,0) [0|1] "" Vector__XXX @@ -457,6 +461,7 @@ CM_ SG_ 835 ACC_MALFUNCTION "display ACC fault on dash if set to 1"; CM_ SG_ 835 ACC_CUT_IN "Display blinking yellow lead if set to 1"; CM_ SG_ 835 DISTANCE "Cycle through ACC following distance from long, mid, short when set to 1"; CM_ SG_ 835 ITS_CONNECT_LEAD "Displayed when lead car is capable of ITS Connect"; +CM_ SG_ 835 LEAD_VEHICLE_STOPPED "Set to 1 when lead is stopped, likely only used in older TSS-P vehicles"; CM_ SG_ 835 ALLOW_LONG_PRESS "Enable Toyota's factory set speed increment behaviour, available on both metrics cars and imperial unit cars"; CM_ SG_ 835 PERMIT_BRAKING "Original ACC has this going high when a car in front is detected. In openpilot and before the PERMIT_BRAKING name, this was 'SET_ME_1' and is hardcoded to be high. Unsure if only informational or has an effect though existing usage in openpilot is to always set it to 1. Originally 'PMTBRKG' in the leaked toyota_2017_ref_pt.dbc file and name expansion speculated to be PerMiT BRaKinG."; CM_ SG_ 835 ACCEL_CMD_ALT "Copy of main ACCEL_CMD, but across 8 bits instead of 16 bits like ACCEL_CMD. Unsure if only informational or has an effect. Likely informational as existing openpilot sets this to 0 and no loss of functionality observed. Originally 'AT_RAW' in leaked toyota_2017_ref_pt.dbc file."; @@ -527,6 +532,7 @@ VAL_ 835 ACC_CUT_IN 1 "CUT-IN Detected" 0 "clear"; VAL_ 835 ALLOW_LONG_PRESS 2 "set speed increase by 5 speed units regardless" 1 "set speed increase by 1 speed unit on short press, 5 speed units on long press"; VAL_ 865 CLUTCH_RELEASED 0 "clutch pressed any amount" 1 "clutch released" VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted"; +VAL_ 921 DISTANCE_LINES 0 "not displayed" 1 "close" 2 "medium" 3 "far"; VAL_ 956 SPORT_ON 0 "off" 1 "on"; VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; VAL_ 956 SPORT_GEAR_ON 0 "off" 1 "on"; diff --git a/toyota_tnga_k_pt_generated.dbc b/toyota_tnga_k_pt_generated.dbc index fb4815bbf1..8903af7109 100644 --- a/toyota_tnga_k_pt_generated.dbc +++ b/toyota_tnga_k_pt_generated.dbc @@ -1,7 +1,7 @@ CM_ "AUTOGENERATED FILE, DO NOT EDIT"; -CM_ "Imported file _comma.dbc starts here"; +CM_ "Imported file _community.dbc starts here"; BO_ 359 STEERING_IPAS_COMMA: 8 IPAS SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX @@ -28,6 +28,12 @@ BO_ 513 GAS_SENSOR: 6 INTERCEPTOR SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON +BO_ 1880 DEBUG: 8 XXX + SG_ BLINDSPOTSIDE : 7|8@0+ (1,0) [0|255] "" XXX + SG_ BLINDSPOT : 38|1@0+ (1,0) [0|15] "" XXX + SG_ BLINDSPOTD1 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ BLINDSPOTD2 : 55|8@0+ (1,0) [0|255] "" XXX + VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX @@ -37,15 +43,13 @@ CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor th BO_ 767 SDSU: 8 XXX SG_ FD_BUTTON : 7|1@0+ (1,0) [0|1] "" XXX + SG_ STATE : 23|4@0+ (1,0) [0|15] "" XXX -CM_ "BO_ SDSU: The sDSU is a modified DSU for use in TSS1 Toyotas. Learn more: https://github.com/wocsor/panda/tree/smart_dsu"; +CM_ "BO_ SDSU: The sDSU is a modified DSU for use in TSS-P Toyotas. Learn more: https://github.com/RetroPilot/ocelot/tree/main/firmware/smart_dsu"; CM_ SG_ 767 FD_BUTTON "The follow distance button signal as forwarded by the sdsu"; -BO_ 1880 DEBUG: 8 XXX - SG_ BLINDSPOTSIDE : 7|8@0+ (1,0) [0|255] "" XXX - SG_ BLINDSPOT : 38|1@0+ (1,0) [0|15] "" XXX - SG_ BLINDSPOTD1 : 47|8@0+ (1,0) [0|255] "" XXX - SG_ BLINDSPOTD2 : 55|8@0+ (1,0) [0|255] "" XXX +VAL_ 767 STATE 7 "STATE_AEB_CTRL" 6 "FAULT_INVALID" 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; + CM_ "Imported file _toyota_2017.dbc starts here"; VERSION "" @@ -207,6 +211,7 @@ BO_ 835 ACC_CONTROL: 8 DSU SG_ ACC_TYPE : 23|2@0+ (1,0) [0|3] "" HCU SG_ CANCEL_REQ : 24|1@0+ (1,0) [0|1] "" HCU SG_ ACC_CUT_IN : 25|1@0+ (1,0) [0|1] "" XXX + SG_ LEAD_VEHICLE_STOPPED : 29|1@0+ (1,0) [0|0] "" DSU SG_ PERMIT_BRAKING : 30|1@0+ (1,0) [0|1] "" HCU SG_ RELEASE_STANDSTILL : 31|1@0+ (1,0) [0|1] "" HCU SG_ ITS_CONNECT_LEAD : 39|8@0+ (1,0) [0|1] "" Vector__XXX @@ -455,6 +460,7 @@ CM_ SG_ 835 ACC_MALFUNCTION "display ACC fault on dash if set to 1"; CM_ SG_ 835 ACC_CUT_IN "Display blinking yellow lead if set to 1"; CM_ SG_ 835 DISTANCE "Cycle through ACC following distance from long, mid, short when set to 1"; CM_ SG_ 835 ITS_CONNECT_LEAD "Displayed when lead car is capable of ITS Connect"; +CM_ SG_ 835 LEAD_VEHICLE_STOPPED "Set to 1 when lead is stopped, likely only used in older TSS-P vehicles"; CM_ SG_ 835 ALLOW_LONG_PRESS "Enable Toyota's factory set speed increment behaviour, available on both metrics cars and imperial unit cars"; CM_ SG_ 835 PERMIT_BRAKING "Original ACC has this going high when a car in front is detected. In openpilot and before the PERMIT_BRAKING name, this was 'SET_ME_1' and is hardcoded to be high. Unsure if only informational or has an effect though existing usage in openpilot is to always set it to 1. Originally 'PMTBRKG' in the leaked toyota_2017_ref_pt.dbc file and name expansion speculated to be PerMiT BRaKinG."; CM_ SG_ 835 ACCEL_CMD_ALT "Copy of main ACCEL_CMD, but across 8 bits instead of 16 bits like ACCEL_CMD. Unsure if only informational or has an effect. Likely informational as existing openpilot sets this to 0 and no loss of functionality observed. Originally 'AT_RAW' in leaked toyota_2017_ref_pt.dbc file."; @@ -525,6 +531,7 @@ VAL_ 835 ACC_CUT_IN 1 "CUT-IN Detected" 0 "clear"; VAL_ 835 ALLOW_LONG_PRESS 2 "set speed increase by 5 speed units regardless" 1 "set speed increase by 1 speed unit on short press, 5 speed units on long press"; VAL_ 865 CLUTCH_RELEASED 0 "clutch pressed any amount" 1 "clutch released" VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted"; +VAL_ 921 DISTANCE_LINES 0 "not displayed" 1 "close" 2 "medium" 3 "far"; VAL_ 956 SPORT_ON 0 "off" 1 "on"; VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; VAL_ 956 SPORT_GEAR_ON 0 "off" 1 "on"; diff --git a/vw_golf_mk4.dbc b/vw_golf_mk4.dbc index 131a4b763c..6f14789135 100644 --- a/vw_golf_mk4.dbc +++ b/vw_golf_mk4.dbc @@ -1518,8 +1518,15 @@ 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_ SG_ 1056 Fehlerstatus_Aussentemp__4_1 "ambient temp error"; CM_ SG_ 1056 Fehlerstatus_Oeltemperatur_4_1 "oil temp error"; diff --git a/vw_mqb_2010.dbc b/vw_mqb_2010.dbc index 8806e0011a..830dc6f4ae 100644 --- a/vw_mqb_2010.dbc +++ b/vw_mqb_2010.dbc @@ -91,6 +91,7 @@ BO_ 679 ACC_13: 8 XXX SG_ ACC_Tachokranz : 58|1@1+ (1,0) [0|1] "" XXX SG_ ACC_Typ_Tachokranz_unten : 59|1@1+ (1,0) [0|1] "" XXX SG_ ACC_ENG_Texte : 60|2@1+ (1,0) [0|3] "" XXX + SG_ ACC_ADAPTIVE : 63|2@0+ (1,0) [0|3] "" XXX BO_ 681 ACC_15: 8 XXX SG_ AWV_Warnung : 16|3@1+ (1,0) [0|7] "" XXX @@ -1459,6 +1460,7 @@ CM_ SG_ 780 SetAbstand "Set following distance"; CM_ SG_ 780 Abstand "Following distance"; CM_ SG_ 780 SetSpeed "ACC set speed"; CM_ SG_ 391 GearPosition "Traditional PRND plus B-mode aggressive regen, B-mode mapped to Drive"; +CM_ SG_ 679 ACC_ADAPTIVE "TSK_06.TSK_Limiter_ausgewaehlt seems to take precedence"; CM_ SG_ 960 ZAS_Kl_15 "Indicates ignition on"; CM_ SG_ 1720 KBI_BCmE_aktiv "Anzeige BCmE aktiv (BCmE-Screen oder Einsparhinweis in der Anzeige)"; CM_ SG_ 1720 KBI_Max_Tankinhalt "Mitteilung des maximalen Tankinhalts an das Reichweitenmodul"; @@ -1559,6 +1561,7 @@ VAL_ 679 ACC_RUV 0 "keine_Anzeige" 1 "RUV_aktiv_Rechtsverkehr" 2 "RUV_aktiv_Link VAL_ 679 ACC_Tachokranz 0 "Tachokranz_nicht_beleuchtet" 1 "Tachokranz_beleuchtet" ; VAL_ 679 ACC_Typ_Tachokranz_unten 0 "LEDs_an" 1 "LEDs_aus" ; VAL_ 679 ACC_ENG_Texte 0 "keine_Anzeige" 1 "keine_Laenderverfuegbarkeit" 2 "nicht_verfuegbar" 3 "Geschwindigkeitsgrenze" ; +VAL_ 679 ACC_ADAPTIVE 1 "adaptive" 2 "non-adaptive" ; VAL_ 681 AWV_Warnung 0 "keine_Anzeige" 1 "latente_Vorwarnung" 2 "Vorwarnung" 3 "Akutwarnung" 4 "Eingriff" 5 "Fahreruebernahmeaufforderung" 6 "Abbiegewarnung" ; VAL_ 681 AWV_Texte 0 "keine_Anzeige" 1 "Systemstoerung" 2 "keine_Sensorsicht" 3 "Demomodus" 4 "System_aus" 5 "nicht_definiert" 6 "ESC_aus" 7 "zurzeit_eingeschraenkt" ; VAL_ 681 AWV_Status_Anzeige 0 "Init" 1 "verfuegbar" 2 "nicht_verfuegbar" ;