diff --git a/docs/CARS.md b/docs/CARS.md index d6acb9b640..1322bf9499 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -1,6 +1,6 @@ -# Support Information for 341 Known Cars +# Support Information for 343 Known Cars |Make|Model|Package|Support Level| |---|---|---|:---:| @@ -72,6 +72,7 @@ |Honda|Civic 2022-24|All|[Upstream](#upstream)| |Honda|Civic Hatchback 2017-21|Honda Sensing|[Upstream](#upstream)| |Honda|Civic Hatchback 2022-24|All|[Upstream](#upstream)| +|Honda|Clarity 2018-21|All|[Community](#community)| |Honda|CR-V 2015-16|Touring Trim|[Upstream](#upstream)| |Honda|CR-V 2017-22|Honda Sensing|[Upstream](#upstream)| |Honda|CR-V 2024|All|[Community](#community)| @@ -85,6 +86,7 @@ |Honda|Insight 2019-22|All|[Upstream](#upstream)| |Honda|Inspire 2018|All|[Upstream](#upstream)| |Honda|Odyssey 2018-20|Honda Sensing|[Upstream](#upstream)| +|Honda|Odyssey 2021-25|All|[Community](#community)| |Honda|Passport 2019-23|All|[Upstream](#upstream)| |Honda|Pilot 2016-22|Honda Sensing|[Upstream](#upstream)| |Honda|Pilot 2023-24|All|[Community](#community)| @@ -383,17 +385,21 @@ Although they're not upstream, the community has openpilot running on other make Supported Models' section of each make [on our wiki](https://wiki.comma.ai/). Some notable works-in-progress: -* Honda CAN-FD vehicles +* Honda * 2024 Acura Integra, commaai/openpilot#32056 - * 2023-24 Honda Accord, commaai/openpilot#32229 - * 2024 Honda CR-V, commaai/openpilot#32806 - * 2024 Honda CR-V Hybrid, commaai/openpilot#31527, which depends on: - * commaai/opendbc#1100 - * 2023-24 Honda Pilot, commaai/openpilot#30324 -* Honda camera ACC stability improvements - * commaai/openpilot#31022, which depends on: - * commaai/panda#1814 - * commaai/opendbc#998 + * 2023-24 Honda Accord (CAN-FD), commaai/openpilot#32229 + * 2024 Honda CR-V (CAN-FD), commaai/openpilot#32806 + * 2024 Honda CR-V Hybrid (CAN-FD), commaai/openpilot#31527 + * Depends on commaai/opendbc#1100 + * 2021-25 Honda Odyssey, commaai/opendbc#1330 + * 2023-24 Honda Pilot (CAN-FD), commaai/openpilot#30324 + * Camera ACC stability improvements, commaai/openpilot#31022 + * Depends on commaai/panda#1814 + * Depends on commaai/opendbc#998 + * These are being reworked for full-time proxy through openpilot + * Manual transmission support (Civic, Integra) + * Depends on commaai/opendbc#1034 (merged) + * Car port support PR not yet filed ## Incompatible diff --git a/opendbc/car/CARS_template.md b/opendbc/car/CARS_template.md index a02ffe15d1..d13f3a4b76 100644 --- a/opendbc/car/CARS_template.md +++ b/opendbc/car/CARS_template.md @@ -46,17 +46,21 @@ Although they're not upstream, the community has openpilot running on other make Supported Models' section of each make [on our wiki](https://wiki.comma.ai/). Some notable works-in-progress: -* Honda CAN-FD vehicles +* Honda * 2024 Acura Integra, commaai/openpilot#32056 - * 2023-24 Honda Accord, commaai/openpilot#32229 - * 2024 Honda CR-V, commaai/openpilot#32806 - * 2024 Honda CR-V Hybrid, commaai/openpilot#31527, which depends on: - * commaai/opendbc#1100 - * 2023-24 Honda Pilot, commaai/openpilot#30324 -* Honda camera ACC stability improvements - * commaai/openpilot#31022, which depends on: - * commaai/panda#1814 - * commaai/opendbc#998 + * 2023-24 Honda Accord (CAN-FD), commaai/openpilot#32229 + * 2024 Honda CR-V (CAN-FD), commaai/openpilot#32806 + * 2024 Honda CR-V Hybrid (CAN-FD), commaai/openpilot#31527 + * Depends on commaai/opendbc#1100 + * 2021-25 Honda Odyssey, commaai/opendbc#1330 + * 2023-24 Honda Pilot (CAN-FD), commaai/openpilot#30324 + * Camera ACC stability improvements, commaai/openpilot#31022 + * Depends on commaai/panda#1814 + * Depends on commaai/opendbc#998 + * These are being reworked for full-time proxy through openpilot + * Manual transmission support (Civic, Integra) + * Depends on commaai/opendbc#1034 (merged) + * Car port support PR not yet filed ## Incompatible diff --git a/opendbc/car/__init__.py b/opendbc/car/__init__.py index 32f53fcdee..5b24daad3a 100644 --- a/opendbc/car/__init__.py +++ b/opendbc/car/__init__.py @@ -21,6 +21,8 @@ # kg of standard extra cargo to count for drive, gas, etc... STD_CARGO_KG = 136. +ACCELERATION_DUE_TO_GRAVITY = 9.81 # m/s^2 + ButtonType = structs.CarState.ButtonEvent.Type AngleRateLimit = namedtuple('AngleRateLimit', ['speed_bp', 'angle_v']) diff --git a/opendbc/car/body/carcontroller.py b/opendbc/car/body/carcontroller.py index 1d0bedb632..020db5d5cf 100644 --- a/opendbc/car/body/carcontroller.py +++ b/opendbc/car/body/carcontroller.py @@ -1,70 +1,12 @@ import numpy as np -from numbers import Number from opendbc.can.packer import CANPacker from opendbc.car import DT_CTRL -from opendbc.car.common.numpy_fast import clip, interp +from opendbc.car.common.pid import PIDController from opendbc.car.body import bodycan from opendbc.car.body.values import SPEED_FROM_RPM from opendbc.car.interfaces import CarControllerBase - -class PIController: - def __init__(self, k_p, k_i, pos_limit=1e308, neg_limit=-1e308, rate=100): - self._k_p = k_p - self._k_i = k_i - if isinstance(self._k_p, Number): - self._k_p = [[0], [self._k_p]] - if isinstance(self._k_i, Number): - self._k_i = [[0], [self._k_i]] - - self.pos_limit = pos_limit - self.neg_limit = neg_limit - - self.i_unwind_rate = 0.3 / rate - self.i_rate = 1.0 / rate - self.speed = 0.0 - - self.reset() - - @property - def k_p(self): - return interp(self.speed, self._k_p[0], self._k_p[1]) - - @property - def k_i(self): - return interp(self.speed, self._k_i[0], self._k_i[1]) - - @property - def error_integral(self): - return self.i/self.k_i - - def reset(self): - self.p = 0.0 - self.i = 0.0 - self.control = 0 - - def update(self, error, speed=0.0, freeze_integrator=False): - self.speed = speed - - self.p = float(error) * self.k_p - - i = self.i + error * self.k_i * self.i_rate - control = self.p + i - - # Update when changing i will move the control away from the limits - # or when i will move towards the sign of the error - if ((error >= 0 and (control <= self.pos_limit or i < 0.0)) or - (error <= 0 and (control >= self.neg_limit or i > 0.0))) and \ - not freeze_integrator: - self.i = i - - control = self.p + self.i - - self.control = clip(control, self.neg_limit, self.pos_limit) - return self.control - - MAX_TORQUE = 500 MAX_TORQUE_RATE = 50 MAX_ANGLE_ERROR = np.radians(7) @@ -78,8 +20,8 @@ def __init__(self, dbc_name, CP): self.packer = CANPacker(dbc_name) # PIDs - self.turn_pid = PIController(110, k_i=11.5, rate=1/DT_CTRL) - self.wheeled_speed_pid = PIController(110, k_i=11.5, rate=1/DT_CTRL) + self.turn_pid = PIDController(110, k_i=11.5, rate=1/DT_CTRL) + self.wheeled_speed_pid = PIDController(110, k_i=11.5, rate=1/DT_CTRL) self.torque_r_filtered = 0. self.torque_l_filtered = 0. diff --git a/opendbc/car/car.capnp b/opendbc/car/car.capnp index 49f82b6dd3..237ba2c26b 100644 --- a/opendbc/car/car.capnp +++ b/opendbc/car/car.capnp @@ -278,7 +278,7 @@ struct CarState { accelCruise @3; decelCruise @4; cancel @5; - altButton1 @6; + lkas @6; altButton2 @7; mainCruise @8; setCruise @9; @@ -508,7 +508,6 @@ struct CarParams { transmissionType @43 :TransmissionType; carFw @44 :List(CarFw); - radarTimeStep @45: Float32 = 0.05; # time delta between radar updates, 20Hz is very standard radarDelay @74 :Float32; fingerprintSource @49: FingerprintSource; networkLocation @50 :NetworkLocation; # Where Panda/C2 is integrated into the car's CAN network @@ -719,4 +718,5 @@ struct CarParams { maxSteeringAngleDegDEPRECATED @54 :Float32; longitudinalActuatorDelayLowerBoundDEPRECATED @61 :Float32; stoppingControlDEPRECATED @31 :Bool; # Does the car allow full control even at lows speeds when stopping + radarTimeStepDEPRECATED @45: Float32 = 0.05; # time delta between radar updates, 20Hz is very standard } diff --git a/opendbc/car/chrysler/fingerprints.py b/opendbc/car/chrysler/fingerprints.py index 072eafb1d0..ba597d70ec 100644 --- a/opendbc/car/chrysler/fingerprints.py +++ b/opendbc/car/chrysler/fingerprints.py @@ -325,6 +325,7 @@ b'68402703AB', b'68402704AB', b'68402708AB', + b'68402714AB', b'68402971AD', b'68454144AD', b'68454145AB', @@ -362,6 +363,7 @@ ], (Ecu.engine, 0x7e0, None): [ b'05035674AB ', + b'68412635AE ', b'68412635AG ', b'68412660AD ', b'68422860AB', @@ -468,6 +470,7 @@ b'68535470AC', b'68548900AB', b'68586307AB', + b'68586307AC', ], (Ecu.fwdRadar, 0x753, None): [ b'04672892AB', @@ -545,6 +548,7 @@ b'68378710AL ', b'68378742AI ', b'68378742AK ', + b'68378743AI ', b'68378743AM ', b'68378748AL ', b'68378758AM ', @@ -559,6 +563,7 @@ b'68455145AE ', b'68455146AC ', b'68460927AA ', + b'68467909AB ', b'68467915AC ', b'68467916AC ', b'68467936AC ', @@ -598,6 +603,7 @@ b'68360081AM', b'68360085AJ', b'68360085AL', + b'68360085AO', b'68360086AH', b'68360086AK', b'68360086AN', @@ -608,6 +614,7 @@ b'68445536AB', b'68445537AB', b'68466081AB', + b'68466086AB', b'68466087AB', b'68484466AC', b'68484467AC', diff --git a/opendbc/car/common/pid.py b/opendbc/car/common/pid.py new file mode 100644 index 0000000000..7a376c86c3 --- /dev/null +++ b/opendbc/car/common/pid.py @@ -0,0 +1,58 @@ +from numbers import Number +from opendbc.car.common.numpy_fast import clip, interp + + +class PIDController: + def __init__(self, k_p, k_i, pos_limit=1e308, neg_limit=-1e308, rate=100): + self._k_p = k_p + self._k_i = k_i + if isinstance(self._k_p, Number): + self._k_p = [[0], [self._k_p]] + if isinstance(self._k_i, Number): + self._k_i = [[0], [self._k_i]] + + self.pos_limit = pos_limit + self.neg_limit = neg_limit + + self.i_unwind_rate = 0.3 / rate + self.i_rate = 1.0 / rate + self.speed = 0.0 + + self.reset() + + @property + def k_p(self): + return interp(self.speed, self._k_p[0], self._k_p[1]) + + @property + def k_i(self): + return interp(self.speed, self._k_i[0], self._k_i[1]) + + @property + def error_integral(self): + return self.i/self.k_i + + def reset(self): + self.p = 0.0 + self.i = 0.0 + self.control = 0 + + def update(self, error, speed=0.0, freeze_integrator=False): + self.speed = speed + + self.p = float(error) * self.k_p + + i = self.i + error * self.k_i * self.i_rate + control = self.p + i + + # Update when changing i will move the control away from the limits + # or when i will move towards the sign of the error + if ((error >= 0 and (control <= self.pos_limit or i < 0.0)) or + (error <= 0 and (control >= self.neg_limit or i > 0.0))) and \ + not freeze_integrator: + self.i = i + + control = self.p + self.i + + self.control = clip(control, self.neg_limit, self.pos_limit) + return self.control diff --git a/opendbc/car/extra_cars.py b/opendbc/car/extra_cars.py index 284c5f59cf..87e1f13819 100644 --- a/opendbc/car/extra_cars.py +++ b/opendbc/car/extra_cars.py @@ -28,24 +28,26 @@ def init_make(self, CP: structs.CarParams): class CAR(Platforms): config: ExtraPlatformConfig - HONDA_CANFD = ExtraPlatformConfig( + EXTRA_HONDA = ExtraPlatformConfig( [ CommunityCarDocs("Acura Integra 2024", "All"), CommunityCarDocs("Honda Accord 2023-24", "All"), + CommunityCarDocs("Honda Clarity 2018-21", "All"), CommunityCarDocs("Honda CR-V 2024", "All"), CommunityCarDocs("Honda CR-V Hybrid 2024", "All"), + CommunityCarDocs("Honda Odyssey 2021-25", "All"), CommunityCarDocs("Honda Pilot 2023-24", "All"), ], ) - HYUNDAI_PALISADE_FACELIFT = ExtraPlatformConfig( + EXTRA_HYUNDAI = ExtraPlatformConfig( [ CommunityCarDocs("Hyundai Palisade 2023-24", package="HDA2"), CommunityCarDocs("Kia Telluride 2023-24", package="HDA2"), ], ) - TOYOTA_SECURITY_CARS = ExtraPlatformConfig( + EXTRA_TOYOTA = ExtraPlatformConfig( [ ToyotaSecurityCarDocs("Subaru Solterra 2023-25"), ToyotaSecurityCarDocs("Lexus NS 2022-25"), @@ -63,7 +65,7 @@ class CAR(Platforms): ], ) - AUDI_FLEXRAY = ExtraPlatformConfig( + EXTRA_VOLKSWAGEN = ExtraPlatformConfig( [ FlexRayCarDocs("Audi A4 2016-24", package="All"), FlexRayCarDocs("Audi A5 2016-24", package="All"), diff --git a/opendbc/car/ford/carcontroller.py b/opendbc/car/ford/carcontroller.py index 7834a10149..748027073f 100644 --- a/opendbc/car/ford/carcontroller.py +++ b/opendbc/car/ford/carcontroller.py @@ -1,8 +1,9 @@ +import math from opendbc.can.packer import CANPacker -from opendbc.car import apply_std_steer_angle_limits, structs +from opendbc.car import ACCELERATION_DUE_TO_GRAVITY, DT_CTRL, apply_std_steer_angle_limits, structs from opendbc.car.ford import fordcan from opendbc.car.ford.values import CarControllerParams, FordFlags -from opendbc.car.common.numpy_fast import clip +from opendbc.car.common.numpy_fast import clip, interp from opendbc.car.interfaces import CarControllerBase, V_CRUISE_MAX LongCtrlState = structs.CarControl.Actuators.LongControlState @@ -21,6 +22,13 @@ def apply_ford_curvature_limits(apply_curvature, apply_curvature_last, current_c return clip(apply_curvature, -CarControllerParams.CURVATURE_MAX, CarControllerParams.CURVATURE_MAX) +def apply_creep_compensation(accel: float, v_ego: float) -> float: + creep_accel = interp(v_ego, [1., 3.], [0.6, 0.]) + if accel < 0.: + accel -= creep_accel + return accel + + class CarController(CarControllerBase): def __init__(self, dbc_name, CP): super().__init__(dbc_name, CP) @@ -28,10 +36,14 @@ def __init__(self, dbc_name, CP): self.CAN = fordcan.CanBus(CP) self.apply_curvature_last = 0 + self.accel = 0.0 + self.gas = 0.0 + self.brake_request = False self.main_on_last = False self.lkas_enabled_last = False self.steer_alert_last = False self.lead_distance_bars_last = None + self.distance_bar_frame = 0 def update(self, CC, CS, now_nanos): can_sends = [] @@ -69,6 +81,11 @@ def update(self, CC, CS, now_nanos): if self.CP.flags & FordFlags.CANFD: # TODO: extended mode + # Ford uses four individual signals to dictate how to drive to the car. Curvature alone (limited to 0.02m/s^2) + # can actuate the steering for a large portion of any lateral movements. However, in order to get further control on + # steer actuation, the other three signals are necessary. Ford controls vehicles differently than most other makes. + # A detailed explanation on ford control can be found here: + # https://www.f150gen14.com/forum/threads/introducing-bluepilot-a-ford-specific-fork-for-comma3x-openpilot.24241/#post-457706 mode = 1 if CC.latActive else 0 counter = (self.frame // CarControllerParams.STEER_STEP) % 0x10 can_sends.append(fordcan.create_lat_ctl2_msg(self.packer, self.CAN, mode, 0., 0., -apply_curvature, 0., counter)) @@ -82,14 +99,42 @@ def update(self, CC, CS, now_nanos): ### longitudinal control ### # send acc msg at 50Hz if self.CP.openpilotLongitudinalControl and (self.frame % CarControllerParams.ACC_CONTROL_STEP) == 0: - # Both gas and accel are in m/s^2, accel is used solely for braking - accel = clip(actuators.accel, CarControllerParams.ACCEL_MIN, CarControllerParams.ACCEL_MAX) + accel = actuators.accel gas = accel + + if CC.longActive: + # Compensate for engine creep at low speed. + # Either the ABS does not account for engine creep, or the correction is very slow + # TODO: verify this applies to EV/hybrid + accel = apply_creep_compensation(accel, CS.out.vEgo) + + # The stock system has been seen rate limiting the brake accel to 5 m/s^3, + # however even 3.5 m/s^3 causes some overshoot with a step response. + accel = max(accel, self.accel - (3.5 * CarControllerParams.ACC_CONTROL_STEP * DT_CTRL)) + + accel = clip(accel, CarControllerParams.ACCEL_MIN, CarControllerParams.ACCEL_MAX) + + # Both gas and accel are in m/s^2, accel is used solely for braking if not CC.longActive or gas < CarControllerParams.MIN_GAS: gas = CarControllerParams.INACTIVE_GAS + + # PCM applies pitch compensation to gas/accel, but we need to compensate for the brake/pre-charge bits + accel_due_to_pitch = 0.0 + if len(CC.orientationNED) == 3: + accel_due_to_pitch = math.sin(CC.orientationNED[1]) * ACCELERATION_DUE_TO_GRAVITY + + accel_pitch_compensated = accel + accel_due_to_pitch + if accel_pitch_compensated > 0.3 or not CC.longActive: + self.brake_request = False + elif accel_pitch_compensated < 0.0: + self.brake_request = True + stopping = CC.actuators.longControlState == LongCtrlState.stopping # TODO: look into using the actuators packet to send the desired speed - can_sends.append(fordcan.create_acc_msg(self.packer, self.CAN, CC.longActive, gas, accel, stopping, v_ego_kph=V_CRUISE_MAX)) + can_sends.append(fordcan.create_acc_msg(self.packer, self.CAN, CC.longActive, gas, accel, stopping, self.brake_request, v_ego_kph=V_CRUISE_MAX)) + + self.accel = accel + self.gas = gas ### ui ### send_ui = (self.main_on_last != main_on) or (self.lkas_enabled_last != CC.latActive) or (self.steer_alert_last != steer_alert) @@ -100,10 +145,13 @@ def update(self, CC, CS, now_nanos): # send acc ui msg at 5Hz or if ui state changes if hud_control.leadDistanceBars != self.lead_distance_bars_last: send_ui = True + self.distance_bar_frame = self.frame + if (self.frame % CarControllerParams.ACC_UI_STEP) == 0 or send_ui: + show_distance_bars = self.frame - self.distance_bar_frame < 400 can_sends.append(fordcan.create_acc_ui_msg(self.packer, self.CAN, self.CP, main_on, CC.latActive, - fcw_alert, CS.out.cruiseState.standstill, hud_control, - CS.acc_tja_status_stock_values)) + fcw_alert, CS.out.cruiseState.standstill, show_distance_bars, + hud_control, CS.acc_tja_status_stock_values)) self.main_on_last = main_on self.lkas_enabled_last = CC.latActive @@ -112,6 +160,8 @@ def update(self, CC, CS, now_nanos): new_actuators = actuators.as_builder() new_actuators.curvature = self.apply_curvature_last + new_actuators.accel = self.accel + new_actuators.gas = self.gas self.frame += 1 return new_actuators, can_sends diff --git a/opendbc/car/ford/carstate.py b/opendbc/car/ford/carstate.py index 8b631e8dee..832d4b7321 100644 --- a/opendbc/car/ford/carstate.py +++ b/opendbc/car/ford/carstate.py @@ -76,6 +76,8 @@ def update(self, cp, cp_cam, *_) -> structs.CarState: else: ret.gearShifter = GearShifter.drive + ret.engineRpm = cp.vl["EngVehicleSpThrottle"]["EngAout_N_Actl"] + # safety ret.stockFcw = bool(cp_cam.vl["ACCDATA_3"]["FcwVisblWarn_B_Rq"]) ret.stockAeb = bool(cp_cam.vl["ACCDATA_2"]["CmbbBrkDecel_B_Rq"]) diff --git a/opendbc/car/ford/fordcan.py b/opendbc/car/ford/fordcan.py index 61263099c7..2ac68c4427 100644 --- a/opendbc/car/ford/fordcan.py +++ b/opendbc/car/ford/fordcan.py @@ -117,7 +117,7 @@ def create_lat_ctl2_msg(packer, CAN: CanBus, mode: int, path_offset: float, path return packer.make_can_msg("LateralMotionControl2", CAN.main, values) -def create_acc_msg(packer, CAN: CanBus, long_active: bool, gas: float, accel: float, stopping: bool, v_ego_kph: float): +def create_acc_msg(packer, CAN: CanBus, long_active: bool, gas: float, accel: float, stopping: bool, brake_request, v_ego_kph: float): """ Creates a CAN message for the Ford ACC Command. @@ -126,24 +126,27 @@ def create_acc_msg(packer, CAN: CanBus, long_active: bool, gas: float, accel: fl Frequency is 50Hz. """ - decel = accel < 0 and long_active values = { "AccBrkTot_A_Rq": accel, # Brake total accel request: [-20|11.9449] m/s^2 "Cmbb_B_Enbl": 1 if long_active else 0, # Enabled: 0=No, 1=Yes "AccPrpl_A_Rq": gas, # Acceleration request: [-5|5.23] m/s^2 + # No observed acceleration seen from this signal alone. During stock system operation, it appears to + # be the raw acceleration request (AccPrpl_A_Rq when positive, AccBrkTot_A_Rq when negative) "AccPrpl_A_Pred": -5.0, # Acceleration request: [-5|5.23] m/s^2 "AccResumEnbl_B_Rq": 1 if long_active else 0, + # No observed acceleration seen from this signal alone "AccVeh_V_Trg": v_ego_kph, # Target speed: [0|255] km/h # TODO: we may be able to improve braking response by utilizing pre-charging better - "AccBrkPrchg_B_Rq": 1 if decel else 0, # Pre-charge brake request: 0=No, 1=Yes - "AccBrkDecel_B_Rq": 1 if decel else 0, # Deceleration request: 0=Inactive, 1=Active + # When setting these two bits without AccBrkTot_A_Rq, an initial jerk is observed and car may be able to brake temporarily with AccPrpl_A_Rq + "AccBrkPrchg_B_Rq": 1 if brake_request else 0, # Pre-charge brake request: 0=No, 1=Yes + "AccBrkDecel_B_Rq": 1 if brake_request else 0, # Deceleration request: 0=Inactive, 1=Active "AccStopStat_B_Rq": 1 if stopping else 0, } return packer.make_can_msg("ACCDATA", CAN.main, values) def create_acc_ui_msg(packer, CAN: CanBus, CP, main_on: bool, enabled: bool, fcw_alert: bool, standstill: bool, - hud_control, stock_values: dict): + show_distance_bars: bool, hud_control, stock_values: dict): """ Creates a CAN message for the Ford IPC adaptive cruise, forward collision warning and traffic jam assist status. @@ -207,7 +210,7 @@ def create_acc_ui_msg(packer, CAN: CanBus, CP, main_on: bool, enabled: bool, fcw values.update({ "AccStopStat_D_Dsply": 2 if standstill else 0, # Stopping status text "AccMsgTxt_D2_Rq": 0, # ACC text - "AccTGap_B_Dsply": 0, # Show time gap control UI + "AccTGap_B_Dsply": 1 if show_distance_bars else 0, # Show time gap control UI "AccFllwMde_B_Dsply": 1 if hud_control.leadVisible else 0, # Lead indicator "AccStopMde_B_Dsply": 1 if standstill else 0, "AccWarn_D_Dsply": 0, # ACC warning diff --git a/opendbc/car/ford/interface.py b/opendbc/car/ford/interface.py index fbd027a2dc..53a5eb99c9 100644 --- a/opendbc/car/ford/interface.py +++ b/opendbc/car/ford/interface.py @@ -2,7 +2,7 @@ from opendbc.car import get_safety_config, structs from opendbc.car.common.conversions import Conversions as CV from opendbc.car.ford.fordcan import CanBus -from opendbc.car.ford.values import Ecu, FordFlags +from opendbc.car.ford.values import DBC, Ecu, FordFlags, RADAR from opendbc.car.interfaces import CarInterfaceBase TransmissionType = structs.CarParams.TransmissionType @@ -19,6 +19,14 @@ def _get_params(ret: structs.CarParams, candidate, fingerprint, car_fw, experime ret.steerActuatorDelay = 0.2 ret.steerLimitTimer = 1.0 + ret.longitudinalTuning.kiBP = [0.] + ret.longitudinalTuning.kiV = [0.5] + + if DBC[candidate]['radar'] == RADAR.DELPHI_MRR: + # average of 33.3 Hz radar timestep / 4 scan modes = 60 ms + # MRR_Header_Timestamps->CAN_DET_TIME_SINCE_MEAS reports 61.3 ms + ret.radarDelay = 0.06 + CAN = CanBus(fingerprint=fingerprint) cfgs = [get_safety_config(structs.CarParams.SafetyModel.ford)] if CAN.main >= 4: diff --git a/opendbc/car/ford/radar_interface.py b/opendbc/car/ford/radar_interface.py index efe3bef7d5..b145207e94 100644 --- a/opendbc/car/ford/radar_interface.py +++ b/opendbc/car/ford/radar_interface.py @@ -9,8 +9,12 @@ DELPHI_ESR_RADAR_MSGS = list(range(0x500, 0x540)) DELPHI_MRR_RADAR_START_ADDR = 0x120 +DELPHI_MRR_RADAR_HEADER_ADDR = 0x174 # MRR_Header_SensorCoverage DELPHI_MRR_RADAR_MSG_COUNT = 64 +DELPHI_MRR_RADAR_RANGE_COVERAGE = {0: 42, 1: 164, 2: 45, 3: 175} # scan index to detection range (m) +MIN_LONG_RANGE_DIST = 30 # meters + def _create_delphi_esr_radar_can_parser(CP) -> CANParser: msg_n = len(DELPHI_ESR_RADAR_MSGS) @@ -20,11 +24,14 @@ def _create_delphi_esr_radar_can_parser(CP) -> CANParser: def _create_delphi_mrr_radar_can_parser(CP) -> CANParser: - messages = [] + messages = [ + ("MRR_Header_InformationDetections", 33), + ("MRR_Header_SensorCoverage", 33), + ] for i in range(1, DELPHI_MRR_RADAR_MSG_COUNT + 1): msg = f"MRR_Detection_{i:03d}" - messages += [(msg, 20)] + messages += [(msg, 33)] return CANParser(RADAR.DELPHI_MRR, messages, CanBus(CP).radar) @@ -36,7 +43,7 @@ def __init__(self, CP): self.updated_messages = set() self.track_id = 0 self.radar = DBC[CP.carFingerprint]['radar'] - if self.radar is None or CP.radarUnavailable: + if CP.radarUnavailable: self.rcp = None elif self.radar == RADAR.DELPHI_ESR: self.rcp = _create_delphi_esr_radar_can_parser(CP) @@ -44,7 +51,7 @@ def __init__(self, CP): self.valid_cnt = {key: 0 for key in DELPHI_ESR_RADAR_MSGS} elif self.radar == RADAR.DELPHI_MRR: self.rcp = _create_delphi_mrr_radar_can_parser(CP) - self.trigger_msg = DELPHI_MRR_RADAR_START_ADDR + DELPHI_MRR_RADAR_MSG_COUNT - 1 + self.trigger_msg = DELPHI_MRR_RADAR_HEADER_ADDR else: raise ValueError(f"Unsupported radar: {self.radar}") @@ -62,14 +69,14 @@ def update(self, can_strings): errors = [] if not self.rcp.can_valid: errors.append("canError") - ret.errors = errors if self.radar == RADAR.DELPHI_ESR: self._update_delphi_esr() elif self.radar == RADAR.DELPHI_MRR: - self._update_delphi_mrr() + errors.extend(self._update_delphi_mrr()) ret.points = list(self.pts.values()) + ret.errors = errors self.updated_messages.clear() return ret @@ -103,14 +110,26 @@ def _update_delphi_esr(self): del self.pts[ii] def _update_delphi_mrr(self): + headerScanIndex = int(self.rcp.vl["MRR_Header_InformationDetections"]['CAN_SCAN_INDEX']) & 0b11 + + errors = [] + if DELPHI_MRR_RADAR_RANGE_COVERAGE[headerScanIndex] != int(self.rcp.vl["MRR_Header_SensorCoverage"]["CAN_RANGE_COVERAGE"]): + errors.append("wrongConfig") + for ii in range(1, DELPHI_MRR_RADAR_MSG_COUNT + 1): msg = self.rcp.vl[f"MRR_Detection_{ii:03d}"] - # SCAN_INDEX rotates through 0..3 on each message - # treat these as separate points + # SCAN_INDEX rotates through 0..3 on each message for different measurement modes + # Indexes 0 and 2 have a max range of ~40m, 1 and 3 are ~170m (MRR_Header_SensorCoverage->CAN_RANGE_COVERAGE) + # Indexes 0 and 1 have a Doppler coverage of +-71 m/s, 2 and 3 have +-60 m/s + # TODO: can we group into 2 groups? scanIndex = msg[f"CAN_SCAN_INDEX_2LSB_{ii:02d}"] i = (ii - 1) * 4 + scanIndex + # Throw out old measurements. Very unlikely to happen, but is proper behavior + if scanIndex != headerScanIndex: + continue + if i not in self.pts: self.pts[i] = structs.RadarData.RadarPoint() self.pts[i].trackId = self.track_id @@ -120,9 +139,13 @@ def _update_delphi_mrr(self): valid = bool(msg[f"CAN_DET_VALID_LEVEL_{ii:02d}"]) + # Long range measurement mode is more sensitive and can detect the road surface + dist = msg[f"CAN_DET_RANGE_{ii:02d}"] # m [0|255.984] + if scanIndex in (1, 3) and dist < MIN_LONG_RANGE_DIST: + valid = False + if valid: azimuth = msg[f"CAN_DET_AZIMUTH_{ii:02d}"] # rad [-3.1416|3.13964] - dist = msg[f"CAN_DET_RANGE_{ii:02d}"] # m [0|255.984] distRate = msg[f"CAN_DET_RANGE_RATE_{ii:02d}"] # m/s [-128|127.984] dRel = cos(azimuth) * dist # m from front of car yRel = -sin(azimuth) * dist # in car frame's y axis, left is positive @@ -141,3 +164,5 @@ def _update_delphi_mrr(self): else: del self.pts[i] + + return errors diff --git a/opendbc/car/gm/interface.py b/opendbc/car/gm/interface.py index 767909bd95..f3953c0eb9 100755 --- a/opendbc/car/gm/interface.py +++ b/opendbc/car/gm/interface.py @@ -138,7 +138,6 @@ def _get_params(ret: structs.CarParams, candidate, fingerprint, car_fw, experime ret.steerActuatorDelay = 0.1 # Default delay, not measured yet ret.steerLimitTimer = 0.4 - ret.radarTimeStep = 0.0667 # GM radar runs at 15Hz instead of standard 20Hz ret.longitudinalActuatorDelay = 0.5 # large delay to initially start braking if candidate == CAR.CHEVROLET_VOLT: diff --git a/opendbc/car/gm/radar_interface.py b/opendbc/car/gm/radar_interface.py index 78f6a89a94..e79d26533b 100755 --- a/opendbc/car/gm/radar_interface.py +++ b/opendbc/car/gm/radar_interface.py @@ -40,7 +40,6 @@ def __init__(self, CP): self.trigger_msg = LAST_RADAR_MSG self.updated_messages = set() - self.radar_ts = CP.radarTimeStep def update(self, can_strings): if self.rcp is None: diff --git a/opendbc/car/honda/carstate.py b/opendbc/car/honda/carstate.py index 1d9a0c1eb2..a20232734e 100644 --- a/opendbc/car/honda/carstate.py +++ b/opendbc/car/honda/carstate.py @@ -16,7 +16,7 @@ BUTTONS_DICT = {CruiseButtons.RES_ACCEL: ButtonType.accelCruise, CruiseButtons.DECEL_SET: ButtonType.decelCruise, CruiseButtons.MAIN: ButtonType.mainCruise, CruiseButtons.CANCEL: ButtonType.cancel} -SETTINGS_BUTTONS_DICT = {CruiseSettings.DISTANCE: ButtonType.gapAdjustCruise, CruiseSettings.LKAS: ButtonType.altButton1} +SETTINGS_BUTTONS_DICT = {CruiseSettings.DISTANCE: ButtonType.gapAdjustCruise, CruiseSettings.LKAS: ButtonType.lkas} def get_can_messages(CP, gearbox_msg): diff --git a/opendbc/car/honda/fingerprints.py b/opendbc/car/honda/fingerprints.py index bed0915cd1..522f8dba81 100644 --- a/opendbc/car/honda/fingerprints.py +++ b/opendbc/car/honda/fingerprints.py @@ -41,6 +41,7 @@ b'46114-TVA-A080\x00\x00', b'46114-TVA-A120\x00\x00', b'46114-TVA-A320\x00\x00', + b'46114-TVA-A410\x00\x00', b'46114-TVE-H550\x00\x00', b'46114-TVE-H560\x00\x00', ], @@ -438,6 +439,7 @@ b'36161-TPA-E050\x00\x00', b'36161-TPG-A030\x00\x00', b'36161-TPG-A040\x00\x00', + b'36161-TPG-A050\x00\x00', ], (Ecu.fwdRadar, 0x18dab0f1, None): [ b'36802-TMB-H040\x00\x00', diff --git a/opendbc/car/honda/radar_interface.py b/opendbc/car/honda/radar_interface.py index 316838aa5d..97c6664d0e 100755 --- a/opendbc/car/honda/radar_interface.py +++ b/opendbc/car/honda/radar_interface.py @@ -18,7 +18,6 @@ def __init__(self, CP): self.radar_fault = False self.radar_wrong_config = False self.radar_off_can = CP.radarUnavailable - self.radar_ts = CP.radarTimeStep # Nidec if self.radar_off_can: diff --git a/opendbc/car/honda/values.py b/opendbc/car/honda/values.py index c1c9a493f8..0188fb9ee8 100644 --- a/opendbc/car/honda/values.py +++ b/opendbc/car/honda/values.py @@ -163,7 +163,7 @@ class CAR(Platforms): flags=HondaFlags.BOSCH_ALT_BRAKE, ) HONDA_CRV_HYBRID = HondaBoschPlatformConfig( - [HondaCarDocs("Honda CR-V Hybrid 2017-21", min_steer_speed=12. * CV.MPH_TO_MS)], + [HondaCarDocs("Honda CR-V Hybrid 2017-22", min_steer_speed=12. * CV.MPH_TO_MS)], # mass: mean of 4 models in kg, steerRatio: 12.3 is spec end-to-end CarSpecs(mass=1667, wheelbase=2.66, steerRatio=16, centerToFrontRatio=0.41, tireStiffnessFactor=0.677), dbc_dict('honda_accord_2018_can_generated', None), diff --git a/opendbc/car/hyundai/fingerprints.py b/opendbc/car/hyundai/fingerprints.py index 5af9255c17..68b245300b 100644 --- a/opendbc/car/hyundai/fingerprints.py +++ b/opendbc/car/hyundai/fingerprints.py @@ -213,9 +213,11 @@ (Ecu.fwdRadar, 0x7d0, None): [ b'\xf1\x00TL__ FCA F-CUP 1.00 1.01 99110-D3500 ', b'\xf1\x00TL__ FCA F-CUP 1.00 1.02 99110-D3510 ', + b'\xf1\x00TL__ FCA FHCUP 1.00 1.02 99110-D3500 ', ], (Ecu.fwdCamera, 0x7c4, None): [ b'\xf1\x00TL MFC AT KOR LHD 1.00 1.02 95895-D3800 180719', + b'\xf1\x00TL MFC AT KOR LHD 1.00 1.06 95895-D3800 190107', b'\xf1\x00TL MFC AT USA LHD 1.00 1.06 95895-D3800 190107', ], }, @@ -229,6 +231,7 @@ (Ecu.abs, 0x7d1, None): [ b'\xf1\x00TM ESC \x02 100\x18\x030 58910-S2600', b'\xf1\x00TM ESC \x02 102\x18\x07\x01 58910-S2600', + b'\xf1\x00TM ESC \x02 103\x18\x11\x05 58910-S2500', b'\xf1\x00TM ESC \x02 103\x18\x11\x07 58910-S2600', b'\xf1\x00TM ESC \x02 104\x19\x07\x07 58910-S2600', b'\xf1\x00TM ESC \x03 103\x18\x11\x07 58910-S2600', @@ -263,6 +266,7 @@ b'\xf1\x00TM ESC \x02 103"\x07\x08 58910-S2GA0', b'\xf1\x00TM ESC \x03 101 \x08\x02 58910-S2DA0', b'\xf1\x00TM ESC \x03 102!\x04\x03 58910-S2DA0', + b'\xf1\x00TM ESC \x03 103"\x07\x06 58910-S2DA0', b'\xf1\x00TM ESC \x04 101 \x08\x04 58910-S2GA0', b'\xf1\x00TM ESC \x04 102!\x04\x05 58910-S2GA0', b'\xf1\x00TM ESC \x04 103"\x07\x08 58910-S2GA0', @@ -404,6 +408,7 @@ b'\xf1\x00LX ESC \x0b 103\x19\t\x07 58910-S8330', b'\xf1\x00LX ESC \x0b 103\x19\t\t 58910-S8350', b'\xf1\x00LX ESC \x0b 103\x19\t\x10 58910-S8360', + b'\xf1\x00LX ESC \x0b 104 \x10\x13 58910-S8330', b'\xf1\x00LX ESC \x0b 104 \x10\x16 58910-S8360', b'\xf1\x00ON ESC \x01 101\x19\t\x08 58910-S9360', b'\xf1\x00ON ESC \x0b 100\x18\x12\x18 58910-S9360', @@ -514,6 +519,7 @@ (Ecu.fwdCamera, 0x7c4, None): [ b'\xf1\x00HI LKAS AT USA LHD 1.00 1.00 95895-D2020 160302', b'\xf1\x00HI LKAS AT USA LHD 1.00 1.00 95895-D2030 170208', + b'\xf1\x00HI LKAS AT USA LHD 1.00 1.01 95895-D2030 170811', b'\xf1\x00HI MFC AT USA LHD 1.00 1.03 99211-D2000 190831', ], }, @@ -611,10 +617,12 @@ b'\xf1\x00OS IEB \x03 210 \x02\x14 58520-K4000', b'\xf1\x00OS IEB \x03 211 \x04\x02 58520-K4000', b'\xf1\x00OS IEB \x03 212 \x11\x13 58520-K4000', + b'\xf1\x00OS IEB \x04 212 \x11\x13 58520-K4000', b'\xf1\x00OS IEB \r 105\x18\t\x18 58520-K4000', ], (Ecu.fwdCamera, 0x7c4, None): [ b'\xf1\x00OE2 LKAS AT EUR LHD 1.00 1.00 95740-K4200 200', + b'\xf1\x00OSE LKAS AT AUS RHD 1.00 1.00 95740-K4300 W50', b'\xf1\x00OSE LKAS AT EUR LHD 1.00 1.00 95740-K4100 W40', b'\xf1\x00OSE LKAS AT EUR RHD 1.00 1.00 95740-K4100 W40', b'\xf1\x00OSE LKAS AT KOR LHD 1.00 1.00 95740-K4100 W40', @@ -624,6 +632,7 @@ (Ecu.eps, 0x7d4, None): [ b'\xf1\x00OS MDPS C 1.00 1.03 56310/K4550 4OEDC103', b'\xf1\x00OS MDPS C 1.00 1.04 56310-XX000 4OEDC104', + b'\xf1\x00OS MDPS C 1.00 1.04 56310/K4550 4OEDC104', b'\xf1\x00OS MDPS C 1.00 1.04 56310K4000\x00 4OEDC104', b'\xf1\x00OS MDPS C 1.00 1.04 56310K4050\x00 4OEDC104', ], @@ -1070,10 +1079,10 @@ }, CAR.GENESIS_GV60_EV_1ST_GEN: { (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00JW1 MFC AT AUS RHD 1.00 1.03 99211-CU100 221118', b'\xf1\x00JW1 MFC AT USA LHD 1.00 1.02 99211-CU000 211215', b'\xf1\x00JW1 MFC AT USA LHD 1.00 1.02 99211-CU100 211215', b'\xf1\x00JW1 MFC AT USA LHD 1.00 1.03 99211-CU000 221118', - b'\xf1\x00JW1 MFC AT AUS RHD 1.00 1.03 99211-CU100 221118', ], (Ecu.fwdRadar, 0x7d0, None): [ b'\xf1\x00JW1_ RDR ----- 1.00 1.00 99110-CU000 ', @@ -1084,6 +1093,7 @@ b'\xf1\x00MQ4 MFC AT USA LHD 1.00 1.00 99210-R5100 221019', b'\xf1\x00MQ4 MFC AT USA LHD 1.00 1.03 99210-R5000 200903', b'\xf1\x00MQ4 MFC AT USA LHD 1.00 1.05 99210-R5000 210623', + b'\xf1\x00MQ4 MFC AT USA LHD 1.00 1.06 99210-R5000 211216', ], (Ecu.fwdRadar, 0x7d0, None): [ b'\xf1\x00MQ4_ SCC F-CUP 1.00 1.06 99110-P2000 ', diff --git a/opendbc/car/interfaces.py b/opendbc/car/interfaces.py index c704f12f4a..f5644a5cff 100644 --- a/opendbc/car/interfaces.py +++ b/opendbc/car/interfaces.py @@ -259,12 +259,11 @@ def __init__(self, CP: structs.CarParams): self.CP = CP self.rcp = None self.pts: dict[int, structs.RadarData.RadarPoint] = {} - self.radar_ts = CP.radarTimeStep self.frame = 0 def update(self, can_packets: list[tuple[int, list[CanData]]]) -> structs.RadarDataT | None: self.frame += 1 - if (self.frame % int(100 * self.radar_ts)) == 0: + if (self.frame % 5) == 0: # 20 Hz is very standard return structs.RadarData() return None diff --git a/opendbc/car/tesla/carcontroller.py b/opendbc/car/tesla/carcontroller.py index 3c0ba959b5..4bcc1a9915 100644 --- a/opendbc/car/tesla/carcontroller.py +++ b/opendbc/car/tesla/carcontroller.py @@ -20,7 +20,7 @@ def update(self, CC, CS, now_nanos): can_sends = [] # Disengage and allow for user override - hands_on_fault = CS.steer_warning == "EAC_ERROR_HANDS_ON" and CS.hands_on_level >= 3 + hands_on_fault = CS.hands_on_level >= 3 lkas_enabled = CC.latActive and not hands_on_fault if self.frame % 2 == 0: @@ -36,14 +36,15 @@ def update(self, CC, CS, now_nanos): self.apply_angle_last = apply_angle can_sends.append(self.tesla_can.create_steering_control(apply_angle, lkas_enabled, (self.frame // 2) % 16)) + if self.frame % 10 == 0: + can_sends.append(self.tesla_can.create_steering_allowed((self.frame // 10) % 16)) + # Longitudinal control if self.CP.openpilotLongitudinalControl and self.frame % 4 == 0: - state = CS.das_control["DAS_accState"] - if hands_on_fault: - state = 13 # "ACC_CANCEL_GENERIC_SILENT" + state = 4 if not hands_on_fault else 13 # 4=ACC_ON, 13=ACC_CANCEL_GENERIC_SILENT accel = clip(actuators.accel, CarControllerParams.ACCEL_MIN, CarControllerParams.ACCEL_MAX) cntr = (self.frame // 4) % 8 - can_sends.append(self.tesla_can.create_longitudinal_command(state, accel, cntr)) + can_sends.append(self.tesla_can.create_longitudinal_command(state, accel, cntr, CC.longActive)) # Increment counter so cancel is prioritized even without openpilot longitudinal if hands_on_fault and not self.CP.openpilotLongitudinalControl: diff --git a/opendbc/car/tesla/carstate.py b/opendbc/car/tesla/carstate.py index 82d1c0d30c..4a4b32c034 100644 --- a/opendbc/car/tesla/carstate.py +++ b/opendbc/car/tesla/carstate.py @@ -14,7 +14,6 @@ def __init__(self, CP): self.can_define = CANDefine(DBC[CP.carFingerprint]['pt']) self.hands_on_level = 0 - self.steer_warning = None self.das_control = None def update(self, cp, cp_cam, *_) -> structs.CarState: @@ -23,7 +22,7 @@ def update(self, cp, cp_cam, *_) -> structs.CarState: # Vehicle speed ret.vEgoRaw = cp.vl["DI_speed"]["DI_vehicleSpeed"] * CV.KPH_TO_MS ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw) - ret.standstill = cp.vl["ESP_B"]["ESP_vehicleStandstillSts"] == 1 + ret.standstill = cp.vl["DI_state"]["DI_vehicleHoldState"] == 3 # Gas pedal pedal_status = cp.vl["DI_systemStatus"]["DI_accelPedalPos"] @@ -37,22 +36,20 @@ def update(self, cp, cp_cam, *_) -> structs.CarState: # Steering wheel epas_status = cp.vl["EPAS3S_sysStatus"] self.hands_on_level = epas_status["EPAS3S_handsOnLevel"] - self.steer_warning = self.can_define.dv["EPAS3S_sysStatus"]["EPAS3S_eacErrorCode"].get(int(epas_status["EPAS3S_eacErrorCode"]), None) ret.steeringAngleDeg = -epas_status["EPAS3S_internalSAS"] ret.steeringRateDeg = -cp_cam.vl["SCCM_steeringAngleSensor"]["SCCM_steeringAngleSpeed"] ret.steeringTorque = -epas_status["EPAS3S_torsionBarTorque"] ret.steeringPressed = self.hands_on_level > 0 eac_status = self.can_define.dv["EPAS3S_sysStatus"]["EPAS3S_eacStatus"].get(int(epas_status["EPAS3S_eacStatus"]), None) - ret.steerFaultPermanent = eac_status in ["EAC_FAULT"] - ret.steerFaultTemporary = self.steer_warning not in ["EAC_ERROR_IDLE", "EAC_ERROR_HANDS_ON"] and eac_status not in ["EAC_ACTIVE", "EAC_AVAILABLE"] + ret.steerFaultPermanent = eac_status == "EAC_FAULT" + ret.steerFaultTemporary = eac_status == "EAC_INHIBITED" # Cruise state cruise_state = self.can_define.dv["DI_state"]["DI_cruiseState"].get(int(cp.vl["DI_state"]["DI_cruiseState"]), None) speed_units = self.can_define.dv["DI_state"]["DI_speedUnits"].get(int(cp.vl["DI_state"]["DI_speedUnits"]), None) - self.acc_enabled = cruise_state in ("ENABLED", "STANDSTILL", "OVERRIDE", "PRE_FAULT", "PRE_CANCEL") - ret.cruiseState.enabled = self.acc_enabled + ret.cruiseState.enabled = cruise_state in ("ENABLED", "STANDSTILL", "OVERRIDE", "PRE_FAULT", "PRE_CANCEL") if speed_units == "KPH": ret.cruiseState.speed = cp.vl["DI_state"]["DI_digitalSpeed"] * CV.KPH_TO_MS elif speed_units == "MPH": @@ -92,7 +89,6 @@ def get_can_parser(CP): messages = [ # sig_address, frequency ("DI_speed", 50), - ("ESP_B", 50), ("DI_systemStatus", 100), ("IBST_status", 25), ("DI_state", 10), diff --git a/opendbc/car/tesla/fingerprints.py b/opendbc/car/tesla/fingerprints.py index f87cddda9f..81cb49a2c8 100644 --- a/opendbc/car/tesla/fingerprints.py +++ b/opendbc/car/tesla/fingerprints.py @@ -12,7 +12,7 @@ b'TeMYG4_DCS_Update_0.0.0 (9),E4014.26.0', b'TeMYG4_Main_0.0.0 (59),E4H014.29.0', b'TeMYG4_SingleECU_0.0.0 (33),E4S014.27', - ] + ], }, CAR.TESLA_MODEL_Y: { (Ecu.eps, 0x730, None): [ @@ -23,6 +23,6 @@ b'TeMYG4_DCS_Update_0.0.0 (13),Y4P002.27.1', b'TeMYG4_DCS_Update_0.0.0 (9),Y4P002.25.0', b'TeMYG4_SingleECU_0.0.0 (33),Y4S002.26', - ] + ], }, } diff --git a/opendbc/car/tesla/teslacan.py b/opendbc/car/tesla/teslacan.py index 22963861bc..f71043bde0 100644 --- a/opendbc/car/tesla/teslacan.py +++ b/opendbc/car/tesla/teslacan.py @@ -24,9 +24,9 @@ def create_steering_control(self, angle, enabled, counter): values["DAS_steeringControlChecksum"] = self.checksum(0x488, data[:3]) return self.packer.make_can_msg("DAS_steeringControl", CANBUS.party, values) - def create_longitudinal_command(self, acc_state, accel, cntr): + def create_longitudinal_command(self, acc_state, accel, cntr, active): values = { - "DAS_setSpeed": 0 if accel < 0 else V_CRUISE_MAX, + "DAS_setSpeed": 0 if (accel < 0 or not active) else V_CRUISE_MAX, "DAS_accState": acc_state, "DAS_aebEvent": 0, "DAS_jerkMin": CarControllerParams.JERK_LIMIT_MIN, @@ -39,3 +39,13 @@ def create_longitudinal_command(self, acc_state, accel, cntr): data = self.packer.make_can_msg("DAS_control", CANBUS.party, values)[1] values["DAS_controlChecksum"] = self.checksum(0x2b9, data[:7]) return self.packer.make_can_msg("DAS_control", CANBUS.party, values) + + def create_steering_allowed(self, counter): + values = { + "APS_eacAllow": 1, + "APS_eacMonitorCounter": counter, + } + + data = self.packer.make_can_msg("APS_eacMonitor", CANBUS.party, values)[1] + values["APS_eacMonitorChecksum"] = self.checksum(0x27d, data[:2]) + return self.packer.make_can_msg("APS_eacMonitor", CANBUS.party, values) diff --git a/opendbc/car/tests/routes.py b/opendbc/car/tests/routes.py index a186782d3b..0b295b5424 100644 --- a/opendbc/car/tests/routes.py +++ b/opendbc/car/tests/routes.py @@ -209,6 +209,7 @@ class CarTestRoute(NamedTuple): CarTestRoute("7e34a988419b5307|2019-12-18--19-13-30", TOYOTA.TOYOTA_RAV4_TSS2), # hybrid CarTestRoute("2475fb3eb2ffcc2e|2022-04-29--12-46-23", TOYOTA.TOYOTA_RAV4_TSS2_2022), # hybrid CarTestRoute("20ba9ade056a8c7b|2021-02-08--21-57-35", TOYOTA.TOYOTA_RAV4_PRIME), # SecOC + CarTestRoute("8bfb000e03b2a257/00000004--f9eee5f52e", TOYOTA.TOYOTA_SIENNA_4TH_GEN), # SecOC CarTestRoute("7a31f030957b9c85|2023-04-01--14-12-51", TOYOTA.LEXUS_ES), CarTestRoute("37041c500fd30100|2020-12-30--12-17-24", TOYOTA.LEXUS_ES), # hybrid CarTestRoute("e6a24be49a6cd46e|2019-10-29--10-52-42", TOYOTA.LEXUS_ES_TSS2), diff --git a/opendbc/car/torque_data/substitute.toml b/opendbc/car/torque_data/substitute.toml index 79497ca9c6..22256a38a2 100644 --- a/opendbc/car/torque_data/substitute.toml +++ b/opendbc/car/torque_data/substitute.toml @@ -10,6 +10,7 @@ legend = ["LAT_ACCEL_FACTOR", "MAX_LAT_ACCEL_MEASURED", "FRICTION"] "TOYOTA_ALPHARD_TSS2" = "TOYOTA_SIENNA" "TOYOTA_PRIUS_V" = "TOYOTA_PRIUS" "TOYOTA_RAV4_PRIME" = "TOYOTA_RAV4_TSS2" +"TOYOTA_SIENNA_4TH_GEN" = "TOYOTA_RAV4_TSS2" "LEXUS_IS" = "LEXUS_NX" "LEXUS_CTH" = "LEXUS_NX" "LEXUS_ES" = "TOYOTA_CAMRY" diff --git a/opendbc/car/toyota/carcontroller.py b/opendbc/car/toyota/carcontroller.py index ebbf701811..e1b4003b84 100644 --- a/opendbc/car/toyota/carcontroller.py +++ b/opendbc/car/toyota/carcontroller.py @@ -1,6 +1,6 @@ import math from opendbc.car import carlog, apply_meas_steer_torque_limits, apply_std_steer_angle_limits, common_fault_avoidance, \ - make_tester_present_msg, rate_limit, structs + make_tester_present_msg, rate_limit, structs, ACCELERATION_DUE_TO_GRAVITY from opendbc.car.can_definitions import CanData from opendbc.car.common.numpy_fast import clip from opendbc.car.secoc import add_mac, build_sync_mac @@ -15,8 +15,6 @@ SteerControlType = structs.CarParams.SteerControlType VisualAlert = structs.CarControl.HUDControl.VisualAlert -ACCELERATION_DUE_TO_GRAVITY = 9.81 # m/s^2 - ACCEL_WINDUP_LIMIT = 0.5 # m/s^2 / frame # LKA limits @@ -46,7 +44,7 @@ def __init__(self, dbc_name, CP): self.distance_button = 0 self.pcm_accel_compensation = 0.0 - self.permit_braking = 0.0 + self.permit_braking = True self.packer = CANPacker(dbc_name) self.accel = 0 @@ -146,10 +144,13 @@ def update(self, CC, CS, now_nanos): # *** gas and brake *** # For cars where we allow a higher max acceleration of 2.0 m/s^2, compensate for PCM request overshoot and imprecise braking - # TODO: sometimes when switching from brake to gas quickly, CLUTCH->ACCEL_NET shows a slow unwind. make it go to 0 immediately if self.CP.flags & ToyotaFlags.RAISED_ACCEL_LIMIT and CC.longActive and not CS.out.cruiseState.standstill: # calculate amount of acceleration PCM should apply to reach target, given pitch - accel_due_to_pitch = math.sin(CS.slope_angle) * ACCELERATION_DUE_TO_GRAVITY + if len(CC.orientationNED) == 3: + accel_due_to_pitch = math.sin(CC.orientationNED[1]) * ACCELERATION_DUE_TO_GRAVITY + else: + accel_due_to_pitch = 0.0 + net_acceleration_request = actuators.accel + accel_due_to_pitch # let PCM handle stopping for now diff --git a/opendbc/car/toyota/carstate.py b/opendbc/car/toyota/carstate.py index 438ee088b8..c81899d137 100644 --- a/opendbc/car/toyota/carstate.py +++ b/opendbc/car/toyota/carstate.py @@ -51,7 +51,6 @@ def __init__(self, CP): self.acc_type = 1 self.lkas_hud = {} self.pcm_accel_net = 0.0 - self.slope_angle = 0.0 self.secoc_synchronization = None def update(self, cp, cp_cam, *_) -> structs.CarState: @@ -88,7 +87,6 @@ def update(self, cp, cp_cam, *_) -> structs.CarState: can_gear = int(cp.vl["GEAR_PACKET_HYBRID"]["GEAR"]) else: ret.gasPressed = cp.vl["PCM_CRUISE"]["GAS_RELEASED"] == 0 # TODO: these also have GAS_PEDAL, come back and unify - self.slope_angle = cp.vl["VSC1S07"]["ASLP"] * CV.DEG_TO_RAD # filtered pitch from the car, negative is downward can_gear = int(cp.vl["GEAR_PACKET"]["GEAR"]) if not self.CP.enableDsu and not self.CP.flags & ToyotaFlags.DISABLE_RADAR.value: ret.stockAeb = bool(cp_acc.vl["PRE_COLLISION"]["PRECOLLISION_ACTIVE"] and cp_acc.vl["PRE_COLLISION"]["FORCE"] < -1e-5) @@ -232,7 +230,6 @@ def get_can_parser(CP): messages += [ ("GEAR_PACKET", 1), - ("VSC1S07", 20), ] if CP.flags & ToyotaFlags.RAISED_ACCEL_LIMIT: diff --git a/opendbc/car/toyota/fingerprints.py b/opendbc/car/toyota/fingerprints.py index 4467542c70..24d7ae3655 100644 --- a/opendbc/car/toyota/fingerprints.py +++ b/opendbc/car/toyota/fingerprints.py @@ -127,6 +127,7 @@ b'\x018966333X0000\x00\x00\x00\x00', b'\x018966333X4000\x00\x00\x00\x00', b'\x01896633T16000\x00\x00\x00\x00', + b'\x01896633TA2000\x00\x00\x00\x00', b'\x028966306B2100\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', b'\x028966306B2300\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', b'\x028966306B2500\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00', @@ -321,6 +322,7 @@ b'F1526F4073\x00\x00\x00\x00\x00\x00', b'F1526F4121\x00\x00\x00\x00\x00\x00', b'F1526F4122\x00\x00\x00\x00\x00\x00', + b'F1526F4190\x00\x00\x00\x00\x00\x00', ], (Ecu.eps, 0x7a1, None): [ b'8965B10011\x00\x00\x00\x00\x00\x00', @@ -337,6 +339,7 @@ b'\x033F401200\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203202\x00\x00\x00\x00', b'\x033F424000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203202\x00\x00\x00\x00', b'\x033F424000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', + b'\x033F435000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x750, 0xf): [ b'8821F0W01000 ', @@ -391,6 +394,7 @@ (Ecu.fwdCamera, 0x750, 0x6d): [ b'\x028646FF410200\x00\x00\x00\x008646GF408200\x00\x00\x00\x00', b'\x028646FF411100\x00\x00\x00\x008646GF409000\x00\x00\x00\x00', + b'\x028646FF413000\x00\x00\x00\x008646GF411000\x00\x00\x00\x00', b'\x028646FF413100\x00\x00\x00\x008646GF411100\x00\x00\x00\x00', ], }, @@ -431,6 +435,7 @@ CAR.TOYOTA_COROLLA_TSS2: { (Ecu.engine, 0x700, None): [ b'\x01896630A22000\x00\x00\x00\x00', + b'\x01896630A42000\x00\x00\x00\x00', b'\x01896630ZG2000\x00\x00\x00\x00', b'\x01896630ZG5000\x00\x00\x00\x00', b'\x01896630ZG5100\x00\x00\x00\x00', @@ -525,6 +530,7 @@ b'8965B16011\x00\x00\x00\x00\x00\x00', b'8965B16101\x00\x00\x00\x00\x00\x00', b'8965B16170\x00\x00\x00\x00\x00\x00', + b'8965B16260\x00\x00\x00\x00\x00\x00', b'8965B76012\x00\x00\x00\x00\x00\x00', b'8965B76050\x00\x00\x00\x00\x00\x00', b'8965B76091\x00\x00\x00\x00\x00\x00', @@ -539,6 +545,7 @@ b'\x01F15260A010\x00\x00\x00\x00\x00\x00', b'\x01F15260A050\x00\x00\x00\x00\x00\x00', b'\x01F15260A070\x00\x00\x00\x00\x00\x00', + b'\x01F15260A33000\x00\x00\x00\x00', b'\x01F152612641\x00\x00\x00\x00\x00\x00', b'\x01F152612651\x00\x00\x00\x00\x00\x00', b'\x01F152612862\x00\x00\x00\x00\x00\x00', @@ -598,6 +605,7 @@ b'\x028646F1601100\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', b'\x028646F1601200\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', b'\x028646F1601300\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + b'\x028646F1601500\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', b'\x028646F4203400\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', b'\x028646F76020C0\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', b'\x028646F7603100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', @@ -716,11 +724,13 @@ b'\x01896630EE7000\x00\x00\x00\x00', b'\x01896630EF8000\x00\x00\x00\x00', b'\x01896630EG3000\x00\x00\x00\x00', + b'\x01896630EG3100\x00\x00\x00\x00', b'\x01896630EG5000\x00\x00\x00\x00', b'\x02896630E66000\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', b'\x02896630E66100\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', b'\x02896630EB3000\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', b'\x02896630EB3100\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', + b'\x02896630EB3200\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x750, 0xf): [ b'\x018821F3301400\x00\x00\x00\x00', @@ -1010,21 +1020,26 @@ b'\x018966342S7000\x00\x00\x00\x00', b'\x018966342Z1000\x00\x00\x00\x00', b'\x018966342Z1100\x00\x00\x00\x00', + b'\x01896634AJ7000\x00\x00\x00\x00', ], (Ecu.abs, 0x7b0, None): [ b'\x01F15264228300\x00\x00\x00\x00', b'\x01F15264228500\x00\x00\x00\x00', b'\x01F15264284100\x00\x00\x00\x00', + b'\x01F152642F3000\x00\x00\x00\x00', ], (Ecu.eps, 0x7a1, None): [ b'\x018965B4209000\x00\x00\x00\x00', + b'\x018965B4233100\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x750, 0xf): [ b'\x018821F3301400\x00\x00\x00\x00', + b'\x018821F6201400\x00\x00\x00\x00', ], (Ecu.fwdCamera, 0x750, 0x6d): [ b'\x028646F4205200\x00\x00\x00\x008646G4202000\x00\x00\x00\x00', b'\x028646F4205300\x00\x00\x00\x008646G4202100\x00\x00\x00\x00', + b'\x028646F4210100\x00\x00\x00\x008646G3305000\x00\x00\x00\x00', ], }, CAR.TOYOTA_RAV4_TSS2: { @@ -1248,6 +1263,28 @@ b'8646F0801100\x00\x00\x00\x00', ], }, + CAR.TOYOTA_SIENNA_4TH_GEN: { + (Ecu.engine, 0x700, None): [ + b'\x01896630841000\x00\x00\x00\x00', + b'\x01896630857101\x00\x00\x00\x00', + b'\x01896630864000\x00\x00\x00\x00', + ], + (Ecu.abs, 0x7b0, None): [ + b'\x01F15260815100\x00\x00\x00\x00', + b'\x01F15260815300\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'\x018965B4509100\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F3301500\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F0802200\x00\x00\x00\x008646G4202100\x00\x00\x00\x00', + b'\x028646F0802300\x00\x00\x00\x008646G4202100\x00\x00\x00\x00', + b'\x028646F0802400\x00\x00\x00\x008646G4202100\x00\x00\x00\x00', + ], + }, CAR.LEXUS_CTH: { (Ecu.dsu, 0x791, None): [ b'881517601100\x00\x00\x00\x00', @@ -1666,6 +1703,7 @@ b'8965B47070\x00\x00\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F3301300\x00\x00\x00\x00', b'\x018821F3301400\x00\x00\x00\x00', ], (Ecu.fwdCamera, 0x750, 0x6d): [ diff --git a/opendbc/car/toyota/interface.py b/opendbc/car/toyota/interface.py index bb9a1ba3ec..3691f9f78c 100644 --- a/opendbc/car/toyota/interface.py +++ b/opendbc/car/toyota/interface.py @@ -67,7 +67,7 @@ def _get_params(ret: structs.CarParams, candidate, fingerprint, car_fw, experime # https://engage.toyota.com/static/images/toyota_safety_sense/TSS_Applicability_Chart.pdf stop_and_go = candidate != CAR.TOYOTA_AVALON - elif candidate in (CAR.TOYOTA_RAV4_TSS2, CAR.TOYOTA_RAV4_TSS2_2022, CAR.TOYOTA_RAV4_TSS2_2023, CAR.TOYOTA_RAV4_PRIME): + elif candidate in (CAR.TOYOTA_RAV4_TSS2, CAR.TOYOTA_RAV4_TSS2_2022, CAR.TOYOTA_RAV4_TSS2_2023, CAR.TOYOTA_RAV4_PRIME, CAR.TOYOTA_SIENNA_4TH_GEN): ret.lateralTuning.init('pid') ret.lateralTuning.pid.kiBP = [0.0] ret.lateralTuning.pid.kpBP = [0.0] diff --git a/opendbc/car/toyota/radar_interface.py b/opendbc/car/toyota/radar_interface.py index 922dbac278..bfb2df0494 100755 --- a/opendbc/car/toyota/radar_interface.py +++ b/opendbc/car/toyota/radar_interface.py @@ -23,7 +23,6 @@ class RadarInterface(RadarInterfaceBase): def __init__(self, CP): super().__init__(CP) self.track_id = 0 - self.radar_ts = CP.radarTimeStep if CP.carFingerprint in TSS2_CAR: self.RADAR_A_MSGS = list(range(0x180, 0x190)) diff --git a/opendbc/car/toyota/values.py b/opendbc/car/toyota/values.py index 47661a92c4..d61849f354 100644 --- a/opendbc/car/toyota/values.py +++ b/opendbc/car/toyota/values.py @@ -252,7 +252,7 @@ class CAR(Platforms): # TODO: Enable this docs entry when it can be suppressed from openpilot CARS.md # [ToyotaCarDocs("Toyota RAV4 Prime 2021-23", min_enable_speed=MIN_ACC_SPEED)], [], - CarSpecs(mass=3650. * CV.LB_TO_KG, wheelbase=2.65, steerRatio=16.88, tireStiffnessFactor=0.5533), + CarSpecs(mass=4372. * CV.LB_TO_KG, wheelbase=2.68, steerRatio=16.88, tireStiffnessFactor=0.5533), dbc_dict('toyota_rav4_prime_generated', 'toyota_tss2_adas'), flags=ToyotaFlags.TSS2 | ToyotaFlags.NO_STOP_TIMER | ToyotaFlags.NO_DSU | ToyotaFlags.SECOC, ) @@ -266,6 +266,14 @@ class CAR(Platforms): dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), flags=ToyotaFlags.NO_STOP_TIMER, ) + TOYOTA_SIENNA_4TH_GEN = PlatformConfig( + # TODO: Enable this docs entry when it can be suppressed from openpilot CARS.md + # [ToyotaCarDocs("Toyota Sienna 2021-23", min_enable_speed=MIN_ACC_SPEED)], + [], + CarSpecs(mass=4625. * CV.LB_TO_KG, wheelbase=3.06, steerRatio=17.8, tireStiffnessFactor=0.444), + dbc_dict('toyota_rav4_prime_generated', 'toyota_tss2_adas'), + flags=ToyotaFlags.TSS2 | ToyotaFlags.NO_STOP_TIMER | ToyotaFlags.NO_DSU | ToyotaFlags.SECOC, + ) # Lexus LEXUS_CTH = PlatformConfig( @@ -549,6 +557,7 @@ def match_fw_to_car_fuzzy(live_fw_versions, vin, offline_fw_versions) -> set[str # Hybrid control computer can be on 0x7e2 (KWP) or 0x7d2 (UDS) depending on platform (Ecu.hybrid, 0x7e2, None), # Hybrid Control Assembly & Computer + (Ecu.hybrid, 0x7d2, None), # Hybrid Control Assembly & Computer (Ecu.srs, 0x780, None), # SRS Airbag # Transmission is combined with engine on some platforms, such as TSS-P RAV4 (Ecu.transmission, 0x701, None), diff --git a/opendbc/car/volkswagen/fingerprints.py b/opendbc/car/volkswagen/fingerprints.py index 4711beaf3c..a3bae382ac 100644 --- a/opendbc/car/volkswagen/fingerprints.py +++ b/opendbc/car/volkswagen/fingerprints.py @@ -52,6 +52,7 @@ CAR.VOLKSWAGEN_ATLAS_MK1: { (Ecu.engine, 0x7e0, None): [ b'\xf1\x8703H906026AA\xf1\x899970', + b'\xf1\x8703H906026AG\xf1\x899971', b'\xf1\x8703H906026AG\xf1\x899973', b'\xf1\x8703H906026AJ\xf1\x890638', b'\xf1\x8703H906026AJ\xf1\x891017', @@ -355,11 +356,13 @@ b'\xf1\x8704E906024L \xf1\x895595', b'\xf1\x8704E906024L \xf1\x899970', b'\xf1\x8704E906027MS\xf1\x896223', + b'\xf1\x8705E906013BN\xf1\x893711', b'\xf1\x8705E906013DB\xf1\x893361', b'\xf1\x875G0906259T \xf1\x890003', ], (Ecu.transmission, 0x7e1, None): [ b'\xf1\x8709G927158BQ\xf1\x893545', + b'\xf1\x8709H927158 \xf1\x890515', b'\xf1\x8709S927158BS\xf1\x893642', b'\xf1\x8709S927158BS\xf1\x893694', b'\xf1\x8709S927158CK\xf1\x893770', @@ -387,8 +390,10 @@ b'\xf1\x875QM909144C \xf1\x891082\xf1\x82\x0521A00642A1', b'\xf1\x875QM909144C \xf1\x891082\xf1\x82\x0521A10A01A1', b'\xf1\x875QN909144B \xf1\x895082\xf1\x82\x0571A10A11A1', + b'\xf1\x875QV907144F \xf1\x891122\xf1\x82\x0001A00701]V', ], (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907567B \xf1\x890534', b'\xf1\x872Q0907572AA\xf1\x890396', b'\xf1\x875Q0907572N \xf1\x890681', b'\xf1\x875Q0907572P \xf1\x890682', diff --git a/opendbc/dbc/acura_rdx_2020_can_generated.dbc b/opendbc/dbc/acura_rdx_2020_can_generated.dbc index c6149921dc..7a225aa599 100644 --- a/opendbc/dbc/acura_rdx_2020_can_generated.dbc +++ b/opendbc/dbc/acura_rdx_2020_can_generated.dbc @@ -322,12 +322,14 @@ BO_ 806 SCM_FEEDBACK: 8 SCM 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 : 7|16@0+ (1,0) [0|127] "" BDY + SG_ SPEED_LIMIT_SIGN : 23|8@0+ (1,0) [0|255] "" XXX + SG_ ROAD_SIGN : 31|8@0+ (1,0) [0|255] "" XXX SG_ ZEROS_BOH_2 : 51|4@0+ (1,0) [0|15] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ AUTO_HIGHBEAMS_ACTIVE : 53|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_ 927 RADAR_HUD: 8 RADAR SG_ ZEROS_BOH : 7|10@0+ (1,0) [0|127] "" BDY @@ -396,7 +398,8 @@ 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"; - +VAL_ 862 SPEED_LIMIT_SIGN 97 "SPEED_LIMIT_5" 98 "SPEED_LIMIT_10" 99 "SPEED_LIMIT_15" 100 "SPEED_LIMIT_20" 101 "SPEED_LIMIT_25" 102 "SPEED_LIMIT_30" 103 "SPEED_LIMIT_35" 104 "SPEED_LIMIT_40" 105 "SPEED_LIMIT_45" 106 "SPEED_LIMIT_50" 107 "SPEED_LIMIT_55" 108 "SPEED_LIMIT_60" 109 "SPEED_LIMIT_65" 110 "SPEED_LIMIT_70" 111 "SPEED_LIMIT_75" 112 "SPEED_LIMIT_80" 113 "SPEED_LIMIT_85" 125 "SPEED_LIMIT_NA" 0 "STOP_SIGN"; +VAL_ 862 ROAD_SIGN 0 "NO_SIGN" 89 "STOP_SIGN"; CM_ "Imported file _bosch_adas_2018.dbc starts here"; BO_ 479 ACC_CONTROL: 8 EON diff --git a/opendbc/dbc/generator/honda/_bosch_2018.dbc b/opendbc/dbc/generator/honda/_bosch_2018.dbc index bf981781d0..b5e8c14d6c 100644 --- a/opendbc/dbc/generator/honda/_bosch_2018.dbc +++ b/opendbc/dbc/generator/honda/_bosch_2018.dbc @@ -152,12 +152,14 @@ BO_ 806 SCM_FEEDBACK: 8 SCM 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 : 7|16@0+ (1,0) [0|127] "" BDY + SG_ SPEED_LIMIT_SIGN : 23|8@0+ (1,0) [0|255] "" XXX + SG_ ROAD_SIGN : 31|8@0+ (1,0) [0|255] "" XXX SG_ ZEROS_BOH_2 : 51|4@0+ (1,0) [0|15] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ AUTO_HIGHBEAMS_ACTIVE : 53|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_ 927 RADAR_HUD: 8 RADAR SG_ ZEROS_BOH : 7|10@0+ (1,0) [0|127] "" BDY @@ -226,3 +228,5 @@ 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"; +VAL_ 862 SPEED_LIMIT_SIGN 97 "SPEED_LIMIT_5" 98 "SPEED_LIMIT_10" 99 "SPEED_LIMIT_15" 100 "SPEED_LIMIT_20" 101 "SPEED_LIMIT_25" 102 "SPEED_LIMIT_30" 103 "SPEED_LIMIT_35" 104 "SPEED_LIMIT_40" 105 "SPEED_LIMIT_45" 106 "SPEED_LIMIT_50" 107 "SPEED_LIMIT_55" 108 "SPEED_LIMIT_60" 109 "SPEED_LIMIT_65" 110 "SPEED_LIMIT_70" 111 "SPEED_LIMIT_75" 112 "SPEED_LIMIT_80" 113 "SPEED_LIMIT_85" 125 "SPEED_LIMIT_NA" 0 "STOP_SIGN"; +VAL_ 862 ROAD_SIGN 0 "NO_SIGN" 89 "STOP_SIGN"; \ No newline at end of file diff --git a/opendbc/dbc/generator/honda/honda_civic_ex_2022_can.dbc b/opendbc/dbc/generator/honda/honda_civic_ex_2022_can.dbc index ad50302379..bbe3eadb31 100644 --- a/opendbc/dbc/generator/honda/honda_civic_ex_2022_can.dbc +++ b/opendbc/dbc/generator/honda/honda_civic_ex_2022_can.dbc @@ -49,6 +49,16 @@ BO_ 467 CRUISE_FAULT_STATUS: 8 XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX +BO_ 477 GEARBOX_ALT_2: 8 XXX + SG_ GEAR_MT : 39|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + +BO_ 495 SPEED_LIMIT_DASH_DISPLAY: 8 ADAS + SG_ SPEED_LIMIT : 47|8@0+ (1,0) [0|255] "mph" 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 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 @@ -89,7 +99,9 @@ BO_ 254913108 LKAS_HUD_2: 8 ADAS CM_ 446 "If exists, describes cruise faults and what the PCM uses for brake press detection."; CM_ SG_ 456 IDLESTOP_ALLOW "allows car to turn off engine at a standstill"; CM_ SG_ 456 STANDSTILL "set to 1 when camera requests -4.0 m/s^2"; +CM_ SG_ 495 SPEED_LIMIT "Defaults to 0xFF if no speed limit found"; VAL_ 401 GEAR_SHIFTER 32 "L" 16 "S" 8 "D" 4 "N" 2 "R" 1 "P"; VAL_ 401 GEAR 7 "L" 10 "S" 4 "D" 3 "N" 2 "R" 1 "P"; VAL_ 419 GEAR_SHIFTER 32 "D" 16 "N" 8 "R" 4 "P" 0 "B" ; +VAL_ 477 GEAR_MT 14 "reverse" 6 "6th" 5 "5th" 4 "4th" 3 "3rd" 2 "2nd" 1 "1st" 0 "Clutch"; diff --git a/opendbc/dbc/generator/toyota/_toyota_2017.dbc b/opendbc/dbc/generator/toyota/_toyota_2017.dbc index a8ff910771..52bf3eb575 100644 --- a/opendbc/dbc/generator/toyota/_toyota_2017.dbc +++ b/opendbc/dbc/generator/toyota/_toyota_2017.dbc @@ -149,7 +149,11 @@ BO_ 643 PRE_COLLISION: 7 DSU BO_ 705 GAS_PEDAL: 8 XXX SG_ GAS_RELEASED : 3|1@0+ (1,0) [0|1] "" XXX - SG_ GAS_PEDAL : 55|8@0+ (0.005,0) [0|1] "" XXX + SG_ ETQLVSC : 15|16@0- (0.03125,0) [0|0] "Nm" XXX + SG_ ETQREAL : 31|16@0- (0.03125,0) [0|0] "Nm" SCS + SG_ ETQISC : 47|8@0+ (1,-192) [0|0] "Nm" XXX + SG_ GAS_PEDAL : 55|8@0+ (0.5,0) [0|0] "%" DS1,FCM + SG_ CHECKSUM : 63|8@0+ (1,0) [0|0] "" DS1,FCM BO_ 740 STEERING_LKA: 5 XXX SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX diff --git a/opendbc/dbc/generator/toyota/toyota_rav4_prime.dbc b/opendbc/dbc/generator/toyota/toyota_rav4_prime.dbc index c60da2c289..3ad3da4373 100644 --- a/opendbc/dbc/generator/toyota/toyota_rav4_prime.dbc +++ b/opendbc/dbc/generator/toyota/toyota_rav4_prime.dbc @@ -97,7 +97,7 @@ BO_ 375 PCM_CRUISE_3: 8 XXX SG_ MSG_CNT_LOWER : 39|2@0+ (1,0) [0|3] "" XXX BO_ 387 ACC_CONTROL_2: 8 XXX - SG_ ACCEL_CMD : 7|16@0- (1,0) [0|65535] "" XXX + SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s^2" HCU SG_ AUTHENTICATOR : 35|28@0+ (1,0) [0|268435455] "" XXX SG_ RESET_FLAG : 37|2@0+ (1,0) [0|3] "" XXX SG_ MSG_CNT_LOWER : 39|2@0+ (1,0) [0|3] "" XXX diff --git a/opendbc/dbc/honda_accord_2018_can_generated.dbc b/opendbc/dbc/honda_accord_2018_can_generated.dbc index 85947333d5..ea9d30f3c8 100644 --- a/opendbc/dbc/honda_accord_2018_can_generated.dbc +++ b/opendbc/dbc/honda_accord_2018_can_generated.dbc @@ -322,12 +322,14 @@ BO_ 806 SCM_FEEDBACK: 8 SCM 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 : 7|16@0+ (1,0) [0|127] "" BDY + SG_ SPEED_LIMIT_SIGN : 23|8@0+ (1,0) [0|255] "" XXX + SG_ ROAD_SIGN : 31|8@0+ (1,0) [0|255] "" XXX SG_ ZEROS_BOH_2 : 51|4@0+ (1,0) [0|15] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ AUTO_HIGHBEAMS_ACTIVE : 53|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_ 927 RADAR_HUD: 8 RADAR SG_ ZEROS_BOH : 7|10@0+ (1,0) [0|127] "" BDY @@ -396,7 +398,8 @@ 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"; - +VAL_ 862 SPEED_LIMIT_SIGN 97 "SPEED_LIMIT_5" 98 "SPEED_LIMIT_10" 99 "SPEED_LIMIT_15" 100 "SPEED_LIMIT_20" 101 "SPEED_LIMIT_25" 102 "SPEED_LIMIT_30" 103 "SPEED_LIMIT_35" 104 "SPEED_LIMIT_40" 105 "SPEED_LIMIT_45" 106 "SPEED_LIMIT_50" 107 "SPEED_LIMIT_55" 108 "SPEED_LIMIT_60" 109 "SPEED_LIMIT_65" 110 "SPEED_LIMIT_70" 111 "SPEED_LIMIT_75" 112 "SPEED_LIMIT_80" 113 "SPEED_LIMIT_85" 125 "SPEED_LIMIT_NA" 0 "STOP_SIGN"; +VAL_ 862 ROAD_SIGN 0 "NO_SIGN" 89 "STOP_SIGN"; CM_ "Imported file _bosch_adas_2018.dbc starts here"; BO_ 479 ACC_CONTROL: 8 EON diff --git a/opendbc/dbc/honda_civic_ex_2022_can_generated.dbc b/opendbc/dbc/honda_civic_ex_2022_can_generated.dbc index 2e474f6fc0..7ec5b13278 100644 --- a/opendbc/dbc/honda_civic_ex_2022_can_generated.dbc +++ b/opendbc/dbc/honda_civic_ex_2022_can_generated.dbc @@ -322,12 +322,14 @@ BO_ 806 SCM_FEEDBACK: 8 SCM 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 : 7|16@0+ (1,0) [0|127] "" BDY + SG_ SPEED_LIMIT_SIGN : 23|8@0+ (1,0) [0|255] "" XXX + SG_ ROAD_SIGN : 31|8@0+ (1,0) [0|255] "" XXX SG_ ZEROS_BOH_2 : 51|4@0+ (1,0) [0|15] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ AUTO_HIGHBEAMS_ACTIVE : 53|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_ 927 RADAR_HUD: 8 RADAR SG_ ZEROS_BOH : 7|10@0+ (1,0) [0|127] "" BDY @@ -396,7 +398,8 @@ 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"; - +VAL_ 862 SPEED_LIMIT_SIGN 97 "SPEED_LIMIT_5" 98 "SPEED_LIMIT_10" 99 "SPEED_LIMIT_15" 100 "SPEED_LIMIT_20" 101 "SPEED_LIMIT_25" 102 "SPEED_LIMIT_30" 103 "SPEED_LIMIT_35" 104 "SPEED_LIMIT_40" 105 "SPEED_LIMIT_45" 106 "SPEED_LIMIT_50" 107 "SPEED_LIMIT_55" 108 "SPEED_LIMIT_60" 109 "SPEED_LIMIT_65" 110 "SPEED_LIMIT_70" 111 "SPEED_LIMIT_75" 112 "SPEED_LIMIT_80" 113 "SPEED_LIMIT_85" 125 "SPEED_LIMIT_NA" 0 "STOP_SIGN"; +VAL_ 862 ROAD_SIGN 0 "NO_SIGN" 89 "STOP_SIGN"; CM_ "Imported file _steering_sensors_a.dbc starts here"; BO_ 330 STEERING_SENSORS: 8 EPS @@ -458,6 +461,16 @@ BO_ 467 CRUISE_FAULT_STATUS: 8 XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX +BO_ 477 GEARBOX_ALT_2: 8 XXX + SG_ GEAR_MT : 39|4@0+ (1,0) [0|15] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + +BO_ 495 SPEED_LIMIT_DASH_DISPLAY: 8 ADAS + SG_ SPEED_LIMIT : 47|8@0+ (1,0) [0|255] "mph" 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 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 @@ -498,7 +511,9 @@ BO_ 254913108 LKAS_HUD_2: 8 ADAS CM_ 446 "If exists, describes cruise faults and what the PCM uses for brake press detection."; CM_ SG_ 456 IDLESTOP_ALLOW "allows car to turn off engine at a standstill"; CM_ SG_ 456 STANDSTILL "set to 1 when camera requests -4.0 m/s^2"; +CM_ SG_ 495 SPEED_LIMIT "Defaults to 0xFF if no speed limit found"; VAL_ 401 GEAR_SHIFTER 32 "L" 16 "S" 8 "D" 4 "N" 2 "R" 1 "P"; VAL_ 401 GEAR 7 "L" 10 "S" 4 "D" 3 "N" 2 "R" 1 "P"; VAL_ 419 GEAR_SHIFTER 32 "D" 16 "N" 8 "R" 4 "P" 0 "B" ; +VAL_ 477 GEAR_MT 14 "reverse" 6 "6th" 5 "5th" 4 "4th" 3 "3rd" 2 "2nd" 1 "1st" 0 "Clutch"; diff --git a/opendbc/dbc/honda_civic_hatchback_ex_2017_can_generated.dbc b/opendbc/dbc/honda_civic_hatchback_ex_2017_can_generated.dbc index 75ba176a8f..60000d88f6 100644 --- a/opendbc/dbc/honda_civic_hatchback_ex_2017_can_generated.dbc +++ b/opendbc/dbc/honda_civic_hatchback_ex_2017_can_generated.dbc @@ -322,12 +322,14 @@ BO_ 806 SCM_FEEDBACK: 8 SCM 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 : 7|16@0+ (1,0) [0|127] "" BDY + SG_ SPEED_LIMIT_SIGN : 23|8@0+ (1,0) [0|255] "" XXX + SG_ ROAD_SIGN : 31|8@0+ (1,0) [0|255] "" XXX SG_ ZEROS_BOH_2 : 51|4@0+ (1,0) [0|15] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ AUTO_HIGHBEAMS_ACTIVE : 53|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_ 927 RADAR_HUD: 8 RADAR SG_ ZEROS_BOH : 7|10@0+ (1,0) [0|127] "" BDY @@ -396,7 +398,8 @@ 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"; - +VAL_ 862 SPEED_LIMIT_SIGN 97 "SPEED_LIMIT_5" 98 "SPEED_LIMIT_10" 99 "SPEED_LIMIT_15" 100 "SPEED_LIMIT_20" 101 "SPEED_LIMIT_25" 102 "SPEED_LIMIT_30" 103 "SPEED_LIMIT_35" 104 "SPEED_LIMIT_40" 105 "SPEED_LIMIT_45" 106 "SPEED_LIMIT_50" 107 "SPEED_LIMIT_55" 108 "SPEED_LIMIT_60" 109 "SPEED_LIMIT_65" 110 "SPEED_LIMIT_70" 111 "SPEED_LIMIT_75" 112 "SPEED_LIMIT_80" 113 "SPEED_LIMIT_85" 125 "SPEED_LIMIT_NA" 0 "STOP_SIGN"; +VAL_ 862 ROAD_SIGN 0 "NO_SIGN" 89 "STOP_SIGN"; CM_ "Imported file _bosch_adas_2018.dbc starts here"; BO_ 479 ACC_CONTROL: 8 EON diff --git a/opendbc/dbc/honda_crv_ex_2017_can_generated.dbc b/opendbc/dbc/honda_crv_ex_2017_can_generated.dbc index 9f3dc0fba9..06ec21b248 100644 --- a/opendbc/dbc/honda_crv_ex_2017_can_generated.dbc +++ b/opendbc/dbc/honda_crv_ex_2017_can_generated.dbc @@ -322,12 +322,14 @@ BO_ 806 SCM_FEEDBACK: 8 SCM 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 : 7|16@0+ (1,0) [0|127] "" BDY + SG_ SPEED_LIMIT_SIGN : 23|8@0+ (1,0) [0|255] "" XXX + SG_ ROAD_SIGN : 31|8@0+ (1,0) [0|255] "" XXX SG_ ZEROS_BOH_2 : 51|4@0+ (1,0) [0|15] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ AUTO_HIGHBEAMS_ACTIVE : 53|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_ 927 RADAR_HUD: 8 RADAR SG_ ZEROS_BOH : 7|10@0+ (1,0) [0|127] "" BDY @@ -396,7 +398,8 @@ 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"; - +VAL_ 862 SPEED_LIMIT_SIGN 97 "SPEED_LIMIT_5" 98 "SPEED_LIMIT_10" 99 "SPEED_LIMIT_15" 100 "SPEED_LIMIT_20" 101 "SPEED_LIMIT_25" 102 "SPEED_LIMIT_30" 103 "SPEED_LIMIT_35" 104 "SPEED_LIMIT_40" 105 "SPEED_LIMIT_45" 106 "SPEED_LIMIT_50" 107 "SPEED_LIMIT_55" 108 "SPEED_LIMIT_60" 109 "SPEED_LIMIT_65" 110 "SPEED_LIMIT_70" 111 "SPEED_LIMIT_75" 112 "SPEED_LIMIT_80" 113 "SPEED_LIMIT_85" 125 "SPEED_LIMIT_NA" 0 "STOP_SIGN"; +VAL_ 862 ROAD_SIGN 0 "NO_SIGN" 89 "STOP_SIGN"; CM_ "Imported file _bosch_adas_2018.dbc starts here"; BO_ 479 ACC_CONTROL: 8 EON diff --git a/opendbc/dbc/honda_insight_ex_2019_can_generated.dbc b/opendbc/dbc/honda_insight_ex_2019_can_generated.dbc index ccbf25bfc7..cbb3d568d4 100644 --- a/opendbc/dbc/honda_insight_ex_2019_can_generated.dbc +++ b/opendbc/dbc/honda_insight_ex_2019_can_generated.dbc @@ -322,12 +322,14 @@ BO_ 806 SCM_FEEDBACK: 8 SCM 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 : 7|16@0+ (1,0) [0|127] "" BDY + SG_ SPEED_LIMIT_SIGN : 23|8@0+ (1,0) [0|255] "" XXX + SG_ ROAD_SIGN : 31|8@0+ (1,0) [0|255] "" XXX SG_ ZEROS_BOH_2 : 51|4@0+ (1,0) [0|15] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ AUTO_HIGHBEAMS_ACTIVE : 53|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_ 927 RADAR_HUD: 8 RADAR SG_ ZEROS_BOH : 7|10@0+ (1,0) [0|127] "" BDY @@ -396,7 +398,8 @@ 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"; - +VAL_ 862 SPEED_LIMIT_SIGN 97 "SPEED_LIMIT_5" 98 "SPEED_LIMIT_10" 99 "SPEED_LIMIT_15" 100 "SPEED_LIMIT_20" 101 "SPEED_LIMIT_25" 102 "SPEED_LIMIT_30" 103 "SPEED_LIMIT_35" 104 "SPEED_LIMIT_40" 105 "SPEED_LIMIT_45" 106 "SPEED_LIMIT_50" 107 "SPEED_LIMIT_55" 108 "SPEED_LIMIT_60" 109 "SPEED_LIMIT_65" 110 "SPEED_LIMIT_70" 111 "SPEED_LIMIT_75" 112 "SPEED_LIMIT_80" 113 "SPEED_LIMIT_85" 125 "SPEED_LIMIT_NA" 0 "STOP_SIGN"; +VAL_ 862 ROAD_SIGN 0 "NO_SIGN" 89 "STOP_SIGN"; CM_ "Imported file _bosch_adas_2018.dbc starts here"; BO_ 479 ACC_CONTROL: 8 EON diff --git a/opendbc/dbc/honda_pilot_2023_can_generated.dbc b/opendbc/dbc/honda_pilot_2023_can_generated.dbc index 91686e80b0..84cc64f01a 100644 --- a/opendbc/dbc/honda_pilot_2023_can_generated.dbc +++ b/opendbc/dbc/honda_pilot_2023_can_generated.dbc @@ -322,12 +322,14 @@ BO_ 806 SCM_FEEDBACK: 8 SCM 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 : 7|16@0+ (1,0) [0|127] "" BDY + SG_ SPEED_LIMIT_SIGN : 23|8@0+ (1,0) [0|255] "" XXX + SG_ ROAD_SIGN : 31|8@0+ (1,0) [0|255] "" XXX SG_ ZEROS_BOH_2 : 51|4@0+ (1,0) [0|15] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ AUTO_HIGHBEAMS_ACTIVE : 53|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_ 927 RADAR_HUD: 8 RADAR SG_ ZEROS_BOH : 7|10@0+ (1,0) [0|127] "" BDY @@ -396,7 +398,8 @@ 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"; - +VAL_ 862 SPEED_LIMIT_SIGN 97 "SPEED_LIMIT_5" 98 "SPEED_LIMIT_10" 99 "SPEED_LIMIT_15" 100 "SPEED_LIMIT_20" 101 "SPEED_LIMIT_25" 102 "SPEED_LIMIT_30" 103 "SPEED_LIMIT_35" 104 "SPEED_LIMIT_40" 105 "SPEED_LIMIT_45" 106 "SPEED_LIMIT_50" 107 "SPEED_LIMIT_55" 108 "SPEED_LIMIT_60" 109 "SPEED_LIMIT_65" 110 "SPEED_LIMIT_70" 111 "SPEED_LIMIT_75" 112 "SPEED_LIMIT_80" 113 "SPEED_LIMIT_85" 125 "SPEED_LIMIT_NA" 0 "STOP_SIGN"; +VAL_ 862 ROAD_SIGN 0 "NO_SIGN" 89 "STOP_SIGN"; CM_ "Imported file _steering_sensors_a.dbc starts here"; BO_ 330 STEERING_SENSORS: 8 EPS diff --git a/opendbc/dbc/tesla_model3_party.dbc b/opendbc/dbc/tesla_model3_party.dbc index c754c5114b..8fa1658691 100644 --- a/opendbc/dbc/tesla_model3_party.dbc +++ b/opendbc/dbc/tesla_model3_party.dbc @@ -1,333 +1,339 @@ -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_ 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 - -BO_ 785 UI_warning: 7 XXX - SG_ buckleStatus : 13|1@0+ (1,0) [0|1] "" XXX - SG_ leftBlinkerOn : 22|1@0+ (1,0) [0|1] "" XXX - SG_ rightBlinkerOn : 23|1@0+ (1,0) [0|1] "" XXX - SG_ anyDoorOpen : 28|1@0+ (1,0) [0|1] "" XXX - -BO_ 923 DAS_status: 8 PARTY - SG_ DAS_statusChecksum : 56|8@1+ (1,0) [0|255] "" aps - SG_ DAS_statusCounter : 52|4@1+ (1,0) [0|15] "" aps - SG_ DAS_summonAvailable : 51|1@1+ (1,0) [0|1] "" aps - SG_ DAS_autoLaneChangeState : 46|5@1+ (1,0) [0|31] "" aps - SG_ DAS_autopilotHandsOnState : 42|4@1+ (1,0) [0|15] "" aps - SG_ DAS_fleetSpeedState : 40|2@1+ (1,0) [0|3] "" aps - SG_ DAS_laneDepartureWarning : 37|3@1+ (1,0) [0|5] "" aps - SG_ DAS_csaState : 35|2@1+ (1,0) [0|3] "" aps - SG_ DAS_sideCollisionInhibit : 34|1@1+ (1,0) [0|1] "" aps - SG_ DAS_sideCollisionWarning : 32|2@1+ (1,0) [0|3] "" aps - SG_ DAS_sideCollisionAvoid : 30|2@1+ (1,0) [0|3] "" aps - SG_ DAS_summonRvsLeashReached : 29|1@1+ (1,0) [0|1] "" aps - SG_ DAS_summonFwdLeashReached : 28|1@1+ (1,0) [0|1] "" aps - SG_ DAS_autoparkWaitingForBrake : 26|1@1+ (1,0) [0|1] "" gtw - SG_ DAS_autoParked : 25|1@1+ (1,0) [0|1] "" aps - SG_ DAS_autoparkReady : 24|1@1+ (1,0) [0|1] "" aps - SG_ DAS_forwardCollisionWarning : 22|2@1+ (1,0) [0|3] "" aps - SG_ DAS_heaterState : 21|1@1+ (1,0) [0|1] "" gtw - SG_ DAS_visionOnlySpeedLimit : 16|5@1+ (5,0) [0|150] "kph/mph" aps - SG_ DAS_summonClearedGate : 15|1@1+ (1,0) [0|1] "" aps - SG_ DAS_summonObstacle : 14|1@1+ (1,0) [0|1] "" aps - SG_ DAS_suppressSpeedWarning : 13|1@1+ (1,0) [0|1] "" aps - SG_ DAS_fusedSpeedLimit : 8|5@1+ (5,0) [0|150] "kph/mph" aps - SG_ DAS_blindSpotRearRight : 6|2@1+ (1,0) [0|3] "" aps - SG_ DAS_blindSpotRearLeft : 4|2@1+ (1,0) [0|3] "" aps - SG_ DAS_autopilotState : 0|4@1+ (1,0) [0|15] "" aps - - - - - - - - -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" ; -VAL_ 785 buckleStatus 1 "LATCHED" 0 "UNLATCHED" ; -VAL_ 785 anyDoorOpen 1 "OPEN" 0 "CLOSED" ; -VAL_ 923 DAS_autoLaneChangeState 5 "ALC_UNAVAILABLE_VEHICLE_SPEED" 17 "ALC_ABORT_POOR_VIEW_RANGE" 23 "ALC_BLOCKED_VEH_TTC_AND_USS_L" 0 "ALC_UNAVAILABLE_DISABLED" 26 "ALC_BLOCKED_LANE_TYPE_L" 29 "ALC_ABORT_TIMEOUT" 9 "ALC_IN_PROGRESS_L" 4 "ALC_UNAVAILABLE_EXITING_HIGHWAY" 22 "ALC_BLOCKED_VEH_TTC_L" 12 "ALC_WAITING_FOR_SIDE_OBST_TO_PASS_R" 18 "ALC_ABORT_LC_HEALTH_BAD" 28 "ALC_WAITING_HANDS_ON" 8 "ALC_AVAILABLE_BOTH" 11 "ALC_WAITING_FOR_SIDE_OBST_TO_PASS_L" 3 "ALC_UNAVAILABLE_TP_FOLLOW" 2 "ALC_UNAVAILABLE_SONICS_INVALID" 21 "ALC_UNAVAILABLE_SOLID_LANE_LINE" 24 "ALC_BLOCKED_VEH_TTC_R" 1 "ALC_UNAVAILABLE_NO_LANES" 25 "ALC_BLOCKED_VEH_TTC_AND_USS_R" 30 "ALC_ABORT_MISSION_PLAN_INVALID" 27 "ALC_BLOCKED_LANE_TYPE_R" 19 "ALC_ABORT_BLINKER_TURNED_OFF" 31 "ALC_SNA" 13 "ALC_WAITING_FOR_FWD_OBST_TO_PASS_L" 16 "ALC_ABORT_SIDE_OBSTACLE_PRESENT_R" 6 "ALC_AVAILABLE_ONLY_L" 20 "ALC_ABORT_OTHER_REASON" 15 "ALC_ABORT_SIDE_OBSTACLE_PRESENT_L" 7 "ALC_AVAILABLE_ONLY_R" 14 "ALC_WAITING_FOR_FWD_OBST_TO_PASS_R" 10 "ALC_IN_PROGRESS_R" ; -VAL_ 923 DAS_autopilotHandsOnState 8 "LC_HANDS_ON_SUSPENDED" 15 "LC_HANDS_ON_SNA" 7 "LC_HANDS_ON_REQD_STRUCK_OUT" 3 "LC_HANDS_ON_REQD_VISUAL" 4 "LC_HANDS_ON_REQD_CHIME_1" 6 "LC_HANDS_ON_REQD_SLOWING" 1 "LC_HANDS_ON_REQD_DETECTED" 2 "LC_HANDS_ON_REQD_NOT_DETECTED" 5 "LC_HANDS_ON_REQD_CHIME_2" 0 "LC_HANDS_ON_NOT_REQD" ; -VAL_ 923 DAS_fleetSpeedState 0 "FLEETSPEED_UNAVAILABLE" 1 "FLEETSPEED_AVAILABLE" 2 "FLEETSPEED_ACTIVE" 3 "FLEETSPEED_HOLD" ; -VAL_ 923 DAS_laneDepartureWarning 5 "SNA" 0 "NONE" 2 "RIGHT_WARNING" 4 "RIGHT_WARNING_SEVERE" 3 "LEFT_WARNING_SEVERE" 1 "LEFT_WARNING" ; -VAL_ 923 DAS_csaState 1 "CSA_EXTERNAL_STATE_AVAILABLE" 3 "CSA_EXTERNAL_STATE_HOLD" 2 "CSA_EXTERNAL_STATE_ENABLE" 0 "CSA_EXTERNAL_STATE_UNAVAILABLE" ; -VAL_ 923 DAS_sideCollisionInhibit 0 "NO_INHIBIT" 1 "INHIBIT" ; -VAL_ 923 DAS_sideCollisionWarning 0 "NONE" 2 "WARN_RIGHT" 1 "WARN_LEFT" 3 "WARN_LEFT_RIGHT" ; -VAL_ 923 DAS_sideCollisionAvoid 3 "SNA" 0 "NONE" 1 "AVOID_LEFT" 2 "AVOID_RIGHT" ; -VAL_ 923 DAS_autoparkReady 0 "AUTOPARK_UNAVAILABLE" 1 "AUTOPARK_READY" ; -VAL_ 923 DAS_forwardCollisionWarning 3 "SNA" 0 "NONE" 1 "FORWARD_COLLISION_WARNING" ; -VAL_ 923 DAS_heaterState 0 "HEATER_OFF_SNA" 1 "HEATER_ON" ; -VAL_ 923 DAS_visionOnlySpeedLimit 31 "NONE" 0 "UNKNOWN_SNA" ; -VAL_ 923 DAS_suppressSpeedWarning 1 "Suppress_Speed_Warning" 0 "Do_Not_Suppress" ; -VAL_ 923 DAS_fusedSpeedLimit 31 "NONE" 0 "UNKNOWN_SNA" ; -VAL_ 923 DAS_blindSpotRearRight 3 "SNA" 0 "NO_WARNING" 1 "WARNING_LEVEL_1" 2 "WARNING_LEVEL_2" ; -VAL_ 923 DAS_blindSpotRearLeft 3 "SNA" 0 "NO_WARNING" 1 "WARNING_LEVEL_1" 2 "WARNING_LEVEL_2" ; -VAL_ 923 DAS_autopilotState 15 "SNA" 8 "ABORTING" 3 "ACTIVE_NOMINAL" 0 "DISABLED" 4 "ACTIVE_RESTRICTED" 5 "ACTIVE_NAV" 14 "FAULT" 1 "UNAVAILABLE" 9 "ABORTED" 2 "AVAILABLE" ; - - - +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_ 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.4,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_ 637 APS_eacMonitor: 3 PARTY + SG_ APS_eacAllow : 0|2@1+ (1,0) [0|0] "" X + SG_ APS_eacMonitorChecksum : 16|8@1+ (1,0) [0|0] "" X + SG_ APS_eacMonitorCounter : 8|4@1+ (1,0) [0|0] "" X + +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 + +BO_ 785 UI_warning: 7 XXX + SG_ buckleStatus : 13|1@0+ (1,0) [0|1] "" XXX + SG_ leftBlinkerOn : 22|1@0+ (1,0) [0|1] "" XXX + SG_ rightBlinkerOn : 23|1@0+ (1,0) [0|1] "" XXX + SG_ anyDoorOpen : 28|1@0+ (1,0) [0|1] "" XXX + +BO_ 923 DAS_status: 8 PARTY + SG_ DAS_statusChecksum : 56|8@1+ (1,0) [0|255] "" aps + SG_ DAS_statusCounter : 52|4@1+ (1,0) [0|15] "" aps + SG_ DAS_summonAvailable : 51|1@1+ (1,0) [0|1] "" aps + SG_ DAS_autoLaneChangeState : 46|5@1+ (1,0) [0|31] "" aps + SG_ DAS_autopilotHandsOnState : 42|4@1+ (1,0) [0|15] "" aps + SG_ DAS_fleetSpeedState : 40|2@1+ (1,0) [0|3] "" aps + SG_ DAS_laneDepartureWarning : 37|3@1+ (1,0) [0|5] "" aps + SG_ DAS_csaState : 35|2@1+ (1,0) [0|3] "" aps + SG_ DAS_sideCollisionInhibit : 34|1@1+ (1,0) [0|1] "" aps + SG_ DAS_sideCollisionWarning : 32|2@1+ (1,0) [0|3] "" aps + SG_ DAS_sideCollisionAvoid : 30|2@1+ (1,0) [0|3] "" aps + SG_ DAS_summonRvsLeashReached : 29|1@1+ (1,0) [0|1] "" aps + SG_ DAS_summonFwdLeashReached : 28|1@1+ (1,0) [0|1] "" aps + SG_ DAS_autoparkWaitingForBrake : 26|1@1+ (1,0) [0|1] "" gtw + SG_ DAS_autoParked : 25|1@1+ (1,0) [0|1] "" aps + SG_ DAS_autoparkReady : 24|1@1+ (1,0) [0|1] "" aps + SG_ DAS_forwardCollisionWarning : 22|2@1+ (1,0) [0|3] "" aps + SG_ DAS_heaterState : 21|1@1+ (1,0) [0|1] "" gtw + SG_ DAS_visionOnlySpeedLimit : 16|5@1+ (5,0) [0|150] "kph/mph" aps + SG_ DAS_summonClearedGate : 15|1@1+ (1,0) [0|1] "" aps + SG_ DAS_summonObstacle : 14|1@1+ (1,0) [0|1] "" aps + SG_ DAS_suppressSpeedWarning : 13|1@1+ (1,0) [0|1] "" aps + SG_ DAS_fusedSpeedLimit : 8|5@1+ (5,0) [0|150] "kph/mph" aps + SG_ DAS_blindSpotRearRight : 6|2@1+ (1,0) [0|3] "" aps + SG_ DAS_blindSpotRearLeft : 4|2@1+ (1,0) [0|3] "" aps + SG_ DAS_autopilotState : 0|4@1+ (1,0) [0|15] "" aps + + + + + + + + +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_ 637 APS_eacAllow 0 "INHIBIT" 1 "ALLOW" 2 "RESERVED" 3 "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" ; +VAL_ 785 buckleStatus 1 "LATCHED" 0 "UNLATCHED" ; +VAL_ 785 anyDoorOpen 1 "OPEN" 0 "CLOSED" ; +VAL_ 923 DAS_autoLaneChangeState 5 "ALC_UNAVAILABLE_VEHICLE_SPEED" 17 "ALC_ABORT_POOR_VIEW_RANGE" 23 "ALC_BLOCKED_VEH_TTC_AND_USS_L" 0 "ALC_UNAVAILABLE_DISABLED" 26 "ALC_BLOCKED_LANE_TYPE_L" 29 "ALC_ABORT_TIMEOUT" 9 "ALC_IN_PROGRESS_L" 4 "ALC_UNAVAILABLE_EXITING_HIGHWAY" 22 "ALC_BLOCKED_VEH_TTC_L" 12 "ALC_WAITING_FOR_SIDE_OBST_TO_PASS_R" 18 "ALC_ABORT_LC_HEALTH_BAD" 28 "ALC_WAITING_HANDS_ON" 8 "ALC_AVAILABLE_BOTH" 11 "ALC_WAITING_FOR_SIDE_OBST_TO_PASS_L" 3 "ALC_UNAVAILABLE_TP_FOLLOW" 2 "ALC_UNAVAILABLE_SONICS_INVALID" 21 "ALC_UNAVAILABLE_SOLID_LANE_LINE" 24 "ALC_BLOCKED_VEH_TTC_R" 1 "ALC_UNAVAILABLE_NO_LANES" 25 "ALC_BLOCKED_VEH_TTC_AND_USS_R" 30 "ALC_ABORT_MISSION_PLAN_INVALID" 27 "ALC_BLOCKED_LANE_TYPE_R" 19 "ALC_ABORT_BLINKER_TURNED_OFF" 31 "ALC_SNA" 13 "ALC_WAITING_FOR_FWD_OBST_TO_PASS_L" 16 "ALC_ABORT_SIDE_OBSTACLE_PRESENT_R" 6 "ALC_AVAILABLE_ONLY_L" 20 "ALC_ABORT_OTHER_REASON" 15 "ALC_ABORT_SIDE_OBSTACLE_PRESENT_L" 7 "ALC_AVAILABLE_ONLY_R" 14 "ALC_WAITING_FOR_FWD_OBST_TO_PASS_R" 10 "ALC_IN_PROGRESS_R" ; +VAL_ 923 DAS_autopilotHandsOnState 8 "LC_HANDS_ON_SUSPENDED" 15 "LC_HANDS_ON_SNA" 7 "LC_HANDS_ON_REQD_STRUCK_OUT" 3 "LC_HANDS_ON_REQD_VISUAL" 4 "LC_HANDS_ON_REQD_CHIME_1" 6 "LC_HANDS_ON_REQD_SLOWING" 1 "LC_HANDS_ON_REQD_DETECTED" 2 "LC_HANDS_ON_REQD_NOT_DETECTED" 5 "LC_HANDS_ON_REQD_CHIME_2" 0 "LC_HANDS_ON_NOT_REQD" ; +VAL_ 923 DAS_fleetSpeedState 0 "FLEETSPEED_UNAVAILABLE" 1 "FLEETSPEED_AVAILABLE" 2 "FLEETSPEED_ACTIVE" 3 "FLEETSPEED_HOLD" ; +VAL_ 923 DAS_laneDepartureWarning 5 "SNA" 0 "NONE" 2 "RIGHT_WARNING" 4 "RIGHT_WARNING_SEVERE" 3 "LEFT_WARNING_SEVERE" 1 "LEFT_WARNING" ; +VAL_ 923 DAS_csaState 1 "CSA_EXTERNAL_STATE_AVAILABLE" 3 "CSA_EXTERNAL_STATE_HOLD" 2 "CSA_EXTERNAL_STATE_ENABLE" 0 "CSA_EXTERNAL_STATE_UNAVAILABLE" ; +VAL_ 923 DAS_sideCollisionInhibit 0 "NO_INHIBIT" 1 "INHIBIT" ; +VAL_ 923 DAS_sideCollisionWarning 0 "NONE" 2 "WARN_RIGHT" 1 "WARN_LEFT" 3 "WARN_LEFT_RIGHT" ; +VAL_ 923 DAS_sideCollisionAvoid 3 "SNA" 0 "NONE" 1 "AVOID_LEFT" 2 "AVOID_RIGHT" ; +VAL_ 923 DAS_autoparkReady 0 "AUTOPARK_UNAVAILABLE" 1 "AUTOPARK_READY" ; +VAL_ 923 DAS_forwardCollisionWarning 3 "SNA" 0 "NONE" 1 "FORWARD_COLLISION_WARNING" ; +VAL_ 923 DAS_heaterState 0 "HEATER_OFF_SNA" 1 "HEATER_ON" ; +VAL_ 923 DAS_visionOnlySpeedLimit 31 "NONE" 0 "UNKNOWN_SNA" ; +VAL_ 923 DAS_suppressSpeedWarning 1 "Suppress_Speed_Warning" 0 "Do_Not_Suppress" ; +VAL_ 923 DAS_fusedSpeedLimit 31 "NONE" 0 "UNKNOWN_SNA" ; +VAL_ 923 DAS_blindSpotRearRight 3 "SNA" 0 "NO_WARNING" 1 "WARNING_LEVEL_1" 2 "WARNING_LEVEL_2" ; +VAL_ 923 DAS_blindSpotRearLeft 3 "SNA" 0 "NO_WARNING" 1 "WARNING_LEVEL_1" 2 "WARNING_LEVEL_2" ; +VAL_ 923 DAS_autopilotState 15 "SNA" 8 "ABORTING" 3 "ACTIVE_NOMINAL" 0 "DISABLED" 4 "ACTIVE_RESTRICTED" 5 "ACTIVE_NAV" 14 "FAULT" 1 "UNAVAILABLE" 9 "ABORTED" 2 "AVAILABLE" ; + + + diff --git a/opendbc/dbc/toyota_new_mc_pt_generated.dbc b/opendbc/dbc/toyota_new_mc_pt_generated.dbc index 1e1ce00a2e..c7de833c36 100644 --- a/opendbc/dbc/toyota_new_mc_pt_generated.dbc +++ b/opendbc/dbc/toyota_new_mc_pt_generated.dbc @@ -153,7 +153,11 @@ BO_ 643 PRE_COLLISION: 7 DSU BO_ 705 GAS_PEDAL: 8 XXX SG_ GAS_RELEASED : 3|1@0+ (1,0) [0|1] "" XXX - SG_ GAS_PEDAL : 55|8@0+ (0.005,0) [0|1] "" XXX + SG_ ETQLVSC : 15|16@0- (0.03125,0) [0|0] "Nm" XXX + SG_ ETQREAL : 31|16@0- (0.03125,0) [0|0] "Nm" SCS + SG_ ETQISC : 47|8@0+ (1,-192) [0|0] "Nm" XXX + SG_ GAS_PEDAL : 55|8@0+ (0.5,0) [0|0] "%" DS1,FCM + SG_ CHECKSUM : 63|8@0+ (1,0) [0|0] "" DS1,FCM BO_ 740 STEERING_LKA: 5 XXX SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX diff --git a/opendbc/dbc/toyota_nodsu_pt_generated.dbc b/opendbc/dbc/toyota_nodsu_pt_generated.dbc index 582768073c..f392713b6a 100644 --- a/opendbc/dbc/toyota_nodsu_pt_generated.dbc +++ b/opendbc/dbc/toyota_nodsu_pt_generated.dbc @@ -153,7 +153,11 @@ BO_ 643 PRE_COLLISION: 7 DSU BO_ 705 GAS_PEDAL: 8 XXX SG_ GAS_RELEASED : 3|1@0+ (1,0) [0|1] "" XXX - SG_ GAS_PEDAL : 55|8@0+ (0.005,0) [0|1] "" XXX + SG_ ETQLVSC : 15|16@0- (0.03125,0) [0|0] "Nm" XXX + SG_ ETQREAL : 31|16@0- (0.03125,0) [0|0] "Nm" SCS + SG_ ETQISC : 47|8@0+ (1,-192) [0|0] "Nm" XXX + SG_ GAS_PEDAL : 55|8@0+ (0.5,0) [0|0] "%" DS1,FCM + SG_ CHECKSUM : 63|8@0+ (1,0) [0|0] "" DS1,FCM BO_ 740 STEERING_LKA: 5 XXX SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX diff --git a/opendbc/dbc/toyota_rav4_prime_generated.dbc b/opendbc/dbc/toyota_rav4_prime_generated.dbc index 4d05d9f450..fb269f2430 100644 --- a/opendbc/dbc/toyota_rav4_prime_generated.dbc +++ b/opendbc/dbc/toyota_rav4_prime_generated.dbc @@ -100,7 +100,7 @@ BO_ 375 PCM_CRUISE_3: 8 XXX SG_ MSG_CNT_LOWER : 39|2@0+ (1,0) [0|3] "" XXX BO_ 387 ACC_CONTROL_2: 8 XXX - SG_ ACCEL_CMD : 7|16@0- (1,0) [0|65535] "" XXX + SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s^2" HCU SG_ AUTHENTICATOR : 35|28@0+ (1,0) [0|268435455] "" XXX SG_ RESET_FLAG : 37|2@0+ (1,0) [0|3] "" XXX SG_ MSG_CNT_LOWER : 39|2@0+ (1,0) [0|3] "" XXX diff --git a/opendbc/dbc/toyota_tnga_k_pt_generated.dbc b/opendbc/dbc/toyota_tnga_k_pt_generated.dbc index bb50dd0bc7..7b348acff5 100644 --- a/opendbc/dbc/toyota_tnga_k_pt_generated.dbc +++ b/opendbc/dbc/toyota_tnga_k_pt_generated.dbc @@ -153,7 +153,11 @@ BO_ 643 PRE_COLLISION: 7 DSU BO_ 705 GAS_PEDAL: 8 XXX SG_ GAS_RELEASED : 3|1@0+ (1,0) [0|1] "" XXX - SG_ GAS_PEDAL : 55|8@0+ (0.005,0) [0|1] "" XXX + SG_ ETQLVSC : 15|16@0- (0.03125,0) [0|0] "Nm" XXX + SG_ ETQREAL : 31|16@0- (0.03125,0) [0|0] "Nm" SCS + SG_ ETQISC : 47|8@0+ (1,-192) [0|0] "Nm" XXX + SG_ GAS_PEDAL : 55|8@0+ (0.5,0) [0|0] "%" DS1,FCM + SG_ CHECKSUM : 63|8@0+ (1,0) [0|0] "" DS1,FCM BO_ 740 STEERING_LKA: 5 XXX SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX