diff --git a/.gitignore b/.gitignore index 3e87dcc43..06c6117b1 100644 --- a/.gitignore +++ b/.gitignore @@ -1,4 +1,5 @@ venv/ +.env .clang-format .DS_Store .tags diff --git a/RELEASES.md b/RELEASES.md index 5d4f114b8..8564975f4 100644 --- a/RELEASES.md +++ b/RELEASES.md @@ -1,3 +1,25 @@ +Version 0.8.13 (2022-02-18) +======================== + * Improved driver monitoring + * Retuned driver pose learner for relaxed driving positions + * Added reliance on driving model to be more scene adaptive + * Matched strictness between comma two and comma three + * Improved performance in turns by compensating for the road bank angle + * Improved camera focus on the comma two + * AGNOS 4 + * ADB support + * improved cell auto configuration + * NEOS 19 + * package updates + * stability improvements + * Subaru ECU firmware fingerprinting thanks to martinl! + * Hyundai Santa Fe Plug-in Hybrid 2022 support thanks to sunnyhaibin! + * Mazda CX-5 2022 support thanks to Jafaral! + * Subaru Impreza 2020 support thanks to martinl! + * Toyota Avalon 2022 support thanks to sshane! + * Toyota Prius v 2017 support thanks to CT921! + * Volkswagen Caravelle 2020 support thanks to jyoung8607! + Version 0.8.12 (2021-12-15) ======================== * New driving model diff --git a/SConstruct b/SConstruct index 14450cec9..832550b14 100644 --- a/SConstruct +++ b/SConstruct @@ -66,7 +66,7 @@ lenv = { "LD_LIBRARY_PATH": [Dir(f"#third_party/acados/{arch}/lib").abspath], "PYTHONPATH": Dir("#").abspath + ":" + Dir("#pyextra/").abspath, - "ACADOS_SOURCE_DIR": Dir("#third_party/acados/acados").abspath, + "ACADOS_SOURCE_DIR": Dir("#third_party/acados/include/acados").abspath, "ACADOS_PYTHON_INTERFACE_PATH": Dir("#pyextra/acados_template").abspath, "TERA_PATH": Dir("#").abspath + f"/third_party/acados/{arch}/t_renderer", } @@ -125,14 +125,18 @@ else: f"#third_party/libyuv/{yuv_dir}/lib", "/usr/local/lib", "/opt/homebrew/lib", + "/usr/local/Homebrew/Library", "/usr/local/opt/openssl/lib", "/opt/homebrew/opt/openssl/lib", + "/usr/local/Cellar", + f"#third_party/acados/{arch}/lib", "/System/Library/Frameworks/OpenGL.framework/Libraries", ] cflags += ["-DGL_SILENCE_DEPRECATION"] cxxflags += ["-DGL_SILENCE_DEPRECATION"] cpppath += [ "/opt/homebrew/include", + "/usr/local/include", "/usr/local/opt/openssl/include", "/opt/homebrew/opt/openssl/include" ] @@ -234,6 +238,9 @@ env = Environment( tools=["default", "cython", "compilation_db"], ) +if arch == "Darwin": + env['RPATHPREFIX'] = "-rpath " + if GetOption('compile_db'): env.CompilationDatabase('compile_commands.json') @@ -298,6 +305,7 @@ if arch == "Darwin": qt_dirs += [f"{qt_env['QTDIR']}/include/Qt{m}" for m in qt_modules] qt_env["LINKFLAGS"] += ["-F" + os.path.join(qt_env['QTDIR'], "lib")] qt_env["FRAMEWORKS"] += [f"Qt{m}" for m in qt_modules] + ["OpenGL"] + qt_env.AppendENVPath('PATH', os.path.join(qt_env['QTDIR'], "bin")) elif arch == "aarch64": qt_env['QTDIR'] = "/system/comma/usr" qt_dirs = [ diff --git a/cereal/car.capnp b/cereal/car.capnp index 5c8c339b7..10f8578b4 100644 --- a/cereal/car.capnp +++ b/cereal/car.capnp @@ -69,7 +69,6 @@ struct CarEvent @0x9b1657f34caf3ad3 { preLaneChangeLeft @57; preLaneChangeRight @58; laneChange @59; - communityFeatureDisallowed @62; lowMemory @63; stockAeb @64; ldw @65; @@ -105,10 +104,12 @@ struct CarEvent @0x9b1657f34caf3ad3 { localizerMalfunction @103; highCpuUsage @105; cruiseMismatch @106; + lkasDisabled @107; - driverMonitorLowAccDEPRECATED @68; radarCanErrorDEPRECATED @15; + communityFeatureDisallowedDEPRECATED @62; radarCommIssueDEPRECATED @67; + driverMonitorLowAccDEPRECATED @68; gasUnavailableDEPRECATED @3; dataNeededDEPRECATED @16; modelCommIssueDEPRECATED @27; @@ -290,7 +291,14 @@ struct CarControl { enabled @0 :Bool; active @7 :Bool; + # Actuator commands as computed by controlsd actuators @6 :Actuators; + + # Any car specific rate limits or quirks applied by + # the CarController are reflected in actuatorsOutput + # and matches what is sent to the car + actuatorsOutput @10 :Actuators; + roll @8 :Float32; pitch @9 :Float32; @@ -299,12 +307,13 @@ struct CarControl { struct Actuators { # range from 0.0 - 1.0 - gasDEPRECATED @0: Float32; - brakeDEPRECATED @1: Float32; + gas @0: Float32; + brake @1: Float32; # range from -1.0 - 1.0 steer @2: Float32; steeringAngleDeg @3: Float32; + speed @6: Float32; # m/s accel @4: Float32; # m/s^2 longControlState @5: LongControlState; @@ -312,7 +321,8 @@ struct CarControl { off @0; pid @1; stopping @2; - starting @3; + + startingDEPRECATED @3; } } @@ -388,6 +398,7 @@ struct CarParams { minSteerSpeed @8 :Float32; maxSteeringAngleDeg @54 :Float32; safetyConfigs @62 :List(SafetyConfig); + unsafeMode @65 :Int16; steerMaxBP @11 :List(Float32); steerMaxV @12 :List(Float32); @@ -423,14 +434,11 @@ struct CarParams { vEgoStarting @59 :Float32; # Speed at which the car goes into starting state directAccelControl @30 :Bool; # Does the car have direct accel control or just gas/brake stoppingControl @31 :Bool; # Does the car allows full control even at lows speeds when stopping - startAccel @32 :Float32; # Required acceleraton to overcome creep braking stopAccel @60 :Float32; # Required acceleraton to keep vehicle stationary steerRateCost @33 :Float32; # Lateral MPC cost on steering rate steerControlType @34 :SteerControlType; radarOffCan @35 :Bool; # True when radar objects aren't visible on CAN - minSpeedCan @51 :Float32; # Minimum vehicle speed from CAN (below this value drops to 0) stoppingDecelRate @52 :Float32; # m/s^2/s while trying to stop - startingAccelRate @53 :Float32; # m/s^2/s while trying to start steerActuatorDelay @36 :Float32; # Steering wheel actuator delay in seconds longitudinalActuatorDelayLowerBound @61 :Float32; # Gas/Brake actuator delay in seconds, lower bound @@ -442,7 +450,6 @@ struct CarParams { carFw @44 :List(CarFw); radarTimeStep @45: Float32 = 0.05; # time delta between radar updates, 20Hz is very standard - communityFeature @46: Bool; # true if a community maintained feature is detected fingerprintSource @49: FingerprintSource; networkLocation @50 :NetworkLocation; # Where Panda/C2 is integrated into the car's CAN network @@ -590,9 +597,13 @@ struct CarParams { } enableCameraDEPRECATED @4 :Bool; - isPandaBlackDEPRECATED @39: Bool; + isPandaBlackDEPRECATED @39 :Bool; hasStockCameraDEPRECATED @57 :Bool; safetyParamDEPRECATED @10 :Int16; safetyModelDEPRECATED @9 :SafetyModel; safetyModelPassiveDEPRECATED @42 :SafetyModel = silent; + minSpeedCanDEPRECATED @51 :Float32; + startAccelDEPRECATED @32 :Float32; + communityFeatureDEPRECATED @46: Bool; + startingAccelRateDEPRECATED @53 :Float32; } diff --git a/cereal/log.capnp b/cereal/log.capnp index 473a9f6b8..6f4f43939 100644 --- a/cereal/log.capnp +++ b/cereal/log.capnp @@ -21,7 +21,6 @@ struct InitData { kernelVersion @15 :Text; osVersion @18 :Text; - gctx @1 :Text; dongleId @2 :Text; deviceType @3 :DeviceType; @@ -55,6 +54,7 @@ struct InitData { } # ***** deprecated stuff ***** + gctxDEPRECATED @1 :Text; androidBuildInfo @5 :AndroidBuildInfo; androidSensorsDEPRECATED @6 :List(AndroidSensor); chffrAndroidExtraDEPRECATED @7 :ChffrAndroidExtra; @@ -389,12 +389,14 @@ struct PandaState @0xa7649e2575e4591e { ignitionCan @13 :Bool; safetyModel @14 :Car.CarParams.SafetyModel; safetyParam @20 :Int16; + unsafeMode @23 :Int16; faultStatus @15 :FaultStatus; powerSaveEnabled @16 :Bool; uptime @17 :UInt32; faults @18 :List(FaultType); harnessStatus @21 :HarnessStatus; heartbeatLost @22 :Bool; + blockedCnt @24 :UInt32; enum FaultStatus { none @0; @@ -825,6 +827,8 @@ struct LongitudinalPlan @0xe00b5b3eba12876c { speeds @33 :List(Float32); jerks @34 :List(Float32); + solverExecutionTime @35 :Float32; + enum LongitudinalPlanSource { cruise @0; lead0 @1; @@ -886,6 +890,8 @@ struct LateralPlan @0xe1e9318e2ae8b51e { curvatures @27 :List(Float32); curvatureRates @28 :List(Float32); + solverExecutionTime @30 :Float32; + enum Desire { none @0; turnLeft @1; @@ -1321,6 +1327,7 @@ struct LiveParametersData { angleOffsetAverageStd @11 :Float32; stiffnessFactorStd @12 :Float32; steerRatioStd @13 :Float32; + roll @14 :Float32; } struct LiveMapDataDEPRECATED { @@ -1481,6 +1488,7 @@ struct Event { clocks @35 :Clocks; deviceState @6 :DeviceState; logMessage @18 :Text; + errorLogMessage @85 :Text; # navigation navInstruction @82 :NavInstruction; diff --git a/cereal/services.py b/cereal/services.py index 89f437359..c8fc3d5cc 100755 --- a/cereal/services.py +++ b/cereal/services.py @@ -35,18 +35,19 @@ services = { "liveTracks": (True, 20.), "sendcan": (True, 100., 139), "logMessage": (True, 0.), + "errorLogMessage": (True, 0., 1), "liveCalibration": (True, 4., 4), "androidLog": (True, 0.), "carState": (True, 100., 10), "carControl": (True, 100., 10), "longitudinalPlan": (True, 20., 5), "procLog": (True, 0.5), - "gpsLocationExternal": (True, 10., 1), + "gpsLocationExternal": (True, 10., 10), "ubloxGnss": (True, 10.), "clocks": (True, 1., 1), "ubloxRaw": (True, 20.), - "liveLocationKalman": (True, 20., 2), - "liveParameters": (True, 20., 2), + "liveLocationKalman": (True, 20., 5), + "liveParameters": (True, 20., 5), "cameraOdometry": (True, 20., 5), "lateralPlan": (True, 20., 5), "thumbnail": (True, 0.2, 1), diff --git a/common/ffi_wrapper.py b/common/ffi_wrapper.py index e6ee2c23f..a228b4025 100644 --- a/common/ffi_wrapper.py +++ b/common/ffi_wrapper.py @@ -28,7 +28,7 @@ def ffi_wrap(name, c_code, c_header, tmpdir="/tmp/ccache", cflags="", libraries= try: mod = __import__(cache) except Exception: - print("cache miss {0}".format(cache)) + print(f"cache miss {cache}") compile_code(cache, c_code, c_header, tmpdir, cflags, libraries) mod = __import__(cache) finally: diff --git a/common/file_helpers.py b/common/file_helpers.py index 2037a665b..592b2a199 100644 --- a/common/file_helpers.py +++ b/common/file_helpers.py @@ -35,7 +35,7 @@ def get_tmpdir_on_same_filesystem(path): if len(parts) > 1 and parts[1] == "scratch": return "/scratch/tmp" elif len(parts) > 2 and parts[2] == "runner": - return "/{}/runner/tmp".format(parts[1]) + return f"/{parts[1]}/runner/tmp" return "/tmp" @@ -81,6 +81,17 @@ def _get_fileobject_func(writer, temp_dir): return writer.get_fileobject(dir=temp_dir) return _get_fileobject +def monkeypatch_os_link(): + # This is neccesary on EON/C2, where os.link is patched out of python + if not hasattr(os, 'link'): + from cffi import FFI + ffi = FFI() + ffi.cdef("int link(const char *oldpath, const char *newpath);") + libc = ffi.dlopen(None) + + def link(src, dest): + return libc.link(src.encode(), dest.encode()) + os.link = link def atomic_write_on_fs_tmp(path, **kwargs): """Creates an atomic writer using a temporary file in a temporary directory @@ -88,6 +99,7 @@ def atomic_write_on_fs_tmp(path, **kwargs): """ # TODO(mgraczyk): This use of AtomicWriter relies on implementation details to set the temp # directory. + monkeypatch_os_link() writer = AtomicWriter(path, **kwargs) return writer._open(_get_fileobject_func(writer, get_tmpdir_on_same_filesystem(path))) @@ -96,5 +108,6 @@ def atomic_write_in_dir(path, **kwargs): """Creates an atomic writer using a temporary file in the same directory as the destination file. """ + monkeypatch_os_link() writer = AtomicWriter(path, **kwargs) return writer._open(_get_fileobject_func(writer, os.path.dirname(path))) diff --git a/common/numpy_fast.py b/common/numpy_fast.py index a8361214d..878c0005c 100644 --- a/common/numpy_fast.py +++ b/common/numpy_fast.py @@ -1,6 +1,3 @@ -def int_rnd(x): - return int(round(x)) - def clip(x, lo, hi): return max(lo, min(hi, x)) diff --git a/common/params_pyx.pyx b/common/params_pyx.pyx index 7b35e815d..a8c43c2f2 100755 --- a/common/params_pyx.pyx +++ b/common/params_pyx.pyx @@ -8,7 +8,6 @@ cdef extern from "selfdrive/common/params.h": cpdef enum ParamKeyType: PERSISTENT CLEAR_ON_MANAGER_START - CLEAR_ON_PANDA_DISCONNECT CLEAR_ON_IGNITION_ON CLEAR_ON_IGNITION_OFF ALL diff --git a/common/profiler.py b/common/profiler.py index e4d208aca..8b1a7a8cf 100644 --- a/common/profiler.py +++ b/common/profiler.py @@ -42,4 +42,4 @@ class Profiler(): print("%30s: %9.2f avg: %7.2f percent: %3.0f IGNORED" % (n, ms*1000.0, ms*1000.0/self.iter, ms/self.tot*100)) else: print("%30s: %9.2f avg: %7.2f percent: %3.0f" % (n, ms*1000.0, ms*1000.0/self.iter, ms/self.tot*100)) - print("Iter clock: %2.6f TOTAL: %2.2f" % (self.tot/self.iter, self.tot)) + print(f"Iter clock: {self.tot / self.iter:2.6f} TOTAL: {self.tot:2.2f}") diff --git a/common/realtime.py b/common/realtime.py index 762410f09..d577680ae 100644 --- a/common/realtime.py +++ b/common/realtime.py @@ -39,7 +39,7 @@ def set_realtime_priority(level: int) -> None: def set_core_affinity(core: int) -> None: if not PC: - os.sched_setaffinity(0, [core,]) + os.sched_setaffinity(0, [core,]) # type: ignore[attr-defined] def config_realtime_process(core: int, priority: int) -> None: @@ -79,7 +79,7 @@ class Ratekeeper: remaining = self._next_frame_time - sec_since_boot() self._next_frame_time += self._interval if self._print_delay_threshold is not None and remaining < -self._print_delay_threshold: - print("%s lagging by %.2f ms" % (self._process_name, -remaining * 1000)) + print(f"{self._process_name} lagging by {-remaining * 1000:.2f} ms") lagged = True self._frame += 1 self._remaining = remaining diff --git a/common/spinner.py b/common/spinner.py index 27b765196..57242d644 100644 --- a/common/spinner.py +++ b/common/spinner.py @@ -24,7 +24,7 @@ class Spinner(): except BrokenPipeError: pass - def update_progress(self, cur: int, total: int): + def update_progress(self, cur: float, total: float): self.update(str(round(100 * cur / total))) def close(self): diff --git a/common/timeout.py b/common/timeout.py index 4d424cdc0..d0b0ce063 100644 --- a/common/timeout.py +++ b/common/timeout.py @@ -12,7 +12,7 @@ class Timeout: """ def __init__(self, seconds, error_msg=None): if error_msg is None: - error_msg = 'Timed out after {} seconds'.format(seconds) + error_msg = f'Timed out after {seconds} seconds' self.seconds = seconds self.error_msg = error_msg diff --git a/common/transformations/camera.py b/common/transformations/camera.py index d71f865ca..7573877a3 100644 --- a/common/transformations/camera.py +++ b/common/transformations/camera.py @@ -125,7 +125,7 @@ def normalize(img_pts, intrinsics=fcam_intrinsics): return img_pts_normalized[:, :2].reshape(input_shape) -def denormalize(img_pts, intrinsics=fcam_intrinsics, width=W, height=H): +def denormalize(img_pts, intrinsics=fcam_intrinsics, width=np.inf, height=np.inf): # denormalizes image coordinates # accepts single pt or array of pts img_pts = np.array(img_pts) @@ -133,10 +133,12 @@ def denormalize(img_pts, intrinsics=fcam_intrinsics, width=W, height=H): img_pts = np.atleast_2d(img_pts) img_pts = np.hstack((img_pts, np.ones((img_pts.shape[0], 1), dtype=img_pts.dtype))) img_pts_denormalized = img_pts.dot(intrinsics.T) - img_pts_denormalized[img_pts_denormalized[:, 0] > width] = np.nan - img_pts_denormalized[img_pts_denormalized[:, 0] < 0] = np.nan - img_pts_denormalized[img_pts_denormalized[:, 1] > height] = np.nan - img_pts_denormalized[img_pts_denormalized[:, 1] < 0] = np.nan + if np.isfinite(width): + img_pts_denormalized[img_pts_denormalized[:, 0] > width] = np.nan + img_pts_denormalized[img_pts_denormalized[:, 0] < 0] = np.nan + if np.isfinite(height): + img_pts_denormalized[img_pts_denormalized[:, 1] > height] = np.nan + img_pts_denormalized[img_pts_denormalized[:, 1] < 0] = np.nan return img_pts_denormalized[:, :2].reshape(input_shape) diff --git a/docs/CARS.md b/docs/CARS.md index 9c762ee7b..5f14a9278 100644 --- a/docs/CARS.md +++ b/docs/CARS.md @@ -43,8 +43,9 @@ | Lexus | RX Hybrid 2016-19 | All | Stock3| 0mph | 0mph | | Lexus | RX Hybrid 2020-21 | All | openpilot | 0mph | 0mph | | Lexus | UX Hybrid 2019-21 | All | openpilot | 0mph | 0mph | -| Toyota | Alphard 2020 | All | openpilot | 0mph | 0mph | +| Toyota | Alphard 2019-20 | All | openpilot | 0mph | 0mph | | Toyota | Avalon 2016-21 | TSS-P | Stock3| 20mph1 | 0mph | +| Toyota | Avalon 2022 | All | openpilot | 0mph | 0mph | | Toyota | Avalon Hybrid 2019-21 | TSS-P | Stock3| 20mph1 | 0mph | | Toyota | Camry 2018-20 | All | Stock | 0mph4 | 0mph | | Toyota | Camry 2021-22 | All | openpilot | 0mph4 | 0mph | @@ -62,7 +63,8 @@ | Toyota | Highlander Hybrid 2020-22 | All | openpilot | 0mph | 0mph | | Toyota | Mirai 2021 | All | openpilot | 0mph | 0mph | | Toyota | Prius 2016-20 | TSS-P | Stock3| 0mph | 0mph | -| Toyota | Prius 2021 | All | openpilot | 0mph | 0mph | +| Toyota | Prius 2021-22 | All | openpilot | 0mph | 0mph | +| Toyota | Prius v 2017 | TSS-P | Stock3| 20mph1 | 0mph | | Toyota | Prius Prime 2017-20 | All | Stock3| 0mph | 0mph | | Toyota | Prius Prime 2021-22 | All | openpilot | 0mph | 0mph | | Toyota | Rav4 2016-18 | TSS-P | Stock3| 20mph1 | 0mph | @@ -78,98 +80,97 @@ ## Community Maintained Cars and Features -| Make | Model (US Market Reference) | Supported Package | ACC | No ACC accel below | No ALC below | -| ----------| ------------------------------| ------------------| -----------------| -------------------| -------------| -| Audi | A3 2014-19 | ACC + Lane Assist | Stock | 0mph | 0mph | -| Audi | A3 Sportback e-tron 2017-18 | ACC + Lane Assist | Stock | 0mph | 0mph | -| Audi | Q2 2018 | ACC + Lane Assist | Stock | 0mph | 0mph | -| Audi | Q3 2020-21 | ACC + Lane Assist | Stock | 0mph | 0mph | -| Audi | S3 2015 | ACC + Lane Assist | Stock | 0mph | 0mph | -| Buick | Regal 20181 | Adaptive Cruise | openpilot | 0mph | 7mph | -| Cadillac | ATS 20181 | Adaptive Cruise | openpilot | 0mph | 7mph | -| Cadillac | Escalade ESV 20161 | ACC + LKAS | openpilot | 0mph | 7mph | -| Chevrolet | Malibu 20171 | Adaptive Cruise | openpilot | 0mph | 7mph | -| Chevrolet | Volt 2017-181 | Adaptive Cruise | openpilot | 0mph | 7mph | -| Chrysler | Pacifica 2017-18 | Adaptive Cruise | Stock | 0mph | 9mph | -| Chrysler | Pacifica 2020 | Adaptive Cruise | Stock | 0mph | 39mph | -| Chrysler | Pacifica Hybrid 2017-18 | Adaptive Cruise | Stock | 0mph | 9mph | -| Chrysler | Pacifica Hybrid 2019-21 | Adaptive Cruise | Stock | 0mph | 39mph | -| Genesis | G70 2018 | All | Stock | 0mph | 0mph | -| Genesis | G70 2020 | All | Stock | 0mph | 0mph | -| Genesis | G80 2018 | All | Stock | 0mph | 0mph | -| Genesis | G90 2018 | All | Stock | 0mph | 0mph | -| GMC | Acadia 20181 | Adaptive Cruise | openpilot | 0mph | 7mph | -| Holden | Astra 20171 | Adaptive Cruise | openpilot | 0mph | 7mph | -| Hyundai | Elantra 2017-19 | SCC + LKAS | Stock | 19mph | 34mph | -| Hyundai | Elantra 2021 | SCC + LKAS | Stock | 0mph | 0mph | -| Hyundai | Elantra Hybrid 2021 | SCC + LKAS | Stock | 0mph | 0mph | -| Hyundai | Genesis 2015-16 | SCC + LKAS | Stock | 19mph | 37mph | -| Hyundai | Ioniq Electric 2019 | SCC + LKAS | Stock | 0mph | 32mph | -| Hyundai | Ioniq Electric 2020 | SCC + LKAS | Stock | 0mph | 0mph | -| Hyundai | Ioniq Hybrid 2017-19 | SCC + LKAS | Stock | 0mph | 32mph | -| Hyundai | Ioniq Hybrid 2020-22 | SCC + LFA | Stock | 0mph | 0mph | -| Hyundai | Ioniq PHEV 2020-21 | SCC + LKAS | Stock | 0mph | 0mph | -| Hyundai | Kona 2020 | SCC + LKAS | Stock | 0mph | 0mph | -| Hyundai | Kona EV 2018-19 | SCC + LKAS | Stock | 0mph | 0mph | -| Hyundai | Kona Hybrid 2020 | SCC + LKAS | Stock | 0mph | 0mph | -| Hyundai | Santa Fe 2019-20 | All | Stock | 0mph | 0mph | -| Hyundai | Santa Fe 2021-22 | All | Stock | 0mph | 0mph | -| Hyundai | Santa Fe Hybrid 2022 | All | Stock | 0mph | 0mph | -| Hyundai | Sonata 2018-2019 | SCC + LKAS | Stock | 0mph | 0mph | -| Hyundai | Sonata Hybrid 2021-22 | All | Stock | 0mph | 0mph | -| Hyundai | Veloster 2019-20 | SCC + LKAS | Stock | 5mph | 0mph | -| Jeep | Grand Cherokee 2016-18 | Adaptive Cruise | Stock | 0mph | 9mph | -| Jeep | Grand Cherokee 2019-20 | Adaptive Cruise | Stock | 0mph | 39mph | -| Kia | Ceed 2019 | SCC + LKAS | Stock | 0mph | 0mph | -| Kia | Forte 2018-21 | SCC + LKAS | Stock | 0mph | 0mph | -| Kia | K5 2021-22 | SCC + LFA | Stock | 0mph | 0mph | -| Kia | Niro EV 2019-21 | SCC + LKAS | Stock | 0mph | 0mph | -| Kia | Niro Hybrid 2021 | SCC + LKAS | Stock | 0mph | 0mph | -| Kia | Niro PHEV 2019 | SCC + LKAS | Stock | 10mph | 32mph | -| Kia | Optima 2017 | SCC + LKAS | Stock | 0mph | 32mph | -| Kia | Optima 2019 | SCC + LKAS | Stock | 0mph | 0mph | -| Kia | Seltos 2021 | SCC + LKAS | Stock | 0mph | 0mph | -| Kia | Sorento 2018-19 | SCC + LKAS | Stock | 0mph | 0mph | -| Kia | Stinger 2018 | SCC + LKAS | Stock | 0mph | 0mph | -| Kia | Telluride 2020 | SCC + LKAS | Stock | 0mph | 0mph | -| Mazda | CX-9 2021 | All | Stock | 0mph | 28mph | -| Nissan | Altima 2019-20 | ProPILOT | Stock | 0mph | 0mph | -| Nissan | Leaf 2018-22 | ProPILOT | Stock | 0mph | 0mph | -| Nissan | Rogue 2018-20 | ProPILOT | Stock | 0mph | 0mph | -| Nissan | X-Trail 2017 | ProPILOT | Stock | 0mph | 0mph | -| SEAT | Ateca 2018 | Driver Assistance | Stock | 0mph | 0mph | -| SEAT | Leon 2014-2020 | Driver Assistance | Stock | 0mph | 0mph | -| Škoda | Kamiq 20212 | Driver Assistance | Stock | 0mph | 0mph | -| Škoda | Karoq 2019 | Driver Assistance | Stock | 0mph | 0mph | -| Škoda | Kodiaq 2018-19 | Driver Assistance | Stock | 0mph | 0mph | -| Škoda | Octavia 2015, 2018-19 | Driver Assistance | Stock | 0mph | 0mph | -| Škoda | Octavia RS 2016 | Driver Assistance | Stock | 0mph | 0mph | -| Škoda | Scala 2020 | Driver Assistance | Stock | 0mph | 0mph | -| Škoda | Superb 2015-18 | Driver Assistance | Stock | 0mph | 0mph | -| Subaru | Ascent 2019 | EyeSight | Stock | 0mph | 0mph | -| Subaru | Crosstrek 2018-19 | EyeSight | Stock | 0mph | 0mph | -| Subaru | Forester 2019-21 | EyeSight | Stock | 0mph | 0mph | -| Subaru | Impreza 2017-19 | EyeSight | Stock | 0mph | 0mph | -| Volkswagen| Arteon 20214 | Driver Assistance | Stock | 0mph | 0mph | -| Volkswagen| Atlas 2018-19 | Driver Assistance | Stock | 0mph | 0mph | -| Volkswagen| California 20214 | Driver Assistance | Stock | 0mph | 32mph | -| Volkswagen| e-Golf 2014, 2019-20 | Driver Assistance | Stock | 0mph | 0mph | -| Volkswagen| Golf 2015-20 | Driver Assistance | Stock | 0mph | 0mph | -| Volkswagen| Golf Alltrack 2017-18 | Driver Assistance | Stock | 0mph | 0mph | -| Volkswagen| Golf GTE 2016 | Driver Assistance | Stock | 0mph | 0mph | -| Volkswagen| Golf GTI 2018-20 | Driver Assistance | Stock | 0mph | 0mph | -| Volkswagen| Golf R 2016-19 | Driver Assistance | Stock | 0mph | 0mph | -| Volkswagen| Golf SportsVan 2016 | Driver Assistance | Stock | 0mph | 0mph | -| Volkswagen| Golf SportWagen 2015 | Driver Assistance | Stock | 0mph | 0mph | -| Volkswagen| Jetta 2018-20 | Driver Assistance | Stock | 0mph | 0mph | -| Volkswagen| Jetta GLI 2021 | Driver Assistance | Stock | 0mph | 0mph | -| Volkswagen| Passat 2016-183 | Driver Assistance | Stock | 0mph | 0mph | -| Volkswagen| Polo 2020 | Driver Assistance | Stock | 0mph | 0mph | -| Volkswagen| T-Cross 20214 | Driver Assistance | Stock | 0mph | 0mph | -| Volkswagen| T-Roc 20214 | Driver Assistance | Stock | 0mph | 0mph | -| Volkswagen| Taos 20224 | Driver Assistance | Stock | 0mph | 0mph | -| Volkswagen| Tiguan 2020 | Driver Assistance | Stock | 0mph | 0mph | -| Volkswagen| Touran 2017 | Driver Assistance | Stock | 0mph | 0mph | +| Make | Model (US Market Reference) | Supported Package | ACC | No ACC accel below | No ALC below | +| ----------| --------------------------------| ------------------| -----------------| -------------------| -------------| +| Audi | A3 2014-19 | ACC + Lane Assist | Stock | 0mph | 0mph | +| Audi | A3 Sportback e-tron 2017-18 | ACC + Lane Assist | Stock | 0mph | 0mph | +| Audi | Q2 2018 | ACC + Lane Assist | Stock | 0mph | 0mph | +| Audi | Q3 2020-21 | ACC + Lane Assist | Stock | 0mph | 0mph | +| Audi | S3 2015 | ACC + Lane Assist | Stock | 0mph | 0mph | +| Cadillac | Escalade ESV 20161 | ACC + LKAS | openpilot | 0mph | 7mph | +| Chevrolet | Volt 2017-181 | Adaptive Cruise | openpilot | 0mph | 7mph | +| Chrysler | Pacifica 2017-18 | Adaptive Cruise | Stock | 0mph | 9mph | +| Chrysler | Pacifica 2020 | Adaptive Cruise | Stock | 0mph | 39mph | +| Chrysler | Pacifica Hybrid 2017-18 | Adaptive Cruise | Stock | 0mph | 9mph | +| Chrysler | Pacifica Hybrid 2019-21 | Adaptive Cruise | Stock | 0mph | 39mph | +| Genesis | G70 2018 | All | Stock | 0mph | 0mph | +| Genesis | G70 2020 | All | Stock | 0mph | 0mph | +| Genesis | G80 2018 | All | Stock | 0mph | 0mph | +| Genesis | G90 2018 | All | Stock | 0mph | 0mph | +| GMC | Acadia 20181 | Adaptive Cruise | openpilot | 0mph | 7mph | +| Hyundai | Elantra 2017-19 | SCC + LKAS | Stock | 19mph | 34mph | +| Hyundai | Elantra 2021 | SCC + LKAS | Stock | 0mph | 0mph | +| Hyundai | Elantra Hybrid 2021 | SCC + LKAS | Stock | 0mph | 0mph | +| Hyundai | Genesis 2015-16 | SCC + LKAS | Stock | 19mph | 37mph | +| Hyundai | Ioniq Electric 2019 | SCC + LKAS | Stock | 0mph | 32mph | +| Hyundai | Ioniq Electric 2020 | SCC + LKAS | Stock | 0mph | 0mph | +| Hyundai | Ioniq Hybrid 2017-19 | SCC + LKAS | Stock | 0mph | 32mph | +| Hyundai | Ioniq Hybrid 2020-22 | SCC + LFA | Stock | 0mph | 0mph | +| Hyundai | Ioniq PHEV 2020-21 | SCC + LKAS | Stock | 0mph | 0mph | +| Hyundai | Kona 2020 | SCC + LKAS | Stock | 0mph | 0mph | +| Hyundai | Kona EV 2018-19 | SCC + LKAS | Stock | 0mph | 0mph | +| Hyundai | Kona Hybrid 2020 | SCC + LKAS | Stock | 0mph | 0mph | +| Hyundai | Santa Fe 2019-20 | All | Stock | 0mph | 0mph | +| Hyundai | Santa Fe 2021-22 | All | Stock | 0mph | 0mph | +| Hyundai | Santa Fe Hybrid 2022 | All | Stock | 0mph | 0mph | +| Hyundai | Santa Fe Plug-in Hybrid 2022 | All | Stock | 0mph | 0mph | +| Hyundai | Sonata 2018-2019 | SCC + LKAS | Stock | 0mph | 0mph | +| Hyundai | Sonata Hybrid 2021-22 | All | Stock | 0mph | 0mph | +| Hyundai | Veloster 2019-20 | SCC + LKAS | Stock | 5mph | 0mph | +| Jeep | Grand Cherokee 2016-18 | Adaptive Cruise | Stock | 0mph | 9mph | +| Jeep | Grand Cherokee 2019-20 | Adaptive Cruise | Stock | 0mph | 39mph | +| Kia | Ceed 2019 | SCC + LKAS | Stock | 0mph | 0mph | +| Kia | Forte 2018-21 | SCC + LKAS | Stock | 0mph | 0mph | +| Kia | K5 2021-22 | SCC + LFA | Stock | 0mph | 0mph | +| Kia | Niro EV 2019-22 | All | Stock | 0mph | 0mph | +| Kia | Niro Hybrid 2021 | SCC + LKAS | Stock | 0mph | 0mph | +| Kia | Niro PHEV 2019 | SCC + LKAS | Stock | 10mph | 32mph | +| Kia | Optima 2017 | SCC + LKAS | Stock | 0mph | 32mph | +| Kia | Optima 2019 | SCC + LKAS | Stock | 0mph | 0mph | +| Kia | Seltos 2021 | SCC + LKAS | Stock | 0mph | 0mph | +| Kia | Sorento 2018-19 | SCC + LKAS | Stock | 0mph | 0mph | +| Kia | Stinger 2018 | SCC + LKAS | Stock | 0mph | 0mph | +| Kia | Telluride 2020 | SCC + LKAS | Stock | 0mph | 0mph | +| Mazda | CX-5 2022 | All | Stock | 0mph | 0mph | +| Mazda | CX-9 2021 | All | Stock | 0mph | 28mph | +| Nissan | Altima 2019-20 | ProPILOT | Stock | 0mph | 0mph | +| Nissan | Leaf 2018-22 | ProPILOT | Stock | 0mph | 0mph | +| Nissan | Rogue 2018-20 | ProPILOT | Stock | 0mph | 0mph | +| Nissan | X-Trail 2017 | ProPILOT | Stock | 0mph | 0mph | +| SEAT | Ateca 2018 | Driver Assistance | Stock | 0mph | 0mph | +| SEAT | Leon 2014-2020 | Driver Assistance | Stock | 0mph | 0mph | +| Subaru | Ascent 2019 | EyeSight | Stock | 0mph | 0mph | +| Subaru | Crosstrek 2018-20 | EyeSight | Stock | 0mph | 0mph | +| Subaru | Forester 2019-21 | EyeSight | Stock | 0mph | 0mph | +| Subaru | Impreza 2017-19 | EyeSight | Stock | 0mph | 0mph | +| Škoda | Kamiq 20212 | Driver Assistance | Stock | 0mph | 0mph | +| Škoda | Karoq 2019 | Driver Assistance | Stock | 0mph | 0mph | +| Škoda | Kodiaq 2018-19 | Driver Assistance | Stock | 0mph | 0mph | +| Škoda | Octavia 2015, 2018-19 | Driver Assistance | Stock | 0mph | 0mph | +| Škoda | Octavia RS 2016 | Driver Assistance | Stock | 0mph | 0mph | +| Škoda | Scala 2020 | Driver Assistance | Stock | 0mph | 0mph | +| Škoda | Superb 2015-18 | Driver Assistance | Stock | 0mph | 0mph | +| Volkswagen| Arteon 2018, 20214 | Driver Assistance | Stock | 0mph | 0mph | +| Volkswagen| Atlas 2018-19, 20224 | Driver Assistance | Stock | 0mph | 0mph | +| Volkswagen| Caravelle 20204 | Driver Assistance | Stock | 0mph | 32mph | +| Volkswagen| California 20214 | Driver Assistance | Stock | 0mph | 32mph | +| Volkswagen| e-Golf 2014, 2019-20 | Driver Assistance | Stock | 0mph | 0mph | +| Volkswagen| Golf 2015-20 | Driver Assistance | Stock | 0mph | 0mph | +| Volkswagen| Golf Alltrack 2017-18 | Driver Assistance | Stock | 0mph | 0mph | +| Volkswagen| Golf GTE 2016 | Driver Assistance | Stock | 0mph | 0mph | +| Volkswagen| Golf GTI 2018-20 | Driver Assistance | Stock | 0mph | 0mph | +| Volkswagen| Golf R 2016-19 | Driver Assistance | Stock | 0mph | 0mph | +| Volkswagen| Golf SportsVan 2016 | Driver Assistance | Stock | 0mph | 0mph | +| Volkswagen| Golf SportWagen 2015 | Driver Assistance | Stock | 0mph | 0mph | +| Volkswagen| Jetta 2018-20 | Driver Assistance | Stock | 0mph | 0mph | +| Volkswagen| Jetta GLI 2021 | Driver Assistance | Stock | 0mph | 0mph | +| Volkswagen| Passat 2016-183 | Driver Assistance | Stock | 0mph | 0mph | +| Volkswagen| Polo 2020 | Driver Assistance | Stock | 0mph | 0mph | +| Volkswagen| T-Cross 20214 | Driver Assistance | Stock | 0mph | 0mph | +| Volkswagen| T-Roc 20214 | Driver Assistance | Stock | 0mph | 0mph | +| Volkswagen| Taos 20224 | Driver Assistance | Stock | 0mph | 0mph | +| Volkswagen| Tiguan 2020 | Driver Assistance | Stock | 0mph | 0mph | +| Volkswagen| Touran 2017 | Driver Assistance | Stock | 0mph | 0mph | 1Requires an [OBD-II car harness](https://comma.ai/shop/products/comma-car-harness) and [community built ASCM harness](https://github.com/commaai/openpilot/wiki/GM#hardware). ***NOTE: disconnecting the ASCM disables Automatic Emergency Braking (AEB).***
2Not including the China market Kamiq, which is based on the (currently) unsupported PQ34 platform.
diff --git a/docs/CONTRIBUTING.md b/docs/CONTRIBUTING.md index b9da6c576..7a074f12d 100644 --- a/docs/CONTRIBUTING.md +++ b/docs/CONTRIBUTING.md @@ -11,6 +11,13 @@ Most open source development activity is coordinated through our [GitHub Discuss * Make sure you have a [GitHub account](https://github.com/signup/free) * Fork [our repositories](https://github.com/commaai) on GitHub +### First contribution +Try out some of these first pull requests ideas to dive into the codebase: + +* Increase our [mypy](http://mypy-lang.org/) coverage +* Write some documentation +* Tackle an open [good first issue](https://github.com/commaai/openpilot/issues?q=is%3Aissue+is%3Aopen+label%3A%22good+first+issue%22) + ## Pull Requests Pull requests should be against the master branch. Welcomed contributions include bug reports, car ports, and any [open issue](https://github.com/commaai/openpilot/issues). If you're unsure about a contribution, feel free to open a discussion, issue, or draft PR to discuss the problem you're trying to solve. diff --git a/launch_env.sh b/launch_env.sh index cb0a0572d..cd0c27f64 100755 --- a/launch_env.sh +++ b/launch_env.sh @@ -7,11 +7,11 @@ export OPENBLAS_NUM_THREADS=1 export VECLIB_MAXIMUM_THREADS=1 if [ -z "$REQUIRED_NEOS_VERSION" ]; then - export REQUIRED_NEOS_VERSION="18" + export REQUIRED_NEOS_VERSION="19.1" fi if [ -z "$AGNOS_VERSION" ]; then - export AGNOS_VERSION="3" + export AGNOS_VERSION="4" fi if [ -z "$PASSIVE" ]; then diff --git a/opendbc/acura_ilx_2016_can_generated.dbc b/opendbc/acura_ilx_2016_can_generated.dbc index 065fe7d5a..56770bca2 100644 --- a/opendbc/acura_ilx_2016_can_generated.dbc +++ b/opendbc/acura_ilx_2016_can_generated.dbc @@ -1,41 +1,36 @@ CM_ "AUTOGENERATED FILE, DO NOT EDIT"; -CM_ "Imported file _honda_2017.dbc starts here"; -VERSION "" +CM_ "Imported file _comma.dbc starts here"; +BO_ 512 GAS_COMMAND: 6 EON + SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR + SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR + SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR + SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR + SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR + +BO_ 513 GAS_SENSOR: 6 INTERCEPTOR + SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON + SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON + SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON + SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON + +VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; -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_ +CM_ "Imported file _honda_common.dbc starts here"; +BO_ 304 GAS_PEDAL_2: 8 PCM + SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON -BU_: EBCM ADAS PCM EPS VSA SCM BDY XXX EPB EON +BO_ 316 GAS_PEDAL: 8 PCM + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON BO_ 344 ENGINE_DATA: 8 PCM SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" EON @@ -49,14 +44,14 @@ BO_ 380 POWERTRAIN_DATA: 8 PCM SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" EON SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" EON - SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "rpm" EON - SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "rpm" EON - SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "rpm" EON - SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "rpm" EON + SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "" EON + SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "" EON + SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "" EON + SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "" EON SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" EON - SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "rpm" EON + SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "" EON SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON BO_ 420 VSA_STATUS: 8 VSA SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON @@ -75,14 +70,6 @@ BO_ 427 STEER_MOTOR_TORQUE: 3 EPS SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" EON -BO_ 432 STANDSTILL: 7 VSA - SG_ CONTROLLED_STANDSTILL : 0|1@0+ (1,0) [0|1] "" EON - SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON - SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON - SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON - BO_ 464 WHEEL_SPEEDS: 8 VSA SG_ WHEEL_SPEED_FL : 7|15@0+ (0.01,0) [0|250] "kph" EON SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON @@ -91,10 +78,120 @@ BO_ 464 WHEEL_SPEEDS: 8 VSA SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON BO_ 490 VEHICLE_DYNAMICS: 8 VSA - SG_ LONG_ACCEL : 23|16@0- (0.0015384,0) [-20|20] "m/s2" EON + SG_ LAT_ACCEL : 7|16@0- (0.0015,0) [-20|20] "m/s2" EON + SG_ LONG_ACCEL : 23|16@0- (0.0015,0) [-20|20] "m/s2" EON SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON +BO_ 773 SEATBELT_STATUS: 7 BDY + SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 804 CRUISE: 8 PCM + SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" EON + SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" EON + SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON + SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" EON + SG_ BOH2 : 47|8@0- (1,0) [0|255] "" EON + SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 829 LKAS_HUD: 5 ADAS + SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY + SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY + SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY + SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY + SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY + SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY + SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY + SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY + SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY + SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY + SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY + +BO_ 884 STALK_STATUS: 8 XXX + SG_ DASHBOARD_ALERT : 39|8@0+ (1,0) [0|255] "" EON + SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON + SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON + SG_ WIPER_SWITCH : 53|2@0+ (1,0) [0|3] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 891 STALK_STATUS_2: 8 XXX + SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON + SG_ LOW_BEAMS : 35|1@0+ (1,0) [0|1] "" XXX + SG_ HIGH_BEAMS : 34|1@0+ (1,0) [0|1] "" XXX + SG_ PARK_LIGHTS : 36|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 1029 DOORS_STATUS: 8 BDY + SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" EON + SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +CM_ SG_ 304 "Seems to be platform-agnostic"; +CM_ SG_ 316 "Should exist on Nidec"; +CM_ SG_ 420 BRAKE_HOLD_RELATED "On when Brake Hold engaged"; +CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; +CM_ SG_ 773 PASS_AIRBAG_ON "Might just be indicator light"; +CM_ SG_ 773 PASS_AIRBAG_OFF "Might just be indicator light"; +CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; +CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; + +VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep"; +VAL_ 884 DASHBOARD_ALERT 0 "none" 51 "acc_problem" 55 "cmbs_problem" 75 "key_not_detected" 79 "fasten_seatbelt" 111 "lkas_problem" 131 "brake_system_problem" 132 "brake_hold_problem" 139 "tbd" 161 "door_open"; +VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off"; + + +CM_ "Imported file _honda_2017.dbc starts here"; +BO_ 145 KINEMATICS: 8 XXX + SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 148 KINEMATICS_ALT: 8 XXX + SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON + SG_ LONG_ACCEL : 24|9@0- (-0.02,0) [-20|20] "m/s2" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +BO_ 432 STANDSTILL: 7 VSA + SG_ CONTROLLED_STANDSTILL : 0|1@0+ (1,0) [0|1] "" EON + SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 487 BRAKE_PRESSURE: 4 VSA + SG_ BRAKE_PRESSURE1 : 7|10@0+ (0.015625,-103) [0|1000] "" EON + SG_ BRAKE_PRESSURE2 : 9|10@0+ (0.015625,-103) [0|1000] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON + BO_ 506 BRAKE_COMMAND: 8 ADAS SG_ COMPUTER_BRAKE : 7|10@0+ (1,0) [0|1] "" EBCM SG_ SET_ME_X00 : 13|5@0+ (1,0) [0|1] "" EBCM @@ -128,17 +225,6 @@ BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON -BO_ 773 SEATBELT_STATUS: 7 BDY - SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON - SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON - SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON - BO_ 777 LOCK_STATUS: 8 XXX SG_ DOORS_UNLOCKED : 54|1@0+ (1,0) [0|1] "" EON SG_ DOORS_LOCKED : 55|1@0+ (1,0) [0|1] "" EON @@ -172,92 +258,22 @@ BO_ 780 ACC_HUD: 8 ADAS SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY -BO_ 804 CRUISE: 8 PCM - SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" EON - SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" EON - SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON - SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" EON - SG_ BOH2 : 47|8@0- (1,0) [0|255] "" EON - SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - -BO_ 829 LKAS_HUD: 5 ADAS - SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY - SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY - SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY - SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY - SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY - SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY - SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY - SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY - SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY - SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY - SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY - SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY - SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY - SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY - SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY - BO_ 892 CRUISE_PARAMS: 8 PCM SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" EON SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON -BO_ 1029 DOORS_STATUS: 8 BDY - SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" EON - SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" EON - SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" EON - SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" EON - SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - -CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; CM_ SG_ 506 AEB_REQ_1 "set for duration of suspected AEB event"; -CM_ SG_ 773 PASS_AIRBAG_ON "Might just be indicator light"; -CM_ SG_ 773 PASS_AIRBAG_OFF "Might just be indicator light"; CM_ SG_ 780 CRUISE_SPEED "255 = no speed"; -CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; -CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; - -VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw" ; -VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime" ; -VAL_ 506 AEB_STATUS 3 "aeb_prepare" 2 "aeb_ready" 1 "aeb_braking" 0 "no_aeb" ; -VAL_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped" ; -VAL_ 780 HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car" ; -VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; - - -CM_ "Imported file _comma.dbc starts here"; -BO_ 512 GAS_COMMAND: 6 EON - SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR - SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR - SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR - -BO_ 513 GAS_SENSOR: 6 INTERCEPTOR - SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON - SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON - SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON - -VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; +VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw"; +VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime"; +VAL_ 506 AEB_STATUS 3 "aeb_prepare" 2 "aeb_ready" 1 "aeb_braking" 0 "no_aeb"; +VAL_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped"; +VAL_ 780 HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car"; CM_ "acura_ilx_2016_can.dbc starts here"; - - -BO_ 145 KINEMATICS: 8 XXX - SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON - BO_ 228 STEERING_CONTROL: 5 ADAS SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS @@ -265,14 +281,6 @@ BO_ 228 STEERING_CONTROL: 5 ADAS SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" EPS -BO_ 304 GAS_PEDAL_2: 8 PCM - SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON - SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON - SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON - -BO_ 316 GAS_PEDAL: 8 PCM - SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON - BO_ 342 STEERING_SENSORS: 6 EPS SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON SG_ STEER_ANGLE_RATE : 23|16@0- (-1,0) [-3000|3000] "deg/s" EON @@ -308,10 +316,7 @@ BO_ 660 SCM_FEEDBACK: 8 SCM SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" EON CM_ SG_ 419 GEAR "10 = reverse, 11 = transition"; -CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; CM_ SG_ 780 CRUISE_SPEED "255 = no speed"; -CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; -CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; 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_ 419 GEAR_SHIFTER 10 "S" 4 "D" 3 "N" 2 "R" 1 "P" ; @@ -321,5 +326,3 @@ VAL_ 422 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime" ; VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw" ; VAL_ 780 HUD_LEAD 3 "no_car" 2 "solid_car" 1 "dashed_car" 0 "no_car" ; -VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; - diff --git a/opendbc/acura_rdx_2018_can_generated.dbc b/opendbc/acura_rdx_2018_can_generated.dbc index 2acbe3fd7..49ae84234 100644 --- a/opendbc/acura_rdx_2018_can_generated.dbc +++ b/opendbc/acura_rdx_2018_can_generated.dbc @@ -1,41 +1,36 @@ CM_ "AUTOGENERATED FILE, DO NOT EDIT"; -CM_ "Imported file _honda_2017.dbc starts here"; -VERSION "" +CM_ "Imported file _comma.dbc starts here"; +BO_ 512 GAS_COMMAND: 6 EON + SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR + SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR + SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR + SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR + SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR + +BO_ 513 GAS_SENSOR: 6 INTERCEPTOR + SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON + SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON + SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON + SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON + +VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; -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_ +CM_ "Imported file _honda_common.dbc starts here"; +BO_ 304 GAS_PEDAL_2: 8 PCM + SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON -BU_: EBCM ADAS PCM EPS VSA SCM BDY XXX EPB EON +BO_ 316 GAS_PEDAL: 8 PCM + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON BO_ 344 ENGINE_DATA: 8 PCM SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" EON @@ -49,14 +44,14 @@ BO_ 380 POWERTRAIN_DATA: 8 PCM SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" EON SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" EON - SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "rpm" EON - SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "rpm" EON - SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "rpm" EON - SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "rpm" EON + SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "" EON + SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "" EON + SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "" EON + SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "" EON SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" EON - SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "rpm" EON + SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "" EON SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON BO_ 420 VSA_STATUS: 8 VSA SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON @@ -75,14 +70,6 @@ BO_ 427 STEER_MOTOR_TORQUE: 3 EPS SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" EON -BO_ 432 STANDSTILL: 7 VSA - SG_ CONTROLLED_STANDSTILL : 0|1@0+ (1,0) [0|1] "" EON - SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON - SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON - SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON - BO_ 464 WHEEL_SPEEDS: 8 VSA SG_ WHEEL_SPEED_FL : 7|15@0+ (0.01,0) [0|250] "kph" EON SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON @@ -91,10 +78,120 @@ BO_ 464 WHEEL_SPEEDS: 8 VSA SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON BO_ 490 VEHICLE_DYNAMICS: 8 VSA - SG_ LONG_ACCEL : 23|16@0- (0.0015384,0) [-20|20] "m/s2" EON + SG_ LAT_ACCEL : 7|16@0- (0.0015,0) [-20|20] "m/s2" EON + SG_ LONG_ACCEL : 23|16@0- (0.0015,0) [-20|20] "m/s2" EON SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON +BO_ 773 SEATBELT_STATUS: 7 BDY + SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 804 CRUISE: 8 PCM + SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" EON + SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" EON + SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON + SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" EON + SG_ BOH2 : 47|8@0- (1,0) [0|255] "" EON + SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 829 LKAS_HUD: 5 ADAS + SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY + SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY + SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY + SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY + SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY + SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY + SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY + SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY + SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY + SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY + SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY + +BO_ 884 STALK_STATUS: 8 XXX + SG_ DASHBOARD_ALERT : 39|8@0+ (1,0) [0|255] "" EON + SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON + SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON + SG_ WIPER_SWITCH : 53|2@0+ (1,0) [0|3] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 891 STALK_STATUS_2: 8 XXX + SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON + SG_ LOW_BEAMS : 35|1@0+ (1,0) [0|1] "" XXX + SG_ HIGH_BEAMS : 34|1@0+ (1,0) [0|1] "" XXX + SG_ PARK_LIGHTS : 36|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 1029 DOORS_STATUS: 8 BDY + SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" EON + SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +CM_ SG_ 304 "Seems to be platform-agnostic"; +CM_ SG_ 316 "Should exist on Nidec"; +CM_ SG_ 420 BRAKE_HOLD_RELATED "On when Brake Hold engaged"; +CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; +CM_ SG_ 773 PASS_AIRBAG_ON "Might just be indicator light"; +CM_ SG_ 773 PASS_AIRBAG_OFF "Might just be indicator light"; +CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; +CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; + +VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep"; +VAL_ 884 DASHBOARD_ALERT 0 "none" 51 "acc_problem" 55 "cmbs_problem" 75 "key_not_detected" 79 "fasten_seatbelt" 111 "lkas_problem" 131 "brake_system_problem" 132 "brake_hold_problem" 139 "tbd" 161 "door_open"; +VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off"; + + +CM_ "Imported file _honda_2017.dbc starts here"; +BO_ 145 KINEMATICS: 8 XXX + SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 148 KINEMATICS_ALT: 8 XXX + SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON + SG_ LONG_ACCEL : 24|9@0- (-0.02,0) [-20|20] "m/s2" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +BO_ 432 STANDSTILL: 7 VSA + SG_ CONTROLLED_STANDSTILL : 0|1@0+ (1,0) [0|1] "" EON + SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 487 BRAKE_PRESSURE: 4 VSA + SG_ BRAKE_PRESSURE1 : 7|10@0+ (0.015625,-103) [0|1000] "" EON + SG_ BRAKE_PRESSURE2 : 9|10@0+ (0.015625,-103) [0|1000] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON + BO_ 506 BRAKE_COMMAND: 8 ADAS SG_ COMPUTER_BRAKE : 7|10@0+ (1,0) [0|1] "" EBCM SG_ SET_ME_X00 : 13|5@0+ (1,0) [0|1] "" EBCM @@ -128,17 +225,6 @@ BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON -BO_ 773 SEATBELT_STATUS: 7 BDY - SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON - SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON - SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON - BO_ 777 LOCK_STATUS: 8 XXX SG_ DOORS_UNLOCKED : 54|1@0+ (1,0) [0|1] "" EON SG_ DOORS_LOCKED : 55|1@0+ (1,0) [0|1] "" EON @@ -172,89 +258,22 @@ BO_ 780 ACC_HUD: 8 ADAS SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY -BO_ 804 CRUISE: 8 PCM - SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" EON - SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" EON - SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON - SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" EON - SG_ BOH2 : 47|8@0- (1,0) [0|255] "" EON - SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - -BO_ 829 LKAS_HUD: 5 ADAS - SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY - SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY - SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY - SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY - SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY - SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY - SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY - SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY - SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY - SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY - SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY - SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY - SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY - SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY - SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY - BO_ 892 CRUISE_PARAMS: 8 PCM SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" EON SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON -BO_ 1029 DOORS_STATUS: 8 BDY - SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" EON - SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" EON - SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" EON - SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" EON - SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - -CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; CM_ SG_ 506 AEB_REQ_1 "set for duration of suspected AEB event"; -CM_ SG_ 773 PASS_AIRBAG_ON "Might just be indicator light"; -CM_ SG_ 773 PASS_AIRBAG_OFF "Might just be indicator light"; CM_ SG_ 780 CRUISE_SPEED "255 = no speed"; -CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; -CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; - -VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw" ; -VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime" ; -VAL_ 506 AEB_STATUS 3 "aeb_prepare" 2 "aeb_ready" 1 "aeb_braking" 0 "no_aeb" ; -VAL_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped" ; -VAL_ 780 HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car" ; -VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; - - -CM_ "Imported file _comma.dbc starts here"; -BO_ 512 GAS_COMMAND: 6 EON - SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR - SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR - SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR - -BO_ 513 GAS_SENSOR: 6 INTERCEPTOR - SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON - SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON - SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON - -VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; +VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw"; +VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime"; +VAL_ 506 AEB_STATUS 3 "aeb_prepare" 2 "aeb_ready" 1 "aeb_braking" 0 "no_aeb"; +VAL_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped"; +VAL_ 780 HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car"; CM_ "acura_rdx_2018_can.dbc starts here"; - - BO_ 342 STEERING_SENSORS: 6 EPS SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON SG_ STEER_ANGLE_RATE : 23|16@0- (-1,0) [-3000|3000] "deg/s" EON @@ -291,12 +310,6 @@ BO_ 422 SCM_BUTTONS: 8 SCM SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON -BO_ 487 BRAKE_PRESSURE: 4 VSA - SG_ BRAKE_PRESSURE1 : 7|10@0+ (0.015625,-103) [0|1000] "" EON - SG_ BRAKE_PRESSURE2 : 9|10@0+ (0.015625,-103) [0|1000] "" EON - SG_ COUNTER : 29|2@0+ (1,0) [0|15] "" EON - SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EON - BO_ 660 SCM_FEEDBACK: 8 SCM SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" EON SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" EON @@ -309,4 +322,3 @@ VAL_ 392 GEAR_SHIFTER 0 "S" 1 "P" 2 "R" 4 "N" 8 "D" ; VAL_ 392 GEAR 26 "S" 4 "D" 3 "N" 2 "R" 1 "P" ; 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_ 422 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; - diff --git a/opendbc/acura_rdx_2020_can_generated.dbc b/opendbc/acura_rdx_2020_can_generated.dbc index 3fadba455..7d0f2188f 100644 --- a/opendbc/acura_rdx_2020_can_generated.dbc +++ b/opendbc/acura_rdx_2020_can_generated.dbc @@ -1,42 +1,154 @@ CM_ "AUTOGENERATED FILE, DO NOT EDIT"; -CM_ "Imported file _bosch_2020.dbc starts here"; -VERSION "" +CM_ "Imported file _honda_common.dbc starts here"; +BO_ 304 GAS_PEDAL_2: 8 PCM + SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 316 GAS_PEDAL: 8 PCM + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 344 ENGINE_DATA: 8 PCM + SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ XMISSION_SPEED2 : 39|16@0+ (0.01,0) [0|250] "kph" EON + SG_ ODOMETER : 55|8@0+ (10,0) [0|2550] "m" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 380 POWERTRAIN_DATA: 8 PCM + SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" EON + SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "" EON + SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "" EON + SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "" EON + SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "" EON + SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" EON + SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 420 VSA_STATUS: 8 VSA + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON + SG_ COMPUTER_BRAKING : 23|1@0+ (1,0) [0|1] "" EON + SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_HOLD_RELATED : 52|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_HOLD_ENABLED : 45|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 427 STEER_MOTOR_TORQUE: 3 EPS + SG_ CONFIG_VALID : 7|1@0+ (1,0) [0|1] "" EON + SG_ MOTOR_TORQUE : 1|10@0+ (1,0) [0|256] "" EON + SG_ OUTPUT_DISABLED : 22|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" EON + +BO_ 464 WHEEL_SPEEDS: 8 VSA + SG_ WHEEL_SPEED_FL : 7|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RL : 25|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RR : 42|15@0+ (0.01,0) [0|250] "kph" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 490 VEHICLE_DYNAMICS: 8 VSA + SG_ LAT_ACCEL : 7|16@0- (0.0015,0) [-20|20] "m/s2" EON + SG_ LONG_ACCEL : 23|16@0- (0.0015,0) [-20|20] "m/s2" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 773 SEATBELT_STATUS: 7 BDY + SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 804 CRUISE: 8 PCM + SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" EON + SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" EON + SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON + SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" EON + SG_ BOH2 : 47|8@0- (1,0) [0|255] "" EON + SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 829 LKAS_HUD: 5 ADAS + SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY + SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY + SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY + SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY + SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY + SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY + SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY + SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY + SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY + SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY + SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY + +BO_ 884 STALK_STATUS: 8 XXX + SG_ DASHBOARD_ALERT : 39|8@0+ (1,0) [0|255] "" EON + SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON + SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON + SG_ WIPER_SWITCH : 53|2@0+ (1,0) [0|3] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 891 STALK_STATUS_2: 8 XXX + SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON + SG_ LOW_BEAMS : 35|1@0+ (1,0) [0|1] "" XXX + SG_ HIGH_BEAMS : 34|1@0+ (1,0) [0|1] "" XXX + SG_ PARK_LIGHTS : 36|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 1029 DOORS_STATUS: 8 BDY + SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" EON + SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +CM_ SG_ 304 "Seems to be platform-agnostic"; +CM_ SG_ 316 "Should exist on Nidec"; +CM_ SG_ 420 BRAKE_HOLD_RELATED "On when Brake Hold engaged"; +CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; +CM_ SG_ 773 PASS_AIRBAG_ON "Might just be indicator light"; +CM_ SG_ 773 PASS_AIRBAG_OFF "Might just be indicator light"; +CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; +CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; + +VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep"; +VAL_ 884 DASHBOARD_ALERT 0 "none" 51 "acc_problem" 55 "cmbs_problem" 75 "key_not_detected" 79 "fasten_seatbelt" 111 "lkas_problem" 131 "brake_system_problem" 132 "brake_hold_problem" 139 "tbd" 161 "door_open"; +VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off"; -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_ - -BU_: EBCM EON CAM RADAR PCM EPS VSA SCM BDY XXX EPB - +CM_ "Imported file _bosch_2018.dbc starts here"; BO_ 148 KINEMATICS: 8 XXX SG_ LAT_ACCEL : 7|10@0+ (-0.035,17.92) [-20|20] "m/s2" EON SG_ LONG_ACCEL : 25|10@0+ (-0.035,17.92) [-20|20] "m/s2" EON @@ -67,33 +179,6 @@ BO_ 232 BRAKE_HOLD: 7 XXX SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" XXX -BO_ 342 STEERING_SENSORS: 6 EPS - SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON - SG_ STEER_ANGLE_RATE : 23|16@0- (-1,0) [-3000|3000] "deg/s" EON - SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" EON - -BO_ 344 ENGINE_DATA: 8 PCM - SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" EON - SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON - SG_ XMISSION_SPEED2 : 39|16@0+ (0.01,0) [0|250] "kph" EON - SG_ ODOMETER : 55|8@0+ (10,0) [0|2550] "m" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON - -BO_ 380 POWERTRAIN_DATA: 8 PCM - SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" EON - SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON - SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" EON - SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "" EON - SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "" EON - SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "" EON - SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "" EON - SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" EON - SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON - BO_ 399 STEER_STATUS: 7 EPS SG_ STEER_TORQUE_SENSOR : 7|16@0- (-1,0) [-31000|31000] "tbd" EON SG_ STEER_ANGLE_RATE : 23|16@0- (-0.1,0) [-31000|31000] "deg/s" EON @@ -103,34 +188,12 @@ BO_ 399 STEER_STATUS: 7 EPS SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" EON -BO_ 420 VSA_STATUS: 8 VSA - SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON - SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON - SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" EON - SG_ BRAKE_HOLD_ENABLED : 45|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON - -BO_ 427 STEER_MOTOR_TORQUE: 3 EPS - SG_ CONFIG_VALID : 7|1@0+ (1,0) [0|1] "" EON - SG_ MOTOR_TORQUE : 1|10@0+ (1,0) [0|256] "" EON - SG_ OUTPUT_DISABLED : 22|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" EON - BO_ 450 EPB_STATUS: 8 EPB SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" EON SG_ EPB_STATE : 29|2@0+ (1,0) [0|3] "" EON SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_ 464 WHEEL_SPEEDS: 8 VSA - SG_ WHEEL_SPEED_FL : 7|15@0+ (0.01,0) [0|250] "kph" EON - SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON - SG_ WHEEL_SPEED_RL : 25|15@0+ (0.01,0) [0|250] "kph" EON - SG_ WHEEL_SPEED_RR : 42|15@0+ (0.01,0) [0|250] "kph" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - BO_ 479 ACC_CONTROL: 8 EON SG_ SET_TO_0 : 20|5@0+ (1,0) [0|1] "" XXX SG_ CONTROL_ON : 23|3@0+ (1,0) [0|5] "" XXX @@ -146,12 +209,6 @@ BO_ 479 ACC_CONTROL: 8 EON SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_ 490 VEHICLE_DYNAMICS: 8 VSA - SG_ LAT_ACCEL : 7|16@0- (0.0015,0) [-20|20] "m/s2" EON - SG_ LONG_ACCEL : 23|16@0- (0.0015,0) [-20|20] "m/s2" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - BO_ 495 ACC_CONTROL_ON: 8 XXX SG_ SET_TO_75 : 31|8@0+ (1,0) [0|255] "" XXX SG_ SET_TO_30 : 39|8@0+ (1,0) [0|255] "" XXX @@ -256,22 +313,11 @@ BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - BO_ 662 SCM_BUTTONS: 4 SCM - SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON - SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" EON - SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" EON - -BO_ 773 SEATBELT_STATUS: 7 BDY - SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON - SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON - SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON +BO_ 662 SCM_BUTTONS: 4 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" EON BO_ 777 CAR_SPEED: 8 PCM SG_ ROUGH_CAR_SPEED : 23|8@0+ (1,0) [0|255] "mph" XXX @@ -307,11 +353,6 @@ BO_ 780 ACC_HUD: 8 ADAS SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_ 804 CRUISE: 8 PCM - SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON - BO_ 806 SCM_FEEDBACK: 8 SCM SG_ DRIVERS_DOOR_OPEN : 17|1@0+ (1,0) [0|1] "" XXX SG_ MAIN_ON : 28|1@0+ (1,0) [0|1] "" EON @@ -321,7 +362,15 @@ BO_ 806 SCM_FEEDBACK: 8 SCM SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_ 829 LKAS_HUD: 5 ADAS +BO_ 862 CAMERA_MESSAGES: 8 CAM + SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY + SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX + SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX + SG_ ZEROS_BOH_2 : 51|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + +BO_ 13274 LKAS_HUD_A: 5 ADAS SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY @@ -335,38 +384,36 @@ BO_ 829 LKAS_HUD: 5 ADAS SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X01 : 20|1@0+ (1,0) [0|1] "" BDY SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY - SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY -BO_ 862 CAMERA_MESSAGES: 8 CAM - SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY - SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX - SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX - SG_ ZEROS_BOH_2 : 51|4@0+ (1,0) [0|15] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 884 STALK_STATUS: 8 XXX - SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON - SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON - SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON - SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON - SG_ WIPER_SWITCH : 53|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - -BO_ 891 STALK_STATUS_2: 8 XXX - SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON - SG_ LOW_BEAMS : 35|1@0+ (1,0) [0|1] "" XXX - SG_ HIGH_BEAMS : 34|1@0+ (1,0) [0|1] "" XXX - SG_ PARK_LIGHTS : 36|1@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON +BO_ 13275 LKAS_HUD_B: 8 ADAS + SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY + SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY + SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY + SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY + SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY + SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY + SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY + SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY + SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X01 : 20|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY + SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" BDY +CM_ SG_ 450 EPB_STATE "3: On, 2: Disengaging, 1: Engaging, 0: Off"; +CM_ SG_ 479 CONTROL_ON "Set to 5 when car is being controlled"; CM_ SG_ 479 AEB_STATUS "set for the duration of AEB event"; CM_ SG_ 479 AEB_BRAKING "set when braking is commanded during AEB event"; CM_ SG_ 479 AEB_PREPARE "set 1s before AEB"; @@ -375,17 +422,16 @@ CM_ SG_ 577 LINE_FAR_EDGE_POSITION "Appears to be a measure of line thickness, i CM_ SG_ 577 LINE_PARAMETER "Unclear if this is low quality line curvature rate or if this is something else, but it is correlated with line curvature, undecoded"; CM_ SG_ 577 LINE_DASHED "1 = line is dashed"; CM_ SG_ 577 LINE_SOLID "1 = line is solid"; -VAL_ 399 STEER_STATUS 6 "tmp_fault" 5 "fault_1" 4 "no_torque_alert_2" 3 "low_speed_lockout" 2 "no_torque_alert_1" 0 "normal" ; + +VAL_ 399 STEER_STATUS 6 "tmp_fault" 5 "fault_1" 4 "no_torque_alert_2" 3 "low_speed_lockout" 2 "no_torque_alert_1" 0 "normal"; CM_ "acura_rdx_2020_can.dbc starts here"; - -BO_ 304 GAS_PEDAL_2: 8 PCM - SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON - SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON - SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON +BO_ 342 STEERING_SENSORS: 6 EPS + SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON + SG_ STEER_ANGLE_RATE : 23|16@0- (-1,0) [-3000|3000] "deg/s" EON + SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" EON BO_ 419 GEARBOX: 8 PCM SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON @@ -429,6 +475,3 @@ VAL_ 545 ECON_ON_2 0 "off" 3 "on" ; VAL_ 662 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; VAL_ 662 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; VAL_ 806 CMBS_BUTTON 3 "pressed" 0 "released" ; -VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off" ; -VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; - diff --git a/opendbc/can/common.h b/opendbc/can/common.h index 95833402e..be9089ef0 100644 --- a/opendbc/can/common.h +++ b/opendbc/can/common.h @@ -32,8 +32,8 @@ public: std::vector parse_sigs; std::vector vals; + std::vector> all_vals; - uint16_t ts; uint64_t seen; uint64_t check_threshold; @@ -43,7 +43,7 @@ public: bool ignore_checksum = false; bool ignore_counter = false; - bool parse(uint64_t sec, uint16_t ts_, uint8_t * dat); + bool parse(uint64_t sec, uint8_t * dat); bool update_counter_generic(int64_t v, int cnt_size); }; diff --git a/opendbc/can/common.pxd b/opendbc/can/common.pxd index 273529bf5..dd54a0e6a 100644 --- a/opendbc/can/common.pxd +++ b/opendbc/can/common.pxd @@ -52,7 +52,6 @@ cdef extern from "common_dbc.h": cdef struct SignalParseOptions: uint32_t address const char* name - double default_value cdef struct MessageParseOptions: @@ -61,9 +60,9 @@ cdef extern from "common_dbc.h": cdef struct SignalValue: uint32_t address - uint16_t ts const char* name double value + vector[double] all_values cdef struct SignalPackValue: string name diff --git a/opendbc/can/common_dbc.h b/opendbc/can/common_dbc.h index f40b4ac42..2464ddea2 100644 --- a/opendbc/can/common_dbc.h +++ b/opendbc/can/common_dbc.h @@ -15,7 +15,6 @@ struct SignalPackValue { struct SignalParseOptions { uint32_t address; const char* name; - double default_value; }; struct MessageParseOptions { @@ -25,9 +24,9 @@ struct MessageParseOptions { struct SignalValue { uint32_t address; - uint16_t ts; const char* name; - double value; + double value; // latest value + std::vector all_values; // all values from this cycle }; enum SignalType { diff --git a/opendbc/can/parser.cc b/opendbc/can/parser.cc index 7e64199a1..dc1887c6e 100644 --- a/opendbc/can/parser.cc +++ b/opendbc/can/parser.cc @@ -13,7 +13,7 @@ // #define DEBUG printf #define INFO printf -bool MessageState::parse(uint64_t sec, uint16_t ts_, uint8_t * dat) { +bool MessageState::parse(uint64_t sec, uint8_t * dat) { uint64_t dat_le = read_u64_le(dat); uint64_t dat_be = read_u64_be(dat); @@ -83,8 +83,8 @@ bool MessageState::parse(uint64_t sec, uint16_t ts_, uint8_t * dat) { } vals[i] = tmp * sig.factor + sig.offset; + all_vals[i].push_back(vals[i]); } - ts = ts_; seen = sec; return true; @@ -148,6 +148,7 @@ CANParser::CANParser(int abus, const std::string& dbc_name, if (sig->type != SignalType::DEFAULT) { state.parse_sigs.push_back(*sig); state.vals.push_back(0); + state.all_vals.push_back({}); } } @@ -160,7 +161,8 @@ CANParser::CANParser(int abus, const std::string& dbc_name, if (strcmp(sig->name, sigop.name) == 0 && sig->type == SignalType::DEFAULT) { state.parse_sigs.push_back(*sig); - state.vals.push_back(sigop.default_value); + state.vals.push_back(0); + state.all_vals.push_back({}); break; } } @@ -189,6 +191,7 @@ CANParser::CANParser(int abus, const std::string& dbc_name, bool ignore_checksum const Signal *sig = &msg->sigs[j]; state.parse_sigs.push_back(*sig); state.vals.push_back(0); + state.all_vals.push_back({}); } message_states[state.address] = state; @@ -210,7 +213,7 @@ void CANParser::update_string(const std::string &data, bool sendcan) { last_sec = event.getLogMonoTime(); - auto cans = sendcan? event.getSendcan() : event.getCan(); + auto cans = sendcan ? event.getSendcan() : event.getCan(); UpdateCans(last_sec, cans); UpdateValid(last_sec); @@ -238,7 +241,7 @@ void CANParser::UpdateCans(uint64_t sec, const capnp::List::Rea uint8_t dat[8] = {0}; memcpy(dat, cmsg.getDat().begin(), cmsg.getDat().size()); - state_it->second.parse(sec, cmsg.getBusTime(), dat); + state_it->second.parse(sec, dat); } } #endif @@ -262,7 +265,7 @@ void CANParser::UpdateCans(uint64_t sec, const capnp::DynamicStruct::Reader& cms if (dat.size() > 8) return; //shouldn't ever happen uint8_t data[8] = {0}; memcpy(data, dat.begin(), dat.size()); - state_it->second.parse(sec, cmsg.get("busTime").as(), data); + state_it->second.parse(sec, data); } void CANParser::UpdateValid(uint64_t sec) { @@ -283,18 +286,19 @@ void CANParser::UpdateValid(uint64_t sec) { std::vector CANParser::query_latest() { std::vector ret; - for (const auto& kv : message_states) { - const auto& state = kv.second; + for (auto& kv : message_states) { + auto& state = kv.second; if (last_sec != 0 && state.seen != last_sec) continue; - for (int i=0; iself.address_to_msg_name[cv.address].c_str() cv_name = cv.name - self.vl[cv.address][cv_name] = cv.value - self.ts[cv.address][cv_name] = cv.ts + self.vl_all[cv.address][cv_name].extend(cv.all_values) + updated_addrs.insert(cv.address) - self.vl[name][cv_name] = cv.value - self.ts[name][cv_name] = cv.ts - - updated_val.insert(cv.address) - - return updated_val + return updated_addrs def update_string(self, dat, sendcan=False): + for v in self.vl_all.values(): + v.clear() + self.can.update_string(dat, sendcan) return self.update_vl() def update_strings(self, strings, sendcan=False): - updated_vals = set() + for v in self.vl_all.values(): + v.clear() + updated_addrs = set() for s in strings: - updated_val = self.update_string(s, sendcan) - updated_vals.update(updated_val) + self.can.update_string(s, sendcan) + updated_addrs.update(self.update_vl()) + return updated_addrs - return updated_vals cdef class CANDefine(): cdef: @@ -184,9 +180,8 @@ cdef class CANDefine(): values = [int(v) for v in def_val[::2]] defs = def_val[1::2] - # two ways to lookup: address or msg name dv[address][sgname] = dict(zip(values, defs)) dv[msgname][sgname] = dv[address][sgname] - self.dv = dict(dv) + self.dv = dict(dv) diff --git a/opendbc/gm_global_a_powertrain.dbc b/opendbc/gm_global_a_powertrain_generated.dbc similarity index 81% rename from opendbc/gm_global_a_powertrain.dbc rename to opendbc/gm_global_a_powertrain_generated.dbc index cf34478d0..db42343f6 100644 --- a/opendbc/gm_global_a_powertrain.dbc +++ b/opendbc/gm_global_a_powertrain_generated.dbc @@ -1,3 +1,25 @@ +CM_ "AUTOGENERATED FILE, DO NOT EDIT"; + + +CM_ "Imported file _comma.dbc starts here"; +BO_ 512 GAS_COMMAND: 6 NEO + SG_ GAS_COMMAND : 7|16@0+ (0.125677,-75.909) [0|1] "" INTERCEPTOR + SG_ GAS_COMMAND2 : 23|16@0+ (0.251976,-76.601) [0|1] "" INTERCEPTOR + SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR + SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR + SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR + +BO_ 513 GAS_SENSOR: 6 INTERCEPTOR + SG_ INTERCEPTOR_GAS : 7|16@0+ (0.125677,-75.909) [0|1] "" NEO + SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.251976,-76.601) [0|1] "" NEO + SG_ STATE : 39|4@0+ (1,0) [0|15] "" NEO + SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" NEO + SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" NEO + +VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; + +CM_ "gm_global_a_powertrain.dbc starts here"; + VERSION "" @@ -67,7 +89,7 @@ BO_ 190 ECMAcceleratorPos: 6 K20_ECM BO_ 201 ECMEngineStatus: 8 K20_ECM SG_ EngineTPS : 39|8@0+ (0.392156863,0) [0|100.000000065] "%" NEO - SG_ EngineRPM : 13|14@0+ (0.25,0) [0|0] "RPM" NEO + SG_ EngineRPM : 15|16@0+ (0.25,0) [0|0] "RPM" NEO SG_ CruiseMainOn : 29|1@0+ (1,0) [0|1] "" NEO SG_ Brake_Pressed : 40|1@0+ (1,0) [0|1] "" NEO SG_ Standstill : 2|1@0+ (1,0) [0|1] "" NEO @@ -147,6 +169,17 @@ BO_ 489 EBCMVehicleDynamic: 8 K17_EBCM SG_ YawRate : 35|12@0- (0.625,0) [0|1] "" NEO SG_ YawRate2 : 51|12@0- (0.0625,0) [-2047|2047] "grad/s" NEO +BO_ 352 VehicleIgnition: 5 XXX + SG_ Ignition : 7|32@0+ (1,0) [0|4294967295] "" XXX + +BO_ 497 VehicleIgnitionAlt: 8 XXX + SG_ Ignition : 5|1@0+ (1,0) [0|1] "" XXX + +BO_ 501 ECMPRDNL2: 8 K20_ECM + SG_ TransmissionState : 48|4@1+ (1,0) [0|7] "" NEO + SG_ PRNDL2 : 27|4@0+ (1,0) [0|255] "" NEO + SG_ ManualMode : 41|1@0+ (1,0) [0|1] "" NEO + BO_ 560 EPBStatus: 8 EPB SG_ EPBClosed : 12|1@0+ (1,0) [0|1] "" NEO @@ -167,6 +200,18 @@ BO_ 715 ASCMGasRegenCmd: 8 K124_ASCM BO_ 717 ASCM_2CD: 5 K124_ASCM +BO_ 789 EBCMFrictionBrakeCmd: 5 K124_ASCM + SG_ RollingCounter : 33|2@0+ (1,0) [0|0] "" NEO + SG_ FrictionBrakeMode : 7|4@0+ (1,0) [0|0] "" NEO + SG_ FrictionBrakeChecksum : 23|16@0+ (1,0) [0|0] "" NEO + SG_ FrictionBrakeCmd : 3|12@0- (1,0) [0|0] "" NEO + +BO_ 800 AEBCmd: 6 K124_ASCM + SG_ RollingCounter : 5|2@0+ (1,0) [0|3] "" NEO + SG_ Checksum : 27|20@0+ (1,0) [0|2047] "" NEO + SG_ BrakeCmdActive : 3|1@1+ (1,0) [0|1] "" NEO + SG_ BrakingForce : 2|7@0+ (1,0) [0|7] "" NEO + BO_ 810 TCICOnStarGPSPosition: 8 K73_TCIC SG_ GPSLongitude : 39|32@0+ (1,-2147483648) [0|0] "milliarcsecond" NEO SG_ GPSLatitude : 7|32@0+ (1,0) [0|0] "milliarcsecond" NEO @@ -218,6 +263,8 @@ BO_TX_BU_ 384 : K124_ASCM,NEO; BO_TX_BU_ 880 : NEO,K124_ASCM; BO_TX_BU_ 1033 : K124_ASCM,NEO; BO_TX_BU_ 715 : NEO,K124_ASCM; +BO_TX_BU_ 789 : NEO,K124_ASCM; +BO_TX_BU_ 800 : NEO,K124_ASCM; CM_ BU_ K16_BECM "Battery Energy Control Module"; @@ -231,7 +278,10 @@ CM_ BU_ NEO "Comma NEO"; CM_ BU_ K124_ASCM "Active Safety Control Module"; CM_ SG_ 381 MSG17D_AccPower "Need to investigate"; CM_ SG_ 190 GasPedalAndAcc "ACC baseline is 62"; +CM_ SG_ 352 Ignition "Non-zero when ignition is on"; CM_ SG_ 451 GasPedalAndAcc2 "ACC baseline is 62"; +CM_ SG_ 497 Ignition "Describes ignition + preconditioning mode, noisy"; +CM_ SG_ 501 PRNDL2 "When ManualMode is Active, Value is 13=L1 12=L2 11=L3 ... 4=L10"; BA_DEF_ "UseGMParameterIDs" INT 0 0; BA_DEF_ "ProtocolType" STRING ; BA_DEF_ "BusType" STRING ; @@ -262,3 +312,6 @@ VAL_ 715 GasRegenCmdActive 1 "Active" 0 "Inactive" ; VAL_ 320 Intellibeam 1 "Active" 0 "Inactive" ; VAL_ 320 HighBeamsActive 1 "Active" 0 "Inactive" ; VAL_ 320 HighBeamsTemporary 1 "Active" 0 "Inactive" ; +VAL_ 501 PRNDL2 6 "L" 4 "D" 3 "N" 2 "R" 1 "P" 0 "Shifting"; +VAL_ 501 TransmissionState 11 "Shifting" 10 "Reverse" 9 "Forward" 8 "Disengaged"; +VAL_ 501 ManualMode 1 "Active" 0 "Inactive" diff --git a/opendbc/honda_accord_2018_can_generated.dbc b/opendbc/honda_accord_2018_can_generated.dbc index 0b79ceef4..12b66c6ec 100644 --- a/opendbc/honda_accord_2018_can_generated.dbc +++ b/opendbc/honda_accord_2018_can_generated.dbc @@ -1,42 +1,154 @@ CM_ "AUTOGENERATED FILE, DO NOT EDIT"; +CM_ "Imported file _honda_common.dbc starts here"; +BO_ 304 GAS_PEDAL_2: 8 PCM + SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 316 GAS_PEDAL: 8 PCM + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 344 ENGINE_DATA: 8 PCM + SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ XMISSION_SPEED2 : 39|16@0+ (0.01,0) [0|250] "kph" EON + SG_ ODOMETER : 55|8@0+ (10,0) [0|2550] "m" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 380 POWERTRAIN_DATA: 8 PCM + SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" EON + SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "" EON + SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "" EON + SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "" EON + SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "" EON + SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" EON + SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 420 VSA_STATUS: 8 VSA + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON + SG_ COMPUTER_BRAKING : 23|1@0+ (1,0) [0|1] "" EON + SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_HOLD_RELATED : 52|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_HOLD_ENABLED : 45|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 427 STEER_MOTOR_TORQUE: 3 EPS + SG_ CONFIG_VALID : 7|1@0+ (1,0) [0|1] "" EON + SG_ MOTOR_TORQUE : 1|10@0+ (1,0) [0|256] "" EON + SG_ OUTPUT_DISABLED : 22|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" EON + +BO_ 464 WHEEL_SPEEDS: 8 VSA + SG_ WHEEL_SPEED_FL : 7|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RL : 25|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RR : 42|15@0+ (0.01,0) [0|250] "kph" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 490 VEHICLE_DYNAMICS: 8 VSA + SG_ LAT_ACCEL : 7|16@0- (0.0015,0) [-20|20] "m/s2" EON + SG_ LONG_ACCEL : 23|16@0- (0.0015,0) [-20|20] "m/s2" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 773 SEATBELT_STATUS: 7 BDY + SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 804 CRUISE: 8 PCM + SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" EON + SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" EON + SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON + SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" EON + SG_ BOH2 : 47|8@0- (1,0) [0|255] "" EON + SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 829 LKAS_HUD: 5 ADAS + SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY + SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY + SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY + SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY + SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY + SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY + SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY + SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY + SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY + SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY + SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY + +BO_ 884 STALK_STATUS: 8 XXX + SG_ DASHBOARD_ALERT : 39|8@0+ (1,0) [0|255] "" EON + SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON + SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON + SG_ WIPER_SWITCH : 53|2@0+ (1,0) [0|3] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 891 STALK_STATUS_2: 8 XXX + SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON + SG_ LOW_BEAMS : 35|1@0+ (1,0) [0|1] "" XXX + SG_ HIGH_BEAMS : 34|1@0+ (1,0) [0|1] "" XXX + SG_ PARK_LIGHTS : 36|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 1029 DOORS_STATUS: 8 BDY + SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" EON + SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +CM_ SG_ 304 "Seems to be platform-agnostic"; +CM_ SG_ 316 "Should exist on Nidec"; +CM_ SG_ 420 BRAKE_HOLD_RELATED "On when Brake Hold engaged"; +CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; +CM_ SG_ 773 PASS_AIRBAG_ON "Might just be indicator light"; +CM_ SG_ 773 PASS_AIRBAG_OFF "Might just be indicator light"; +CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; +CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; + +VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep"; +VAL_ 884 DASHBOARD_ALERT 0 "none" 51 "acc_problem" 55 "cmbs_problem" 75 "key_not_detected" 79 "fasten_seatbelt" 111 "lkas_problem" 131 "brake_system_problem" 132 "brake_hold_problem" 139 "tbd" 161 "door_open"; +VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off"; + + CM_ "Imported file _bosch_2018.dbc starts here"; -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_ - -BU_: EBCM EON CAM RADAR PCM EPS VSA SCM BDY XXX EPB - BO_ 148 KINEMATICS: 8 XXX SG_ LAT_ACCEL : 7|10@0+ (-0.035,17.92) [-20|20] "m/s2" EON SG_ LONG_ACCEL : 25|10@0+ (-0.035,17.92) [-20|20] "m/s2" EON @@ -67,37 +179,6 @@ BO_ 232 BRAKE_HOLD: 7 XXX SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" XXX -BO_ 330 STEERING_SENSORS: 8 EPS - SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON - SG_ STEER_ANGLE_RATE : 23|16@0- (-1,0) [-3000|3000] "deg/s" EON - SG_ STEER_SENSOR_STATUS_1 : 34|1@0+ (1,0) [0|1] "" EON - SG_ STEER_SENSOR_STATUS_2 : 33|1@0+ (1,0) [0|1] "" EON - SG_ STEER_SENSOR_STATUS_3 : 32|1@0+ (1,0) [0|1] "" EON - SG_ STEER_WHEEL_ANGLE : 47|16@0- (-0.1,0) [-500|500] "deg" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON - -BO_ 344 ENGINE_DATA: 8 PCM - SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" EON - SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON - SG_ XMISSION_SPEED2 : 39|16@0+ (0.01,0) [0|250] "kph" EON - SG_ ODOMETER : 55|8@0+ (10,0) [0|2550] "m" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON - -BO_ 380 POWERTRAIN_DATA: 8 PCM - SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" EON - SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON - SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" EON - SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "" EON - SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "" EON - SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "" EON - SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "" EON - SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" EON - SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON - BO_ 399 STEER_STATUS: 7 EPS SG_ STEER_TORQUE_SENSOR : 7|16@0- (-1,0) [-31000|31000] "tbd" EON SG_ STEER_ANGLE_RATE : 23|16@0- (-0.1,0) [-31000|31000] "deg/s" EON @@ -107,34 +188,12 @@ BO_ 399 STEER_STATUS: 7 EPS SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" EON -BO_ 420 VSA_STATUS: 8 VSA - SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON - SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON - SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" EON - SG_ BRAKE_HOLD_ENABLED : 45|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON - -BO_ 427 STEER_MOTOR_TORQUE: 3 EPS - SG_ CONFIG_VALID : 7|1@0+ (1,0) [0|1] "" EON - SG_ MOTOR_TORQUE : 1|10@0+ (1,0) [0|256] "" EON - SG_ OUTPUT_DISABLED : 22|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" EON - BO_ 450 EPB_STATUS: 8 EPB SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" EON SG_ EPB_STATE : 29|2@0+ (1,0) [0|3] "" EON SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_ 464 WHEEL_SPEEDS: 8 VSA - SG_ WHEEL_SPEED_FL : 7|15@0+ (0.01,0) [0|250] "kph" EON - SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON - SG_ WHEEL_SPEED_RL : 25|15@0+ (0.01,0) [0|250] "kph" EON - SG_ WHEEL_SPEED_RR : 42|15@0+ (0.01,0) [0|250] "kph" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - BO_ 479 ACC_CONTROL: 8 EON SG_ SET_TO_0 : 20|5@0+ (1,0) [0|1] "" XXX SG_ CONTROL_ON : 23|3@0+ (1,0) [0|5] "" XXX @@ -150,12 +209,6 @@ BO_ 479 ACC_CONTROL: 8 EON SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_ 490 VEHICLE_DYNAMICS: 8 VSA - SG_ LAT_ACCEL : 7|16@0- (0.0015,0) [-20|20] "m/s2" EON - SG_ LONG_ACCEL : 23|16@0- (0.0015,0) [-20|20] "m/s2" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - BO_ 495 ACC_CONTROL_ON: 8 XXX SG_ SET_TO_75 : 31|8@0+ (1,0) [0|255] "" XXX SG_ SET_TO_30 : 39|8@0+ (1,0) [0|255] "" XXX @@ -260,22 +313,11 @@ BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - BO_ 662 SCM_BUTTONS: 4 SCM - SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON - SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" EON - SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" EON - -BO_ 773 SEATBELT_STATUS: 7 BDY - SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON - SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON - SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON +BO_ 662 SCM_BUTTONS: 4 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" EON BO_ 777 CAR_SPEED: 8 PCM SG_ ROUGH_CAR_SPEED : 23|8@0+ (1,0) [0|255] "mph" XXX @@ -311,11 +353,6 @@ BO_ 780 ACC_HUD: 8 ADAS SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_ 804 CRUISE: 8 PCM - SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON - BO_ 806 SCM_FEEDBACK: 8 SCM SG_ DRIVERS_DOOR_OPEN : 17|1@0+ (1,0) [0|1] "" XXX SG_ MAIN_ON : 28|1@0+ (1,0) [0|1] "" EON @@ -325,27 +362,6 @@ BO_ 806 SCM_FEEDBACK: 8 SCM SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_ 829 LKAS_HUD: 5 ADAS - SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY - SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY - SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY - SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY - SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY - SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY - SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY - SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY - SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY - SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY - SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY - SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY - SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY - SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY - SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY - 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 @@ -354,23 +370,6 @@ BO_ 862 CAMERA_MESSAGES: 8 CAM SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_ 884 STALK_STATUS: 8 XXX - SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON - SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON - SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON - SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON - SG_ WIPER_SWITCH : 53|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - -BO_ 891 STALK_STATUS_2: 8 XXX - SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON - SG_ LOW_BEAMS : 35|1@0+ (1,0) [0|1] "" XXX - SG_ HIGH_BEAMS : 34|1@0+ (1,0) [0|1] "" XXX - SG_ PARK_LIGHTS : 36|1@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - BO_ 13274 LKAS_HUD_A: 5 ADAS SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY @@ -413,6 +412,8 @@ BO_ 13275 LKAS_HUD_B: 8 ADAS SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" BDY +CM_ SG_ 450 EPB_STATE "3: On, 2: Disengaging, 1: Engaging, 0: Off"; +CM_ SG_ 479 CONTROL_ON "Set to 5 when car is being controlled"; CM_ SG_ 479 AEB_STATUS "set for the duration of AEB event"; CM_ SG_ 479 AEB_BRAKING "set when braking is commanded during AEB event"; CM_ SG_ 479 AEB_PREPARE "set 1s before AEB"; @@ -421,24 +422,21 @@ CM_ SG_ 577 LINE_FAR_EDGE_POSITION "Appears to be a measure of line thickness, i CM_ SG_ 577 LINE_PARAMETER "Unclear if this is low quality line curvature rate or if this is something else, but it is correlated with line curvature, undecoded"; CM_ SG_ 577 LINE_DASHED "1 = line is dashed"; CM_ SG_ 577 LINE_SOLID "1 = line is solid"; -VAL_ 399 STEER_STATUS 6 "tmp_fault" 5 "fault_1" 4 "no_torque_alert_2" 3 "low_speed_lockout" 2 "no_torque_alert_1" 0 "normal" ; + +VAL_ 399 STEER_STATUS 6 "tmp_fault" 5 "fault_1" 4 "no_torque_alert_2" 3 "low_speed_lockout" 2 "no_torque_alert_1" 0 "normal"; CM_ "honda_accord_2018_can.dbc starts here"; - -BO_ 304 GAS_PEDAL_2: 8 PCM - SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON - SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON - SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON +BO_ 330 STEERING_SENSORS: 8 EPS + SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON + SG_ STEER_ANGLE_RATE : 23|16@0- (-1,0) [-3000|3000] "deg/s" EON + SG_ STEER_SENSOR_STATUS_1 : 34|1@0+ (1,0) [0|1] "" EON + SG_ STEER_SENSOR_STATUS_2 : 33|1@0+ (1,0) [0|1] "" EON + SG_ STEER_SENSOR_STATUS_3 : 32|1@0+ (1,0) [0|1] "" EON + SG_ STEER_WHEEL_ANGLE : 47|16@0- (-0.1,0) [-500|500] "deg" EON SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON -BO_ 419 GEARBOX: 8 PCM - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - SG_ GEAR_SHIFTER : 29|6@0+ (1,0) [0|63] "" EON - SG_ GEAR : 7|8@0+ (1,0) [0|255] "" EON - BO_ 401 GEARBOX_15T: 8 PCM SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" EON SG_ BOH : 45|6@0+ (1,0) [0|63] "" XXX @@ -448,7 +446,14 @@ BO_ 401 GEARBOX_15T: 8 PCM SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON +BO_ 419 GEARBOX: 8 XXX + SG_ GEAR_SHIFTER : 24|8@1+ (1,0) [0|255] "" XXX + SG_ GEAR : 32|8@1+ (1,0) [0|255] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + BO_ 432 STANDSTILL: 7 VSA + SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON @@ -459,9 +464,20 @@ BO_ 446 BRAKE_MODULE: 3 VSA SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" XXX +BO_ 506 LEGACY_BRAKE_COMMAND: 8 ADAS + SG_ CHIME : 40|8@1+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX + +BO_ 892 CRUISE_PARAMS: 8 PCM + SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|15] "" EON + BO_ 927 RADAR_HUD: 8 RADAR SG_ ZEROS_BOH : 7|10@0+ (1,0) [0|127] "" BDY SG_ CMBS_OFF : 12|1@0+ (1,0) [0|1] "" BDY + SG_ ZEROS_BOH3 : 31|32@0+ (1,0) [0|4294967295] "" XXX SG_ RESUME_INSTRUCTION : 21|1@0+ (1,0) [0|1] "" XXX SG_ SET_TO_1 : 13|1@0+ (1,0) [0|1] "" BDY SG_ ZEROS_BOH2 : 11|4@0+ (1,0) [0|1] "" XXX @@ -479,13 +495,11 @@ BO_ 1302 ODOMETER: 8 XXX SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON -VAL_ 419 GEAR_SHIFTER 32 "D" 8 "R" 4 "P" ; -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_ 545 ECON_ON_2 0 "off" 3 "on" ; -VAL_ 662 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; -VAL_ 662 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; -VAL_ 806 CMBS_BUTTON 3 "pressed" 0 "released" ; -VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off" ; -VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; - +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 2 "S" 32 "D" 16 "N" 8 "R" 4 "P"; +VAL_ 419 GEAR 26 "S" 20 "D" 19 "N" 18 "R" 17 "P"; +VAL_ 545 ECON_ON_2 0 "off" 3 "on"; +VAL_ 662 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none"; +VAL_ 662 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none"; +VAL_ 806 CMBS_BUTTON 3 "pressed" 0 "released"; diff --git a/opendbc/honda_civic_hatchback_ex_2017_can_generated.dbc b/opendbc/honda_civic_hatchback_ex_2017_can_generated.dbc index cb2a3592a..bd972f7f8 100644 --- a/opendbc/honda_civic_hatchback_ex_2017_can_generated.dbc +++ b/opendbc/honda_civic_hatchback_ex_2017_can_generated.dbc @@ -1,42 +1,154 @@ CM_ "AUTOGENERATED FILE, DO NOT EDIT"; +CM_ "Imported file _honda_common.dbc starts here"; +BO_ 304 GAS_PEDAL_2: 8 PCM + SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 316 GAS_PEDAL: 8 PCM + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 344 ENGINE_DATA: 8 PCM + SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ XMISSION_SPEED2 : 39|16@0+ (0.01,0) [0|250] "kph" EON + SG_ ODOMETER : 55|8@0+ (10,0) [0|2550] "m" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 380 POWERTRAIN_DATA: 8 PCM + SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" EON + SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "" EON + SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "" EON + SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "" EON + SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "" EON + SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" EON + SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 420 VSA_STATUS: 8 VSA + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON + SG_ COMPUTER_BRAKING : 23|1@0+ (1,0) [0|1] "" EON + SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_HOLD_RELATED : 52|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_HOLD_ENABLED : 45|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 427 STEER_MOTOR_TORQUE: 3 EPS + SG_ CONFIG_VALID : 7|1@0+ (1,0) [0|1] "" EON + SG_ MOTOR_TORQUE : 1|10@0+ (1,0) [0|256] "" EON + SG_ OUTPUT_DISABLED : 22|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" EON + +BO_ 464 WHEEL_SPEEDS: 8 VSA + SG_ WHEEL_SPEED_FL : 7|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RL : 25|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RR : 42|15@0+ (0.01,0) [0|250] "kph" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 490 VEHICLE_DYNAMICS: 8 VSA + SG_ LAT_ACCEL : 7|16@0- (0.0015,0) [-20|20] "m/s2" EON + SG_ LONG_ACCEL : 23|16@0- (0.0015,0) [-20|20] "m/s2" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 773 SEATBELT_STATUS: 7 BDY + SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 804 CRUISE: 8 PCM + SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" EON + SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" EON + SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON + SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" EON + SG_ BOH2 : 47|8@0- (1,0) [0|255] "" EON + SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 829 LKAS_HUD: 5 ADAS + SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY + SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY + SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY + SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY + SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY + SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY + SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY + SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY + SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY + SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY + SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY + +BO_ 884 STALK_STATUS: 8 XXX + SG_ DASHBOARD_ALERT : 39|8@0+ (1,0) [0|255] "" EON + SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON + SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON + SG_ WIPER_SWITCH : 53|2@0+ (1,0) [0|3] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 891 STALK_STATUS_2: 8 XXX + SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON + SG_ LOW_BEAMS : 35|1@0+ (1,0) [0|1] "" XXX + SG_ HIGH_BEAMS : 34|1@0+ (1,0) [0|1] "" XXX + SG_ PARK_LIGHTS : 36|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 1029 DOORS_STATUS: 8 BDY + SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" EON + SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +CM_ SG_ 304 "Seems to be platform-agnostic"; +CM_ SG_ 316 "Should exist on Nidec"; +CM_ SG_ 420 BRAKE_HOLD_RELATED "On when Brake Hold engaged"; +CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; +CM_ SG_ 773 PASS_AIRBAG_ON "Might just be indicator light"; +CM_ SG_ 773 PASS_AIRBAG_OFF "Might just be indicator light"; +CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; +CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; + +VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep"; +VAL_ 884 DASHBOARD_ALERT 0 "none" 51 "acc_problem" 55 "cmbs_problem" 75 "key_not_detected" 79 "fasten_seatbelt" 111 "lkas_problem" 131 "brake_system_problem" 132 "brake_hold_problem" 139 "tbd" 161 "door_open"; +VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off"; + + CM_ "Imported file _bosch_2018.dbc starts here"; -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_ - -BU_: EBCM EON CAM RADAR PCM EPS VSA SCM BDY XXX EPB - BO_ 148 KINEMATICS: 8 XXX SG_ LAT_ACCEL : 7|10@0+ (-0.035,17.92) [-20|20] "m/s2" EON SG_ LONG_ACCEL : 25|10@0+ (-0.035,17.92) [-20|20] "m/s2" EON @@ -67,37 +179,6 @@ BO_ 232 BRAKE_HOLD: 7 XXX SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" XXX -BO_ 330 STEERING_SENSORS: 8 EPS - SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON - SG_ STEER_ANGLE_RATE : 23|16@0- (-1,0) [-3000|3000] "deg/s" EON - SG_ STEER_SENSOR_STATUS_1 : 34|1@0+ (1,0) [0|1] "" EON - SG_ STEER_SENSOR_STATUS_2 : 33|1@0+ (1,0) [0|1] "" EON - SG_ STEER_SENSOR_STATUS_3 : 32|1@0+ (1,0) [0|1] "" EON - SG_ STEER_WHEEL_ANGLE : 47|16@0- (-0.1,0) [-500|500] "deg" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON - -BO_ 344 ENGINE_DATA: 8 PCM - SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" EON - SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON - SG_ XMISSION_SPEED2 : 39|16@0+ (0.01,0) [0|250] "kph" EON - SG_ ODOMETER : 55|8@0+ (10,0) [0|2550] "m" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON - -BO_ 380 POWERTRAIN_DATA: 8 PCM - SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" EON - SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON - SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" EON - SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "" EON - SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "" EON - SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "" EON - SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "" EON - SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" EON - SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON - BO_ 399 STEER_STATUS: 7 EPS SG_ STEER_TORQUE_SENSOR : 7|16@0- (-1,0) [-31000|31000] "tbd" EON SG_ STEER_ANGLE_RATE : 23|16@0- (-0.1,0) [-31000|31000] "deg/s" EON @@ -107,34 +188,12 @@ BO_ 399 STEER_STATUS: 7 EPS SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" EON -BO_ 420 VSA_STATUS: 8 VSA - SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON - SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON - SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" EON - SG_ BRAKE_HOLD_ENABLED : 45|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON - -BO_ 427 STEER_MOTOR_TORQUE: 3 EPS - SG_ CONFIG_VALID : 7|1@0+ (1,0) [0|1] "" EON - SG_ MOTOR_TORQUE : 1|10@0+ (1,0) [0|256] "" EON - SG_ OUTPUT_DISABLED : 22|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" EON - BO_ 450 EPB_STATUS: 8 EPB SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" EON SG_ EPB_STATE : 29|2@0+ (1,0) [0|3] "" EON SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_ 464 WHEEL_SPEEDS: 8 VSA - SG_ WHEEL_SPEED_FL : 7|15@0+ (0.01,0) [0|250] "kph" EON - SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON - SG_ WHEEL_SPEED_RL : 25|15@0+ (0.01,0) [0|250] "kph" EON - SG_ WHEEL_SPEED_RR : 42|15@0+ (0.01,0) [0|250] "kph" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - BO_ 479 ACC_CONTROL: 8 EON SG_ SET_TO_0 : 20|5@0+ (1,0) [0|1] "" XXX SG_ CONTROL_ON : 23|3@0+ (1,0) [0|5] "" XXX @@ -150,12 +209,6 @@ BO_ 479 ACC_CONTROL: 8 EON SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_ 490 VEHICLE_DYNAMICS: 8 VSA - SG_ LAT_ACCEL : 7|16@0- (0.0015,0) [-20|20] "m/s2" EON - SG_ LONG_ACCEL : 23|16@0- (0.0015,0) [-20|20] "m/s2" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - BO_ 495 ACC_CONTROL_ON: 8 XXX SG_ SET_TO_75 : 31|8@0+ (1,0) [0|255] "" XXX SG_ SET_TO_30 : 39|8@0+ (1,0) [0|255] "" XXX @@ -260,22 +313,11 @@ BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - BO_ 662 SCM_BUTTONS: 4 SCM - SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON - SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" EON - SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" EON - -BO_ 773 SEATBELT_STATUS: 7 BDY - SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON - SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON - SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON +BO_ 662 SCM_BUTTONS: 4 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" EON BO_ 777 CAR_SPEED: 8 PCM SG_ ROUGH_CAR_SPEED : 23|8@0+ (1,0) [0|255] "mph" XXX @@ -311,11 +353,6 @@ BO_ 780 ACC_HUD: 8 ADAS SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_ 804 CRUISE: 8 PCM - SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON - BO_ 806 SCM_FEEDBACK: 8 SCM SG_ DRIVERS_DOOR_OPEN : 17|1@0+ (1,0) [0|1] "" XXX SG_ MAIN_ON : 28|1@0+ (1,0) [0|1] "" EON @@ -325,27 +362,6 @@ BO_ 806 SCM_FEEDBACK: 8 SCM SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_ 829 LKAS_HUD: 5 ADAS - SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY - SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY - SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY - SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY - SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY - SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY - SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY - SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY - SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY - SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY - SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY - SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY - SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY - SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY - SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY - 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 @@ -354,23 +370,6 @@ BO_ 862 CAMERA_MESSAGES: 8 CAM SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_ 884 STALK_STATUS: 8 XXX - SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON - SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON - SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON - SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON - SG_ WIPER_SWITCH : 53|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - -BO_ 891 STALK_STATUS_2: 8 XXX - SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON - SG_ LOW_BEAMS : 35|1@0+ (1,0) [0|1] "" XXX - SG_ HIGH_BEAMS : 34|1@0+ (1,0) [0|1] "" XXX - SG_ PARK_LIGHTS : 36|1@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - BO_ 13274 LKAS_HUD_A: 5 ADAS SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY @@ -413,6 +412,8 @@ BO_ 13275 LKAS_HUD_B: 8 ADAS SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" BDY +CM_ SG_ 450 EPB_STATE "3: On, 2: Disengaging, 1: Engaging, 0: Off"; +CM_ SG_ 479 CONTROL_ON "Set to 5 when car is being controlled"; CM_ SG_ 479 AEB_STATUS "set for the duration of AEB event"; CM_ SG_ 479 AEB_BRAKING "set when braking is commanded during AEB event"; CM_ SG_ 479 AEB_PREPARE "set 1s before AEB"; @@ -421,15 +422,18 @@ CM_ SG_ 577 LINE_FAR_EDGE_POSITION "Appears to be a measure of line thickness, i CM_ SG_ 577 LINE_PARAMETER "Unclear if this is low quality line curvature rate or if this is something else, but it is correlated with line curvature, undecoded"; CM_ SG_ 577 LINE_DASHED "1 = line is dashed"; CM_ SG_ 577 LINE_SOLID "1 = line is solid"; -VAL_ 399 STEER_STATUS 6 "tmp_fault" 5 "fault_1" 4 "no_torque_alert_2" 3 "low_speed_lockout" 2 "no_torque_alert_1" 0 "normal" ; + +VAL_ 399 STEER_STATUS 6 "tmp_fault" 5 "fault_1" 4 "no_torque_alert_2" 3 "low_speed_lockout" 2 "no_torque_alert_1" 0 "normal"; CM_ "honda_civic_hatchback_ex_2017_can.dbc starts here"; - -BO_ 304 GAS_PEDAL_2: 8 PCM - SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON - SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON - SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON +BO_ 330 STEERING_SENSORS: 8 EPS + SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON + SG_ STEER_ANGLE_RATE : 23|16@0- (-1,0) [-3000|3000] "deg/s" EON + SG_ STEER_SENSOR_STATUS_1 : 34|1@0+ (1,0) [0|1] "" EON + SG_ STEER_SENSOR_STATUS_2 : 33|1@0+ (1,0) [0|1] "" EON + SG_ STEER_SENSOR_STATUS_3 : 32|1@0+ (1,0) [0|1] "" EON + SG_ STEER_WHEEL_ANGLE : 47|16@0- (-0.1,0) [-500|500] "deg" EON SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON @@ -472,21 +476,9 @@ BO_ 927 RADAR_HUD: 8 RADAR SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_ 1029 DOORS_STATUS: 8 BDY - SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" EON - SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" EON - SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" EON - SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" EON - SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON - 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_ 545 ECON_ON_2 0 "off" 3 "on" ; VAL_ 662 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; VAL_ 662 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; VAL_ 806 CMBS_BUTTON 3 "pressed" 0 "released" ; -VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off" ; -VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; - diff --git a/opendbc/honda_civic_sedan_16_diesel_2019_can_generated.dbc b/opendbc/honda_civic_sedan_16_diesel_2019_can_generated.dbc deleted file mode 100644 index 0ddb0bd40..000000000 --- a/opendbc/honda_civic_sedan_16_diesel_2019_can_generated.dbc +++ /dev/null @@ -1,487 +0,0 @@ -CM_ "AUTOGENERATED FILE, DO NOT EDIT"; - - -CM_ "Imported file _bosch_2018.dbc starts here"; -VERSION "" - - -NS_ : - NS_DESC_ - CM_ - BA_DEF_ - BA_ - VAL_ - CAT_DEF_ - CAT_ - FILTER - BA_DEF_DEF_ - EV_DATA_ - ENVVAR_DATA_ - SGTYPE_ - SGTYPE_VAL_ - BA_DEF_SGTYPE_ - BA_SGTYPE_ - SIG_TYPE_REF_ - VAL_TABLE_ - SIG_GROUP_ - SIG_VALTYPE_ - SIGTYPE_VALTYPE_ - BO_TX_BU_ - BA_DEF_REL_ - BA_REL_ - BA_DEF_DEF_REL_ - BU_SG_REL_ - BU_EV_REL_ - BU_BO_REL_ - SG_MUL_VAL_ - -BU_: EBCM EON CAM RADAR PCM EPS VSA SCM BDY XXX EPB - -BO_ 148 KINEMATICS: 8 XXX - SG_ LAT_ACCEL : 7|10@0+ (-0.035,17.92) [-20|20] "m/s2" EON - SG_ LONG_ACCEL : 25|10@0+ (-0.035,17.92) [-20|20] "m/s2" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - -BO_ 228 STEERING_CONTROL: 5 EON - SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS - SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS - SG_ SET_ME_X00_2 : 31|8@0+ (1,0) [0|0] "" EPS - SG_ STEER_TORQUE : 7|16@0- (1,0) [-4096|4096] "" EPS - SG_ STEER_DOWN_TO_ZERO : 38|1@0+ (1,0) [0|1] "" EPS - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" EPS - -BO_ 229 BOSCH_SUPPLEMENTAL_1: 8 XXX - SG_ SET_ME_X04 : 0|8@1+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 8|8@1+ (1,0) [0|255] "" XXX - SG_ SET_ME_X80 : 16|8@1+ (1,0) [0|255] "" XXX - SG_ SET_ME_X10 : 24|8@1+ (1,0) [0|255] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 232 BRAKE_HOLD: 7 XXX - SG_ XMISSION_SPEED : 7|14@0- (1,0) [1|0] "" XXX - SG_ COMPUTER_BRAKE : 39|16@0+ (1,0) [0|0] "" XXX - SG_ COMPUTER_BRAKE_REQUEST : 29|1@0+ (1,0) [0|0] "" XXX - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" XXX - -BO_ 330 STEERING_SENSORS: 8 EPS - SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON - SG_ STEER_ANGLE_RATE : 23|16@0- (-1,0) [-3000|3000] "deg/s" EON - SG_ STEER_SENSOR_STATUS_1 : 34|1@0+ (1,0) [0|1] "" EON - SG_ STEER_SENSOR_STATUS_2 : 33|1@0+ (1,0) [0|1] "" EON - SG_ STEER_SENSOR_STATUS_3 : 32|1@0+ (1,0) [0|1] "" EON - SG_ STEER_WHEEL_ANGLE : 47|16@0- (-0.1,0) [-500|500] "deg" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON - -BO_ 344 ENGINE_DATA: 8 PCM - SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" EON - SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON - SG_ XMISSION_SPEED2 : 39|16@0+ (0.01,0) [0|250] "kph" EON - SG_ ODOMETER : 55|8@0+ (10,0) [0|2550] "m" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON - -BO_ 380 POWERTRAIN_DATA: 8 PCM - SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" EON - SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON - SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" EON - SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "" EON - SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "" EON - SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "" EON - SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "" EON - SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" EON - SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON - -BO_ 399 STEER_STATUS: 7 EPS - SG_ STEER_TORQUE_SENSOR : 7|16@0- (-1,0) [-31000|31000] "tbd" EON - SG_ STEER_ANGLE_RATE : 23|16@0- (-0.1,0) [-31000|31000] "deg/s" EON - SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" EON - SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" EON - SG_ STEER_CONFIG_INDEX : 43|4@0+ (1,0) [0|15] "" EON - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" EON - -BO_ 420 VSA_STATUS: 8 VSA - SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON - SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON - SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" EON - SG_ BRAKE_HOLD_ENABLED : 45|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON - -BO_ 427 STEER_MOTOR_TORQUE: 3 EPS - SG_ CONFIG_VALID : 7|1@0+ (1,0) [0|1] "" EON - SG_ MOTOR_TORQUE : 1|10@0+ (1,0) [0|256] "" EON - SG_ OUTPUT_DISABLED : 22|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" EON - -BO_ 450 EPB_STATUS: 8 EPB - SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" EON - SG_ EPB_STATE : 29|2@0+ (1,0) [0|3] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 464 WHEEL_SPEEDS: 8 VSA - SG_ WHEEL_SPEED_FL : 7|15@0+ (0.01,0) [0|250] "kph" EON - SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON - SG_ WHEEL_SPEED_RL : 25|15@0+ (0.01,0) [0|250] "kph" EON - SG_ WHEEL_SPEED_RR : 42|15@0+ (0.01,0) [0|250] "kph" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - -BO_ 479 ACC_CONTROL: 8 EON - SG_ SET_TO_0 : 20|5@0+ (1,0) [0|1] "" XXX - SG_ CONTROL_ON : 23|3@0+ (1,0) [0|5] "" XXX - SG_ GAS_COMMAND : 7|16@0- (1,0) [0|0] "" XXX - SG_ ACCEL_COMMAND : 31|11@0- (0.01,0) [0|0] "m/s2" XXX - SG_ BRAKE_LIGHTS : 62|1@0+ (1,0) [0|1] "" XXX - SG_ BRAKE_REQUEST : 34|1@0+ (1,0) [0|1] "" XXX - SG_ STANDSTILL : 35|1@0+ (1,0) [0|1] "" XXX - SG_ STANDSTILL_RELEASE : 36|1@0+ (1,0) [0|1] "" XXX - SG_ AEB_STATUS : 33|1@0+ (1,0) [0|1] "" XXX - SG_ AEB_BRAKING : 47|1@0+ (1,0) [0|1] "" XXX - SG_ AEB_PREPARE : 43|1@0+ (1,0) [0|1] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 490 VEHICLE_DYNAMICS: 8 VSA - SG_ LAT_ACCEL : 7|16@0- (0.0015,0) [-20|20] "m/s2" EON - SG_ LONG_ACCEL : 23|16@0- (0.0015,0) [-20|20] "m/s2" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - -BO_ 495 ACC_CONTROL_ON: 8 XXX - SG_ SET_TO_75 : 31|8@0+ (1,0) [0|255] "" XXX - SG_ SET_TO_30 : 39|8@0+ (1,0) [0|255] "" XXX - SG_ ZEROS_BOH : 23|8@0+ (1,0) [0|255] "" XXX - SG_ ZEROS_BOH2 : 47|16@0+ (1,0) [0|255] "" XXX - SG_ SET_TO_FF : 15|8@0+ (1,0) [0|255] "" XXX - SG_ SET_TO_3 : 6|7@0+ (1,0) [0|4095] "" XXX - SG_ CONTROL_ON : 7|1@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - -BO_ 545 XXX_16: 6 SCM - SG_ ECON_ON : 23|1@0+ (1,0) [0|1] "" XXX - SG_ DRIVE_MODE : 37|2@0+ (1,0) [0|3] "" XXX - SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" BDY - -BO_ 576 LEFT_LANE_LINE_1: 8 CAM - SG_ LINE_DISTANCE_VISIBLE : 39|9@0+ (1,0) [0|1] "" XXX - SG_ LINE_PROBABILITY : 46|6@0+ (0.015625,0) [0|1] "" XXX - SG_ LINE_OFFSET : 23|12@0+ (0.004,-8.192) [0|1] "Meters" XXX - SG_ LINE_ANGLE : 7|12@0+ (0.0005,-1.024) [0|1] "" XXX - SG_ FRAME_INDEX : 8|4@1+ (1,0) [0|15] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|1] "" XXX - -BO_ 577 LEFT_LANE_LINE_2: 8 CAM - SG_ LINE_FAR_EDGE_POSITION : 55|8@0+ (1,-128) [0|1] "" XXX - SG_ LINE_SOLID : 13|1@0+ (1,0) [0|1] "" XXX - SG_ LINE_DASHED : 14|1@0+ (1,0) [0|1] "" XXX - SG_ LINE_CURVATURE : 23|12@0+ (0.00001,-0.02048) [0|1] "" XXX - SG_ LINE_PARAMETER : 39|12@0+ (1,0) [0|1] "" XXX - SG_ FRAME_INDEX : 7|4@0+ (1,0) [0|15] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|1] "" XXX - -BO_ 579 RIGHT_LANE_LINE_1: 8 CAM - SG_ LINE_DISTANCE_VISIBLE : 39|9@0+ (1,0) [0|1] "" XXX - SG_ LINE_PROBABILITY : 46|6@0+ (0.015625,0) [0|1] "" XXX - SG_ LINE_OFFSET : 23|12@0+ (0.004,-8.192) [0|1] "Meters" XXX - SG_ LINE_ANGLE : 7|12@0+ (0.0005,-1.024) [0|1] "" XXX - SG_ FRAME_INDEX : 8|4@1+ (1,0) [0|15] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|1] "" XXX - -BO_ 580 RIGHT_LANE_LINE_2: 8 CAM - SG_ LINE_FAR_EDGE_POSITION : 55|8@0+ (1,-128) [0|1] "" XXX - SG_ LINE_SOLID : 13|1@0+ (1,0) [0|1] "" XXX - SG_ LINE_DASHED : 14|1@0+ (1,0) [0|1] "" XXX - SG_ LINE_CURVATURE : 23|12@0+ (0.00001,-0.02048) [0|1] "" XXX - SG_ LINE_PARAMETER : 39|12@0+ (1,0) [0|1] "" XXX - SG_ FRAME_INDEX : 7|4@0+ (1,0) [0|15] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|1] "" XXX - -BO_ 582 ADJACENT_LEFT_LANE_LINE_1: 8 CAM - SG_ LINE_DISTANCE_VISIBLE : 39|9@0+ (1,0) [0|1] "" XXX - SG_ LINE_PROBABILITY : 46|6@0+ (0.015625,0) [0|1] "" XXX - SG_ LINE_OFFSET : 23|12@0+ (0.004,-8.192) [0|1] "Meters" XXX - SG_ LINE_ANGLE : 7|12@0+ (0.0005,-1.024) [0|1] "" XXX - SG_ FRAME_INDEX : 8|4@1+ (1,0) [0|15] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|1] "" XXX - -BO_ 583 ADJACENT_LEFT_LANE_LINE_2: 8 CAM - SG_ LINE_FAR_EDGE_POSITION : 55|8@0+ (1,-128) [0|1] "" XXX - SG_ LINE_SOLID : 13|1@0+ (1,0) [0|1] "" XXX - SG_ LINE_DASHED : 14|1@0+ (1,0) [0|1] "" XXX - SG_ LINE_CURVATURE : 23|12@0+ (0.00001,-0.02048) [0|1] "" XXX - SG_ LINE_PARAMETER : 39|12@0+ (1,0) [0|1] "" XXX - SG_ FRAME_INDEX : 7|4@0+ (1,0) [0|15] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|1] "" XXX - -BO_ 585 ADJACENT_RIGHT_LANE_LINE_1: 8 CAM - SG_ LINE_DISTANCE_VISIBLE : 39|9@0+ (1,0) [0|1] "" XXX - SG_ LINE_PROBABILITY : 46|6@0+ (0.015625,0) [0|1] "" XXX - SG_ LINE_OFFSET : 23|12@0+ (0.004,-8.192) [0|1] "Meters" XXX - SG_ LINE_ANGLE : 7|12@0+ (0.0005,-1.024) [0|1] "" XXX - SG_ FRAME_INDEX : 8|4@1+ (1,0) [0|15] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|1] "" XXX - -BO_ 586 ADJACENT_RIGHT_LANE_LINE_2: 8 CAM - SG_ LINE_FAR_EDGE_POSITION : 55|8@0+ (1,-128) [0|1] "" XXX - SG_ LINE_SOLID : 13|1@0+ (1,0) [0|1] "" XXX - SG_ LINE_DASHED : 14|1@0+ (1,0) [0|1] "" XXX - SG_ LINE_CURVATURE : 23|12@0+ (0.00001,-0.02048) [0|1] "" XXX - SG_ LINE_PARAMETER : 39|12@0+ (1,0) [0|1] "" XXX - SG_ FRAME_INDEX : 7|4@0+ (1,0) [0|15] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|1] "" XXX - -BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA - SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" EON - SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" EON - SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" EON - SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" EON - SG_ SET_TO_X55 : 39|8@0+ (1,0) [0|255] "" XXX - SG_ SET_TO_X55_2 : 47|8@0+ (1,0) [0|255] "" EON - SG_ LONG_COUNTER : 55|8@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - - BO_ 662 SCM_BUTTONS: 4 SCM - SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON - SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" EON - SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" EON - -BO_ 773 SEATBELT_STATUS: 7 BDY - SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON - SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON - SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON - -BO_ 777 CAR_SPEED: 8 PCM - SG_ ROUGH_CAR_SPEED : 23|8@0+ (1,0) [0|255] "mph" XXX - SG_ CAR_SPEED : 7|16@0+ (0.01,0) [0|65535] "kph" XXX - SG_ ROUGH_CAR_SPEED_3 : 39|16@0+ (0.01,0) [0|65535] "kph" XXX - SG_ ROUGH_CAR_SPEED_2 : 31|8@0+ (1,0) [0|255] "mph" XXX - SG_ LOCK_STATUS : 55|2@0+ (1,0) [0|255] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - SG_ IMPERIAL_UNIT : 63|1@0+ (1,0) [0|1] "" XXX - -BO_ 780 ACC_HUD: 8 ADAS - SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "kph" BDY - SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY - SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY - SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY - SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY - SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY - SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY - SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY - SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY - SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY - SG_ ZEROS_BOH : 7|24@0+ (0.002759506,0) [0|100] "m/s" BDY - SG_ FCM_OFF : 35|1@0+ (1,0) [0|1] "" BDY - SG_ SET_TO_1 : 36|1@0+ (1,0) [0|1] "" XXX - SG_ HUD_DISTANCE : 47|2@0+ (1,0) [0|3] "" BDY - SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY - SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY - SG_ ACC_ON : 52|1@0+ (1,0) [0|1] "" XXX - SG_ BOH_6 : 51|4@0+ (1,0) [0|15] "" XXX - SG_ SET_TO_X1 : 55|1@0+ (1,0) [0|1] "" XXX - SG_ IMPERIAL_UNIT : 54|1@0+ (1,0) [0|1] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 804 CRUISE: 8 PCM - SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON - -BO_ 806 SCM_FEEDBACK: 8 SCM - SG_ DRIVERS_DOOR_OPEN : 17|1@0+ (1,0) [0|1] "" XXX - SG_ MAIN_ON : 28|1@0+ (1,0) [0|1] "" EON - SG_ RIGHT_BLINKER : 27|1@0+ (1,0) [0|1] "" EON - SG_ LEFT_BLINKER : 26|1@0+ (1,0) [0|1] "" EON - SG_ CMBS_STATES : 22|2@0+ (1,0) [0|3] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 829 LKAS_HUD: 5 ADAS - SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY - SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY - SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY - SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY - SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY - SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY - SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY - SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY - SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY - SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY - SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY - SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY - SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY - SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY - SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY - -BO_ 862 CAMERA_MESSAGES: 8 CAM - SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY - SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX - SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX - SG_ ZEROS_BOH_2 : 51|4@0+ (1,0) [0|15] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 884 STALK_STATUS: 8 XXX - SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON - SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON - SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON - SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON - SG_ WIPER_SWITCH : 53|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - -BO_ 891 STALK_STATUS_2: 8 XXX - SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON - SG_ LOW_BEAMS : 35|1@0+ (1,0) [0|1] "" XXX - SG_ HIGH_BEAMS : 34|1@0+ (1,0) [0|1] "" XXX - SG_ PARK_LIGHTS : 36|1@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - -BO_ 13274 LKAS_HUD_A: 5 ADAS - SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY - SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY - SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY - SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY - SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY - SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY - SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY - SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY - SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY - SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY - SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY - SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY - SG_ SET_ME_X01 : 20|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY - SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY - -BO_ 13275 LKAS_HUD_B: 8 ADAS - SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY - SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY - SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY - SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY - SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY - SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY - SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY - SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY - SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY - SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY - SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY - SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY - SG_ SET_ME_X01 : 20|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY - SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" BDY - -CM_ SG_ 479 AEB_STATUS "set for the duration of AEB event"; -CM_ SG_ 479 AEB_BRAKING "set when braking is commanded during AEB event"; -CM_ SG_ 479 AEB_PREPARE "set 1s before AEB"; -CM_ SG_ 576 LINE_DISTANCE_VISIBLE "Length of line visible, undecoded"; -CM_ SG_ 577 LINE_FAR_EDGE_POSITION "Appears to be a measure of line thickness, indicates location of the portion of the line furthest from the car, undecoded"; -CM_ SG_ 577 LINE_PARAMETER "Unclear if this is low quality line curvature rate or if this is something else, but it is correlated with line curvature, undecoded"; -CM_ SG_ 577 LINE_DASHED "1 = line is dashed"; -CM_ SG_ 577 LINE_SOLID "1 = line is solid"; -VAL_ 399 STEER_STATUS 6 "tmp_fault" 5 "fault_1" 4 "no_torque_alert_2" 3 "low_speed_lockout" 2 "no_torque_alert_1" 0 "normal" ; - -CM_ "honda_civic_sedan_16_diesel_2019_can.dbc starts here"; - - -BO_ 316 GAS_PEDAL_2: 8 XXX - SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 419 GEARBOX: 8 XXX - SG_ GEAR_SHIFTER : 24|8@1+ (1,0) [0|255] "" XXX - SG_ GEAR : 32|8@1+ (1,0) [0|255] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 432 STANDSTILL: 7 VSA - SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON - SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON - SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" EON - -BO_ 506 LEGACY_BRAKE_COMMAND: 8 ADAS - SG_ CHIME : 40|8@1+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - -BO_ 892 CRUISE_PARAMS: 8 PCM - SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|15] "" EON - -BO_ 927 RADAR_HUD: 8 RADAR - SG_ ZEROS_BOH : 7|10@0+ (1,0) [0|127] "" BDY - SG_ CMBS_OFF : 12|1@0+ (1,0) [0|1] "" BDY - SG_ ZEROS_BOH3 : 31|32@0+ (1,0) [0|4294967295] "" XXX - SG_ RESUME_INSTRUCTION : 21|1@0+ (1,0) [0|1] "" XXX - SG_ SET_TO_1 : 13|1@0+ (1,0) [0|1] "" BDY - SG_ ZEROS_BOH2 : 11|4@0+ (1,0) [0|1] "" XXX - SG_ APPLY_BRAKES_FOR_CANC : 23|1@0+ (1,0) [0|1] "" XXX - SG_ ACC_ALERTS : 20|5@0+ (1,0) [0|1] "" BDY - SG_ SET_TO_0 : 22|1@0+ (1,0) [0|1] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 1029 DOORS_STATUS: 8 BDY - SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" EON - SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" EON - SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" EON - SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" EON - SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON - -VAL_ 419 GEAR_SHIFTER 2 "S" 32 "D" 16 "N" 8 "R" 4 "P" ; -VAL_ 419 GEAR 26 "S" 20 "D" 19 "N" 18 "R" 17 "P" ; -VAL_ 545 ECON_ON_2 0 "off" 3 "on" ; -VAL_ 662 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; -VAL_ 662 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; -VAL_ 806 CMBS_BUTTON 3 "pressed" 0 "released" ; -VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off" ; -VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; - diff --git a/opendbc/honda_civic_touring_2016_can_generated.dbc b/opendbc/honda_civic_touring_2016_can_generated.dbc index 9315c822a..3a2a196fd 100644 --- a/opendbc/honda_civic_touring_2016_can_generated.dbc +++ b/opendbc/honda_civic_touring_2016_can_generated.dbc @@ -1,41 +1,36 @@ CM_ "AUTOGENERATED FILE, DO NOT EDIT"; -CM_ "Imported file _honda_2017.dbc starts here"; -VERSION "" +CM_ "Imported file _comma.dbc starts here"; +BO_ 512 GAS_COMMAND: 6 EON + SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR + SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR + SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR + SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR + SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR + +BO_ 513 GAS_SENSOR: 6 INTERCEPTOR + SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON + SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON + SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON + SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON + +VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; -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_ +CM_ "Imported file _honda_common.dbc starts here"; +BO_ 304 GAS_PEDAL_2: 8 PCM + SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON -BU_: EBCM ADAS PCM EPS VSA SCM BDY XXX EPB EON +BO_ 316 GAS_PEDAL: 8 PCM + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON BO_ 344 ENGINE_DATA: 8 PCM SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" EON @@ -49,14 +44,14 @@ BO_ 380 POWERTRAIN_DATA: 8 PCM SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" EON SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" EON - SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "rpm" EON - SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "rpm" EON - SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "rpm" EON - SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "rpm" EON + SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "" EON + SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "" EON + SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "" EON + SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "" EON SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" EON - SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "rpm" EON + SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "" EON SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON BO_ 420 VSA_STATUS: 8 VSA SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON @@ -75,14 +70,6 @@ BO_ 427 STEER_MOTOR_TORQUE: 3 EPS SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" EON -BO_ 432 STANDSTILL: 7 VSA - SG_ CONTROLLED_STANDSTILL : 0|1@0+ (1,0) [0|1] "" EON - SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON - SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON - SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON - BO_ 464 WHEEL_SPEEDS: 8 VSA SG_ WHEEL_SPEED_FL : 7|15@0+ (0.01,0) [0|250] "kph" EON SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON @@ -91,10 +78,120 @@ BO_ 464 WHEEL_SPEEDS: 8 VSA SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON BO_ 490 VEHICLE_DYNAMICS: 8 VSA - SG_ LONG_ACCEL : 23|16@0- (0.0015384,0) [-20|20] "m/s2" EON + SG_ LAT_ACCEL : 7|16@0- (0.0015,0) [-20|20] "m/s2" EON + SG_ LONG_ACCEL : 23|16@0- (0.0015,0) [-20|20] "m/s2" EON SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON +BO_ 773 SEATBELT_STATUS: 7 BDY + SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 804 CRUISE: 8 PCM + SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" EON + SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" EON + SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON + SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" EON + SG_ BOH2 : 47|8@0- (1,0) [0|255] "" EON + SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 829 LKAS_HUD: 5 ADAS + SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY + SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY + SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY + SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY + SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY + SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY + SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY + SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY + SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY + SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY + SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY + +BO_ 884 STALK_STATUS: 8 XXX + SG_ DASHBOARD_ALERT : 39|8@0+ (1,0) [0|255] "" EON + SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON + SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON + SG_ WIPER_SWITCH : 53|2@0+ (1,0) [0|3] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 891 STALK_STATUS_2: 8 XXX + SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON + SG_ LOW_BEAMS : 35|1@0+ (1,0) [0|1] "" XXX + SG_ HIGH_BEAMS : 34|1@0+ (1,0) [0|1] "" XXX + SG_ PARK_LIGHTS : 36|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 1029 DOORS_STATUS: 8 BDY + SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" EON + SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +CM_ SG_ 304 "Seems to be platform-agnostic"; +CM_ SG_ 316 "Should exist on Nidec"; +CM_ SG_ 420 BRAKE_HOLD_RELATED "On when Brake Hold engaged"; +CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; +CM_ SG_ 773 PASS_AIRBAG_ON "Might just be indicator light"; +CM_ SG_ 773 PASS_AIRBAG_OFF "Might just be indicator light"; +CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; +CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; + +VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep"; +VAL_ 884 DASHBOARD_ALERT 0 "none" 51 "acc_problem" 55 "cmbs_problem" 75 "key_not_detected" 79 "fasten_seatbelt" 111 "lkas_problem" 131 "brake_system_problem" 132 "brake_hold_problem" 139 "tbd" 161 "door_open"; +VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off"; + + +CM_ "Imported file _honda_2017.dbc starts here"; +BO_ 145 KINEMATICS: 8 XXX + SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 148 KINEMATICS_ALT: 8 XXX + SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON + SG_ LONG_ACCEL : 24|9@0- (-0.02,0) [-20|20] "m/s2" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +BO_ 432 STANDSTILL: 7 VSA + SG_ CONTROLLED_STANDSTILL : 0|1@0+ (1,0) [0|1] "" EON + SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 487 BRAKE_PRESSURE: 4 VSA + SG_ BRAKE_PRESSURE1 : 7|10@0+ (0.015625,-103) [0|1000] "" EON + SG_ BRAKE_PRESSURE2 : 9|10@0+ (0.015625,-103) [0|1000] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON + BO_ 506 BRAKE_COMMAND: 8 ADAS SG_ COMPUTER_BRAKE : 7|10@0+ (1,0) [0|1] "" EBCM SG_ SET_ME_X00 : 13|5@0+ (1,0) [0|1] "" EBCM @@ -128,17 +225,6 @@ BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON -BO_ 773 SEATBELT_STATUS: 7 BDY - SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON - SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON - SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON - BO_ 777 LOCK_STATUS: 8 XXX SG_ DOORS_UNLOCKED : 54|1@0+ (1,0) [0|1] "" EON SG_ DOORS_LOCKED : 55|1@0+ (1,0) [0|1] "" EON @@ -172,95 +258,22 @@ BO_ 780 ACC_HUD: 8 ADAS SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY -BO_ 804 CRUISE: 8 PCM - SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" EON - SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" EON - SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON - SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" EON - SG_ BOH2 : 47|8@0- (1,0) [0|255] "" EON - SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - -BO_ 829 LKAS_HUD: 5 ADAS - SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY - SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY - SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY - SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY - SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY - SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY - SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY - SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY - SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY - SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY - SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY - SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY - SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY - SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY - SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY - BO_ 892 CRUISE_PARAMS: 8 PCM SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" EON SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON -BO_ 1029 DOORS_STATUS: 8 BDY - SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" EON - SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" EON - SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" EON - SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" EON - SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - -CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; CM_ SG_ 506 AEB_REQ_1 "set for duration of suspected AEB event"; -CM_ SG_ 773 PASS_AIRBAG_ON "Might just be indicator light"; -CM_ SG_ 773 PASS_AIRBAG_OFF "Might just be indicator light"; CM_ SG_ 780 CRUISE_SPEED "255 = no speed"; -CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; -CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; - -VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw" ; -VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime" ; -VAL_ 506 AEB_STATUS 3 "aeb_prepare" 2 "aeb_ready" 1 "aeb_braking" 0 "no_aeb" ; -VAL_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped" ; -VAL_ 780 HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car" ; -VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; - - -CM_ "Imported file _comma.dbc starts here"; -BO_ 512 GAS_COMMAND: 6 EON - SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR - SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR - SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR - -BO_ 513 GAS_SENSOR: 6 INTERCEPTOR - SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON - SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON - SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON - -VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; +VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw"; +VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime"; +VAL_ 506 AEB_STATUS 3 "aeb_prepare" 2 "aeb_ready" 1 "aeb_braking" 0 "no_aeb"; +VAL_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped"; +VAL_ 780 HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car"; CM_ "honda_civic_touring_2016_can.dbc starts here"; - - -BO_ 148 KINEMATICS: 8 XXX - SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON - SG_ LONG_ACCEL : 24|9@0- (-0.02,0) [-20|20] "m/s2" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - BO_ 228 STEERING_CONTROL: 5 ADAS SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS @@ -269,13 +282,6 @@ BO_ 228 STEERING_CONTROL: 5 ADAS SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" EPS -BO_ 304 GAS_PEDAL_2: 8 PCM - SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON - SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON - SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - BO_ 330 STEERING_SENSORS: 8 EPS SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON SG_ STEER_ANGLE_RATE : 23|16@0- (-1,0) [-3000|3000] "deg/s" EON @@ -310,12 +316,6 @@ BO_ 450 EPB_STATUS: 8 EPB BO_ 493 HUD_SETTING: 5 XXX SG_ IMPERIAL_UNIT : 5|1@0+ (1,0) [0|1] "" EON -BO_ 487 BRAKE_PRESSURE: 4 VSA - SG_ BRAKE_PRESSURE1 : 7|10@0+ (0.015625,-103) [0|1000] "" EON - SG_ BRAKE_PRESSURE2 : 9|10@0+ (0.015625,-103) [0|1000] "" EON - SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EON - SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON - BO_ 545 ECON_STATUS: 6 XXX SG_ ECON_ON_2 : 37|2@0+ (1,0) [0|3] "" EON SG_ ECON_ON : 23|1@0+ (1,0) [0|1] "" EON @@ -345,20 +345,6 @@ BO_ 862 HIGHBEAM_CONTROL: 8 ADAS SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_ 884 STALK_STATUS: 8 XXX - SG_ DASHBOARD_ALERT : 39|8@0+ (1,0) [0|255] "" EON - SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON - SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON - SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON - SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - -BO_ 891 WIPERS: 8 XXX - SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - BO_ 927 RADAR_HUD: 8 ADAS SG_ ZEROS_BOH : 7|17@0+ (1,0) [0|127] "" BDY SG_ APPLY_BRAKES_FOR_CANC : 23|1@0+ (1,0) [0|15] "" BDY @@ -378,7 +364,6 @@ BO_ 1302 ODOMETER: 8 XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON CM_ SG_ 401 GEAR "10 = reverse, 11 = transition"; -CM_ SG_ 420 BRAKE_HOLD_RELATED "On when Brake Hold engaged"; CM_ SG_ 450 EPB_STATE "3 \"engaged\" 2 \"disengaging\" 1 \"engaging\" 0 \"disengaged\""; CM_ SG_ 806 REVERSE_LIGHT "Might be reverse gear selected and not the lights"; @@ -390,7 +375,4 @@ VAL_ 545 ECON_ON_2 0 "off" 3 "on" ; VAL_ 662 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; VAL_ 662 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; VAL_ 806 CMBS_BUTTON 3 "pressed" 0 "released" ; -VAL_ 884 DASHBOARD_ALERT 0 "none" 51 "acc_problem" 55 "cmbs_problem" 75 "key_not_detected" 79 "fasten_seatbelt" 111 "lkas_problem" 131 "brake_system_problem" 132 "brake_hold_problem" 139 "tbd" 161 "door_open" -VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off" ; VAL_ 927 ACC_ALERTS 29 "esp_active_acc_canceled" 10 "b_pedal_applied" 9 "speed_too_low" 8 "speed_too_high" 7 "p_brake_applied" 6 "gear_no_d" 5 "seatbelt" 4 "too_steep_downhill" 3 "too_steep_uphill" 2 "too_close" 1 "no_vehicle_ahead" ; - diff --git a/opendbc/honda_crv_ex_2017_can_generated.dbc b/opendbc/honda_crv_ex_2017_can_generated.dbc index 3be8848bd..95b0f46ba 100644 --- a/opendbc/honda_crv_ex_2017_can_generated.dbc +++ b/opendbc/honda_crv_ex_2017_can_generated.dbc @@ -1,42 +1,154 @@ CM_ "AUTOGENERATED FILE, DO NOT EDIT"; +CM_ "Imported file _honda_common.dbc starts here"; +BO_ 304 GAS_PEDAL_2: 8 PCM + SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 316 GAS_PEDAL: 8 PCM + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 344 ENGINE_DATA: 8 PCM + SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ XMISSION_SPEED2 : 39|16@0+ (0.01,0) [0|250] "kph" EON + SG_ ODOMETER : 55|8@0+ (10,0) [0|2550] "m" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 380 POWERTRAIN_DATA: 8 PCM + SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" EON + SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "" EON + SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "" EON + SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "" EON + SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "" EON + SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" EON + SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 420 VSA_STATUS: 8 VSA + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON + SG_ COMPUTER_BRAKING : 23|1@0+ (1,0) [0|1] "" EON + SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_HOLD_RELATED : 52|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_HOLD_ENABLED : 45|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 427 STEER_MOTOR_TORQUE: 3 EPS + SG_ CONFIG_VALID : 7|1@0+ (1,0) [0|1] "" EON + SG_ MOTOR_TORQUE : 1|10@0+ (1,0) [0|256] "" EON + SG_ OUTPUT_DISABLED : 22|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" EON + +BO_ 464 WHEEL_SPEEDS: 8 VSA + SG_ WHEEL_SPEED_FL : 7|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RL : 25|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RR : 42|15@0+ (0.01,0) [0|250] "kph" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 490 VEHICLE_DYNAMICS: 8 VSA + SG_ LAT_ACCEL : 7|16@0- (0.0015,0) [-20|20] "m/s2" EON + SG_ LONG_ACCEL : 23|16@0- (0.0015,0) [-20|20] "m/s2" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 773 SEATBELT_STATUS: 7 BDY + SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 804 CRUISE: 8 PCM + SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" EON + SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" EON + SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON + SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" EON + SG_ BOH2 : 47|8@0- (1,0) [0|255] "" EON + SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 829 LKAS_HUD: 5 ADAS + SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY + SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY + SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY + SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY + SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY + SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY + SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY + SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY + SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY + SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY + SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY + +BO_ 884 STALK_STATUS: 8 XXX + SG_ DASHBOARD_ALERT : 39|8@0+ (1,0) [0|255] "" EON + SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON + SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON + SG_ WIPER_SWITCH : 53|2@0+ (1,0) [0|3] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 891 STALK_STATUS_2: 8 XXX + SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON + SG_ LOW_BEAMS : 35|1@0+ (1,0) [0|1] "" XXX + SG_ HIGH_BEAMS : 34|1@0+ (1,0) [0|1] "" XXX + SG_ PARK_LIGHTS : 36|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 1029 DOORS_STATUS: 8 BDY + SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" EON + SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +CM_ SG_ 304 "Seems to be platform-agnostic"; +CM_ SG_ 316 "Should exist on Nidec"; +CM_ SG_ 420 BRAKE_HOLD_RELATED "On when Brake Hold engaged"; +CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; +CM_ SG_ 773 PASS_AIRBAG_ON "Might just be indicator light"; +CM_ SG_ 773 PASS_AIRBAG_OFF "Might just be indicator light"; +CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; +CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; + +VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep"; +VAL_ 884 DASHBOARD_ALERT 0 "none" 51 "acc_problem" 55 "cmbs_problem" 75 "key_not_detected" 79 "fasten_seatbelt" 111 "lkas_problem" 131 "brake_system_problem" 132 "brake_hold_problem" 139 "tbd" 161 "door_open"; +VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off"; + + CM_ "Imported file _bosch_2018.dbc starts here"; -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_ - -BU_: EBCM EON CAM RADAR PCM EPS VSA SCM BDY XXX EPB - BO_ 148 KINEMATICS: 8 XXX SG_ LAT_ACCEL : 7|10@0+ (-0.035,17.92) [-20|20] "m/s2" EON SG_ LONG_ACCEL : 25|10@0+ (-0.035,17.92) [-20|20] "m/s2" EON @@ -67,37 +179,6 @@ BO_ 232 BRAKE_HOLD: 7 XXX SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" XXX -BO_ 330 STEERING_SENSORS: 8 EPS - SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON - SG_ STEER_ANGLE_RATE : 23|16@0- (-1,0) [-3000|3000] "deg/s" EON - SG_ STEER_SENSOR_STATUS_1 : 34|1@0+ (1,0) [0|1] "" EON - SG_ STEER_SENSOR_STATUS_2 : 33|1@0+ (1,0) [0|1] "" EON - SG_ STEER_SENSOR_STATUS_3 : 32|1@0+ (1,0) [0|1] "" EON - SG_ STEER_WHEEL_ANGLE : 47|16@0- (-0.1,0) [-500|500] "deg" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON - -BO_ 344 ENGINE_DATA: 8 PCM - SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" EON - SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON - SG_ XMISSION_SPEED2 : 39|16@0+ (0.01,0) [0|250] "kph" EON - SG_ ODOMETER : 55|8@0+ (10,0) [0|2550] "m" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON - -BO_ 380 POWERTRAIN_DATA: 8 PCM - SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" EON - SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON - SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" EON - SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "" EON - SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "" EON - SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "" EON - SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "" EON - SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" EON - SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON - BO_ 399 STEER_STATUS: 7 EPS SG_ STEER_TORQUE_SENSOR : 7|16@0- (-1,0) [-31000|31000] "tbd" EON SG_ STEER_ANGLE_RATE : 23|16@0- (-0.1,0) [-31000|31000] "deg/s" EON @@ -107,34 +188,12 @@ BO_ 399 STEER_STATUS: 7 EPS SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" EON -BO_ 420 VSA_STATUS: 8 VSA - SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON - SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON - SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" EON - SG_ BRAKE_HOLD_ENABLED : 45|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON - -BO_ 427 STEER_MOTOR_TORQUE: 3 EPS - SG_ CONFIG_VALID : 7|1@0+ (1,0) [0|1] "" EON - SG_ MOTOR_TORQUE : 1|10@0+ (1,0) [0|256] "" EON - SG_ OUTPUT_DISABLED : 22|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" EON - BO_ 450 EPB_STATUS: 8 EPB SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" EON SG_ EPB_STATE : 29|2@0+ (1,0) [0|3] "" EON SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_ 464 WHEEL_SPEEDS: 8 VSA - SG_ WHEEL_SPEED_FL : 7|15@0+ (0.01,0) [0|250] "kph" EON - SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON - SG_ WHEEL_SPEED_RL : 25|15@0+ (0.01,0) [0|250] "kph" EON - SG_ WHEEL_SPEED_RR : 42|15@0+ (0.01,0) [0|250] "kph" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - BO_ 479 ACC_CONTROL: 8 EON SG_ SET_TO_0 : 20|5@0+ (1,0) [0|1] "" XXX SG_ CONTROL_ON : 23|3@0+ (1,0) [0|5] "" XXX @@ -150,12 +209,6 @@ BO_ 479 ACC_CONTROL: 8 EON SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_ 490 VEHICLE_DYNAMICS: 8 VSA - SG_ LAT_ACCEL : 7|16@0- (0.0015,0) [-20|20] "m/s2" EON - SG_ LONG_ACCEL : 23|16@0- (0.0015,0) [-20|20] "m/s2" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - BO_ 495 ACC_CONTROL_ON: 8 XXX SG_ SET_TO_75 : 31|8@0+ (1,0) [0|255] "" XXX SG_ SET_TO_30 : 39|8@0+ (1,0) [0|255] "" XXX @@ -260,22 +313,11 @@ BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - BO_ 662 SCM_BUTTONS: 4 SCM - SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON - SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" EON - SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" EON - -BO_ 773 SEATBELT_STATUS: 7 BDY - SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON - SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON - SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON +BO_ 662 SCM_BUTTONS: 4 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" EON BO_ 777 CAR_SPEED: 8 PCM SG_ ROUGH_CAR_SPEED : 23|8@0+ (1,0) [0|255] "mph" XXX @@ -311,11 +353,6 @@ BO_ 780 ACC_HUD: 8 ADAS SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_ 804 CRUISE: 8 PCM - SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON - BO_ 806 SCM_FEEDBACK: 8 SCM SG_ DRIVERS_DOOR_OPEN : 17|1@0+ (1,0) [0|1] "" XXX SG_ MAIN_ON : 28|1@0+ (1,0) [0|1] "" EON @@ -325,27 +362,6 @@ BO_ 806 SCM_FEEDBACK: 8 SCM SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_ 829 LKAS_HUD: 5 ADAS - SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY - SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY - SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY - SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY - SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY - SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY - SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY - SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY - SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY - SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY - SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY - SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY - SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY - SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY - SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY - 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 @@ -354,23 +370,6 @@ BO_ 862 CAMERA_MESSAGES: 8 CAM SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_ 884 STALK_STATUS: 8 XXX - SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON - SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON - SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON - SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON - SG_ WIPER_SWITCH : 53|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - -BO_ 891 STALK_STATUS_2: 8 XXX - SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON - SG_ LOW_BEAMS : 35|1@0+ (1,0) [0|1] "" XXX - SG_ HIGH_BEAMS : 34|1@0+ (1,0) [0|1] "" XXX - SG_ PARK_LIGHTS : 36|1@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - BO_ 13274 LKAS_HUD_A: 5 ADAS SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY @@ -413,6 +412,8 @@ BO_ 13275 LKAS_HUD_B: 8 ADAS SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" BDY +CM_ SG_ 450 EPB_STATE "3: On, 2: Disengaging, 1: Engaging, 0: Off"; +CM_ SG_ 479 CONTROL_ON "Set to 5 when car is being controlled"; CM_ SG_ 479 AEB_STATUS "set for the duration of AEB event"; CM_ SG_ 479 AEB_BRAKING "set when braking is commanded during AEB event"; CM_ SG_ 479 AEB_PREPARE "set 1s before AEB"; @@ -421,18 +422,21 @@ CM_ SG_ 577 LINE_FAR_EDGE_POSITION "Appears to be a measure of line thickness, i CM_ SG_ 577 LINE_PARAMETER "Unclear if this is low quality line curvature rate or if this is something else, but it is correlated with line curvature, undecoded"; CM_ SG_ 577 LINE_DASHED "1 = line is dashed"; CM_ SG_ 577 LINE_SOLID "1 = line is solid"; -VAL_ 399 STEER_STATUS 6 "tmp_fault" 5 "fault_1" 4 "no_torque_alert_2" 3 "low_speed_lockout" 2 "no_torque_alert_1" 0 "normal" ; + +VAL_ 399 STEER_STATUS 6 "tmp_fault" 5 "fault_1" 4 "no_torque_alert_2" 3 "low_speed_lockout" 2 "no_torque_alert_1" 0 "normal"; CM_ "honda_crv_ex_2017_can.dbc starts here"; - -BO_ 304 GAS_PEDAL_2: 8 PCM - SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON - SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON - SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON +BO_ 330 STEERING_SENSORS: 8 EPS + SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON + SG_ STEER_ANGLE_RATE : 23|16@0- (-1,0) [-3000|3000] "deg/s" EON + SG_ STEER_SENSOR_STATUS_1 : 34|1@0+ (1,0) [0|1] "" EON + SG_ STEER_SENSOR_STATUS_2 : 33|1@0+ (1,0) [0|1] "" EON + SG_ STEER_SENSOR_STATUS_3 : 32|1@0+ (1,0) [0|1] "" EON + SG_ STEER_WHEEL_ANGLE : 47|16@0- (-0.1,0) [-500|500] "deg" EON SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON - + BO_ 401 GEARBOX: 8 PCM SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" EON SG_ BOH : 45|6@0+ (1,0) [0|63] "" XXX @@ -467,23 +471,11 @@ BO_ 927 RADAR_HUD: 8 RADAR SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_ 1029 DOORS_STATUS: 8 BDY - SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" EON - SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" EON - SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" EON - SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" EON - SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON - BO_ 1302 ODOMETER: 8 XXX SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" EON SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON -CM_ SG_ 344 DISTANCE_COUNTER ""; -CM_ SG_ 450 EPB_STATE "3: On, 2: Disengaging, 1: Engaging, 0: Off"; -CM_ SG_ 479 CONTROL_ON "Set to 5 when car is being controlled"; CM_ SG_ 479 RELATED_TO_GAS "bits 7, 3, and 1 set to 1 when gas not applied"; CM_ SG_ 479 GAS_BRAKE "Signed value, negative when braking and positive when applying gas"; @@ -493,6 +485,3 @@ VAL_ 545 ECON_ON_2 0 "off" 3 "on" ; VAL_ 662 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; VAL_ 662 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; VAL_ 806 CMBS_BUTTON 3 "pressed" 0 "released" ; -VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off" ; -VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; - diff --git a/opendbc/honda_crv_executive_2016_can_generated.dbc b/opendbc/honda_crv_executive_2016_can_generated.dbc index 55611dd9e..aa11f190c 100644 --- a/opendbc/honda_crv_executive_2016_can_generated.dbc +++ b/opendbc/honda_crv_executive_2016_can_generated.dbc @@ -1,41 +1,36 @@ CM_ "AUTOGENERATED FILE, DO NOT EDIT"; -CM_ "Imported file _honda_2017.dbc starts here"; -VERSION "" +CM_ "Imported file _comma.dbc starts here"; +BO_ 512 GAS_COMMAND: 6 EON + SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR + SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR + SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR + SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR + SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR + +BO_ 513 GAS_SENSOR: 6 INTERCEPTOR + SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON + SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON + SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON + SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON + +VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; -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_ +CM_ "Imported file _honda_common.dbc starts here"; +BO_ 304 GAS_PEDAL_2: 8 PCM + SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON -BU_: EBCM ADAS PCM EPS VSA SCM BDY XXX EPB EON +BO_ 316 GAS_PEDAL: 8 PCM + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON BO_ 344 ENGINE_DATA: 8 PCM SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" EON @@ -49,14 +44,14 @@ BO_ 380 POWERTRAIN_DATA: 8 PCM SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" EON SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" EON - SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "rpm" EON - SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "rpm" EON - SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "rpm" EON - SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "rpm" EON + SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "" EON + SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "" EON + SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "" EON + SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "" EON SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" EON - SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "rpm" EON + SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "" EON SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON BO_ 420 VSA_STATUS: 8 VSA SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON @@ -75,14 +70,6 @@ BO_ 427 STEER_MOTOR_TORQUE: 3 EPS SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" EON -BO_ 432 STANDSTILL: 7 VSA - SG_ CONTROLLED_STANDSTILL : 0|1@0+ (1,0) [0|1] "" EON - SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON - SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON - SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON - BO_ 464 WHEEL_SPEEDS: 8 VSA SG_ WHEEL_SPEED_FL : 7|15@0+ (0.01,0) [0|250] "kph" EON SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON @@ -91,10 +78,120 @@ BO_ 464 WHEEL_SPEEDS: 8 VSA SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON BO_ 490 VEHICLE_DYNAMICS: 8 VSA - SG_ LONG_ACCEL : 23|16@0- (0.0015384,0) [-20|20] "m/s2" EON + SG_ LAT_ACCEL : 7|16@0- (0.0015,0) [-20|20] "m/s2" EON + SG_ LONG_ACCEL : 23|16@0- (0.0015,0) [-20|20] "m/s2" EON SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON +BO_ 773 SEATBELT_STATUS: 7 BDY + SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 804 CRUISE: 8 PCM + SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" EON + SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" EON + SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON + SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" EON + SG_ BOH2 : 47|8@0- (1,0) [0|255] "" EON + SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 829 LKAS_HUD: 5 ADAS + SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY + SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY + SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY + SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY + SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY + SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY + SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY + SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY + SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY + SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY + SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY + +BO_ 884 STALK_STATUS: 8 XXX + SG_ DASHBOARD_ALERT : 39|8@0+ (1,0) [0|255] "" EON + SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON + SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON + SG_ WIPER_SWITCH : 53|2@0+ (1,0) [0|3] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 891 STALK_STATUS_2: 8 XXX + SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON + SG_ LOW_BEAMS : 35|1@0+ (1,0) [0|1] "" XXX + SG_ HIGH_BEAMS : 34|1@0+ (1,0) [0|1] "" XXX + SG_ PARK_LIGHTS : 36|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 1029 DOORS_STATUS: 8 BDY + SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" EON + SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +CM_ SG_ 304 "Seems to be platform-agnostic"; +CM_ SG_ 316 "Should exist on Nidec"; +CM_ SG_ 420 BRAKE_HOLD_RELATED "On when Brake Hold engaged"; +CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; +CM_ SG_ 773 PASS_AIRBAG_ON "Might just be indicator light"; +CM_ SG_ 773 PASS_AIRBAG_OFF "Might just be indicator light"; +CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; +CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; + +VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep"; +VAL_ 884 DASHBOARD_ALERT 0 "none" 51 "acc_problem" 55 "cmbs_problem" 75 "key_not_detected" 79 "fasten_seatbelt" 111 "lkas_problem" 131 "brake_system_problem" 132 "brake_hold_problem" 139 "tbd" 161 "door_open"; +VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off"; + + +CM_ "Imported file _honda_2017.dbc starts here"; +BO_ 145 KINEMATICS: 8 XXX + SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 148 KINEMATICS_ALT: 8 XXX + SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON + SG_ LONG_ACCEL : 24|9@0- (-0.02,0) [-20|20] "m/s2" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +BO_ 432 STANDSTILL: 7 VSA + SG_ CONTROLLED_STANDSTILL : 0|1@0+ (1,0) [0|1] "" EON + SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 487 BRAKE_PRESSURE: 4 VSA + SG_ BRAKE_PRESSURE1 : 7|10@0+ (0.015625,-103) [0|1000] "" EON + SG_ BRAKE_PRESSURE2 : 9|10@0+ (0.015625,-103) [0|1000] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON + BO_ 506 BRAKE_COMMAND: 8 ADAS SG_ COMPUTER_BRAKE : 7|10@0+ (1,0) [0|1] "" EBCM SG_ SET_ME_X00 : 13|5@0+ (1,0) [0|1] "" EBCM @@ -128,17 +225,6 @@ BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON -BO_ 773 SEATBELT_STATUS: 7 BDY - SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON - SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON - SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON - BO_ 777 LOCK_STATUS: 8 XXX SG_ DOORS_UNLOCKED : 54|1@0+ (1,0) [0|1] "" EON SG_ DOORS_LOCKED : 55|1@0+ (1,0) [0|1] "" EON @@ -172,89 +258,22 @@ BO_ 780 ACC_HUD: 8 ADAS SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY -BO_ 804 CRUISE: 8 PCM - SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" EON - SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" EON - SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON - SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" EON - SG_ BOH2 : 47|8@0- (1,0) [0|255] "" EON - SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - -BO_ 829 LKAS_HUD: 5 ADAS - SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY - SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY - SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY - SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY - SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY - SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY - SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY - SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY - SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY - SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY - SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY - SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY - SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY - SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY - SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY - BO_ 892 CRUISE_PARAMS: 8 PCM SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" EON SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON -BO_ 1029 DOORS_STATUS: 8 BDY - SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" EON - SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" EON - SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" EON - SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" EON - SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - -CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; CM_ SG_ 506 AEB_REQ_1 "set for duration of suspected AEB event"; -CM_ SG_ 773 PASS_AIRBAG_ON "Might just be indicator light"; -CM_ SG_ 773 PASS_AIRBAG_OFF "Might just be indicator light"; CM_ SG_ 780 CRUISE_SPEED "255 = no speed"; -CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; -CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; - -VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw" ; -VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime" ; -VAL_ 506 AEB_STATUS 3 "aeb_prepare" 2 "aeb_ready" 1 "aeb_braking" 0 "no_aeb" ; -VAL_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped" ; -VAL_ 780 HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car" ; -VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; - - -CM_ "Imported file _comma.dbc starts here"; -BO_ 512 GAS_COMMAND: 6 EON - SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR - SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR - SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR - -BO_ 513 GAS_SENSOR: 6 INTERCEPTOR - SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON - SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON - SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON - -VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; +VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw"; +VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime"; +VAL_ 506 AEB_STATUS 3 "aeb_prepare" 2 "aeb_ready" 1 "aeb_braking" 0 "no_aeb"; +VAL_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped"; +VAL_ 780 HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car"; CM_ "honda_crv_executive_2016_can.dbc starts here"; - - BO_ 342 STEERING_SENSORS: 6 EPS SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON SG_ STEER_ANGLE_RATE : 23|16@0- (1,0) [-3000|3000] "deg/s" EON @@ -291,12 +310,6 @@ BO_ 422 SCM_BUTTONS: 8 SCM SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON -BO_ 487 BRAKE_PRESSURE: 4 VSA - SG_ BRAKE_PRESSURE1 : 7|10@0+ (0.015625,-103) [0|1000] "" EON - SG_ BRAKE_PRESSURE2 : 9|10@0+ (0.015625,-103) [0|1000] "" EON - SG_ COUNTER : 29|2@0+ (1,0) [0|15] "" EON - SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EON - BO_ 660 SCM_FEEDBACK: 8 SCM SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" EON SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" EON @@ -304,15 +317,8 @@ BO_ 660 SCM_FEEDBACK: 8 SCM SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON -BO_ 891 WIPERS: 8 XXX - SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - 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_ 419 GEAR_SHIFTER 32 "D" 8 "R" 4 "P" ; VAL_ 422 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; VAL_ 422 LIGHTS_SETTING 3 "high_beam" 2 "low_beam" 1 "position" 0 "no_lights" ; VAL_ 422 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; -VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off" ; - diff --git a/opendbc/honda_crv_hybrid_2019_can_generated.dbc b/opendbc/honda_crv_hybrid_2019_can_generated.dbc deleted file mode 100644 index 01a24c96c..000000000 --- a/opendbc/honda_crv_hybrid_2019_can_generated.dbc +++ /dev/null @@ -1,480 +0,0 @@ -CM_ "AUTOGENERATED FILE, DO NOT EDIT"; - - -CM_ "Imported file _bosch_2018.dbc starts here"; -VERSION "" - - -NS_ : - NS_DESC_ - CM_ - BA_DEF_ - BA_ - VAL_ - CAT_DEF_ - CAT_ - FILTER - BA_DEF_DEF_ - EV_DATA_ - ENVVAR_DATA_ - SGTYPE_ - SGTYPE_VAL_ - BA_DEF_SGTYPE_ - BA_SGTYPE_ - SIG_TYPE_REF_ - VAL_TABLE_ - SIG_GROUP_ - SIG_VALTYPE_ - SIGTYPE_VALTYPE_ - BO_TX_BU_ - BA_DEF_REL_ - BA_REL_ - BA_DEF_DEF_REL_ - BU_SG_REL_ - BU_EV_REL_ - BU_BO_REL_ - SG_MUL_VAL_ - -BU_: EBCM EON CAM RADAR PCM EPS VSA SCM BDY XXX EPB - -BO_ 148 KINEMATICS: 8 XXX - SG_ LAT_ACCEL : 7|10@0+ (-0.035,17.92) [-20|20] "m/s2" EON - SG_ LONG_ACCEL : 25|10@0+ (-0.035,17.92) [-20|20] "m/s2" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - -BO_ 228 STEERING_CONTROL: 5 EON - SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS - SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS - SG_ SET_ME_X00_2 : 31|8@0+ (1,0) [0|0] "" EPS - SG_ STEER_TORQUE : 7|16@0- (1,0) [-4096|4096] "" EPS - SG_ STEER_DOWN_TO_ZERO : 38|1@0+ (1,0) [0|1] "" EPS - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" EPS - -BO_ 229 BOSCH_SUPPLEMENTAL_1: 8 XXX - SG_ SET_ME_X04 : 0|8@1+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 8|8@1+ (1,0) [0|255] "" XXX - SG_ SET_ME_X80 : 16|8@1+ (1,0) [0|255] "" XXX - SG_ SET_ME_X10 : 24|8@1+ (1,0) [0|255] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 232 BRAKE_HOLD: 7 XXX - SG_ XMISSION_SPEED : 7|14@0- (1,0) [1|0] "" XXX - SG_ COMPUTER_BRAKE : 39|16@0+ (1,0) [0|0] "" XXX - SG_ COMPUTER_BRAKE_REQUEST : 29|1@0+ (1,0) [0|0] "" XXX - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" XXX - -BO_ 330 STEERING_SENSORS: 8 EPS - SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON - SG_ STEER_ANGLE_RATE : 23|16@0- (-1,0) [-3000|3000] "deg/s" EON - SG_ STEER_SENSOR_STATUS_1 : 34|1@0+ (1,0) [0|1] "" EON - SG_ STEER_SENSOR_STATUS_2 : 33|1@0+ (1,0) [0|1] "" EON - SG_ STEER_SENSOR_STATUS_3 : 32|1@0+ (1,0) [0|1] "" EON - SG_ STEER_WHEEL_ANGLE : 47|16@0- (-0.1,0) [-500|500] "deg" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON - -BO_ 344 ENGINE_DATA: 8 PCM - SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" EON - SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON - SG_ XMISSION_SPEED2 : 39|16@0+ (0.01,0) [0|250] "kph" EON - SG_ ODOMETER : 55|8@0+ (10,0) [0|2550] "m" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON - -BO_ 380 POWERTRAIN_DATA: 8 PCM - SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" EON - SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON - SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" EON - SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "" EON - SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "" EON - SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "" EON - SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "" EON - SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" EON - SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON - -BO_ 399 STEER_STATUS: 7 EPS - SG_ STEER_TORQUE_SENSOR : 7|16@0- (-1,0) [-31000|31000] "tbd" EON - SG_ STEER_ANGLE_RATE : 23|16@0- (-0.1,0) [-31000|31000] "deg/s" EON - SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" EON - SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" EON - SG_ STEER_CONFIG_INDEX : 43|4@0+ (1,0) [0|15] "" EON - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" EON - -BO_ 420 VSA_STATUS: 8 VSA - SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON - SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON - SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" EON - SG_ BRAKE_HOLD_ENABLED : 45|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON - -BO_ 427 STEER_MOTOR_TORQUE: 3 EPS - SG_ CONFIG_VALID : 7|1@0+ (1,0) [0|1] "" EON - SG_ MOTOR_TORQUE : 1|10@0+ (1,0) [0|256] "" EON - SG_ OUTPUT_DISABLED : 22|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" EON - -BO_ 450 EPB_STATUS: 8 EPB - SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" EON - SG_ EPB_STATE : 29|2@0+ (1,0) [0|3] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 464 WHEEL_SPEEDS: 8 VSA - SG_ WHEEL_SPEED_FL : 7|15@0+ (0.01,0) [0|250] "kph" EON - SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON - SG_ WHEEL_SPEED_RL : 25|15@0+ (0.01,0) [0|250] "kph" EON - SG_ WHEEL_SPEED_RR : 42|15@0+ (0.01,0) [0|250] "kph" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - -BO_ 479 ACC_CONTROL: 8 EON - SG_ SET_TO_0 : 20|5@0+ (1,0) [0|1] "" XXX - SG_ CONTROL_ON : 23|3@0+ (1,0) [0|5] "" XXX - SG_ GAS_COMMAND : 7|16@0- (1,0) [0|0] "" XXX - SG_ ACCEL_COMMAND : 31|11@0- (0.01,0) [0|0] "m/s2" XXX - SG_ BRAKE_LIGHTS : 62|1@0+ (1,0) [0|1] "" XXX - SG_ BRAKE_REQUEST : 34|1@0+ (1,0) [0|1] "" XXX - SG_ STANDSTILL : 35|1@0+ (1,0) [0|1] "" XXX - SG_ STANDSTILL_RELEASE : 36|1@0+ (1,0) [0|1] "" XXX - SG_ AEB_STATUS : 33|1@0+ (1,0) [0|1] "" XXX - SG_ AEB_BRAKING : 47|1@0+ (1,0) [0|1] "" XXX - SG_ AEB_PREPARE : 43|1@0+ (1,0) [0|1] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 490 VEHICLE_DYNAMICS: 8 VSA - SG_ LAT_ACCEL : 7|16@0- (0.0015,0) [-20|20] "m/s2" EON - SG_ LONG_ACCEL : 23|16@0- (0.0015,0) [-20|20] "m/s2" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - -BO_ 495 ACC_CONTROL_ON: 8 XXX - SG_ SET_TO_75 : 31|8@0+ (1,0) [0|255] "" XXX - SG_ SET_TO_30 : 39|8@0+ (1,0) [0|255] "" XXX - SG_ ZEROS_BOH : 23|8@0+ (1,0) [0|255] "" XXX - SG_ ZEROS_BOH2 : 47|16@0+ (1,0) [0|255] "" XXX - SG_ SET_TO_FF : 15|8@0+ (1,0) [0|255] "" XXX - SG_ SET_TO_3 : 6|7@0+ (1,0) [0|4095] "" XXX - SG_ CONTROL_ON : 7|1@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - -BO_ 545 XXX_16: 6 SCM - SG_ ECON_ON : 23|1@0+ (1,0) [0|1] "" XXX - SG_ DRIVE_MODE : 37|2@0+ (1,0) [0|3] "" XXX - SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" BDY - -BO_ 576 LEFT_LANE_LINE_1: 8 CAM - SG_ LINE_DISTANCE_VISIBLE : 39|9@0+ (1,0) [0|1] "" XXX - SG_ LINE_PROBABILITY : 46|6@0+ (0.015625,0) [0|1] "" XXX - SG_ LINE_OFFSET : 23|12@0+ (0.004,-8.192) [0|1] "Meters" XXX - SG_ LINE_ANGLE : 7|12@0+ (0.0005,-1.024) [0|1] "" XXX - SG_ FRAME_INDEX : 8|4@1+ (1,0) [0|15] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|1] "" XXX - -BO_ 577 LEFT_LANE_LINE_2: 8 CAM - SG_ LINE_FAR_EDGE_POSITION : 55|8@0+ (1,-128) [0|1] "" XXX - SG_ LINE_SOLID : 13|1@0+ (1,0) [0|1] "" XXX - SG_ LINE_DASHED : 14|1@0+ (1,0) [0|1] "" XXX - SG_ LINE_CURVATURE : 23|12@0+ (0.00001,-0.02048) [0|1] "" XXX - SG_ LINE_PARAMETER : 39|12@0+ (1,0) [0|1] "" XXX - SG_ FRAME_INDEX : 7|4@0+ (1,0) [0|15] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|1] "" XXX - -BO_ 579 RIGHT_LANE_LINE_1: 8 CAM - SG_ LINE_DISTANCE_VISIBLE : 39|9@0+ (1,0) [0|1] "" XXX - SG_ LINE_PROBABILITY : 46|6@0+ (0.015625,0) [0|1] "" XXX - SG_ LINE_OFFSET : 23|12@0+ (0.004,-8.192) [0|1] "Meters" XXX - SG_ LINE_ANGLE : 7|12@0+ (0.0005,-1.024) [0|1] "" XXX - SG_ FRAME_INDEX : 8|4@1+ (1,0) [0|15] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|1] "" XXX - -BO_ 580 RIGHT_LANE_LINE_2: 8 CAM - SG_ LINE_FAR_EDGE_POSITION : 55|8@0+ (1,-128) [0|1] "" XXX - SG_ LINE_SOLID : 13|1@0+ (1,0) [0|1] "" XXX - SG_ LINE_DASHED : 14|1@0+ (1,0) [0|1] "" XXX - SG_ LINE_CURVATURE : 23|12@0+ (0.00001,-0.02048) [0|1] "" XXX - SG_ LINE_PARAMETER : 39|12@0+ (1,0) [0|1] "" XXX - SG_ FRAME_INDEX : 7|4@0+ (1,0) [0|15] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|1] "" XXX - -BO_ 582 ADJACENT_LEFT_LANE_LINE_1: 8 CAM - SG_ LINE_DISTANCE_VISIBLE : 39|9@0+ (1,0) [0|1] "" XXX - SG_ LINE_PROBABILITY : 46|6@0+ (0.015625,0) [0|1] "" XXX - SG_ LINE_OFFSET : 23|12@0+ (0.004,-8.192) [0|1] "Meters" XXX - SG_ LINE_ANGLE : 7|12@0+ (0.0005,-1.024) [0|1] "" XXX - SG_ FRAME_INDEX : 8|4@1+ (1,0) [0|15] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|1] "" XXX - -BO_ 583 ADJACENT_LEFT_LANE_LINE_2: 8 CAM - SG_ LINE_FAR_EDGE_POSITION : 55|8@0+ (1,-128) [0|1] "" XXX - SG_ LINE_SOLID : 13|1@0+ (1,0) [0|1] "" XXX - SG_ LINE_DASHED : 14|1@0+ (1,0) [0|1] "" XXX - SG_ LINE_CURVATURE : 23|12@0+ (0.00001,-0.02048) [0|1] "" XXX - SG_ LINE_PARAMETER : 39|12@0+ (1,0) [0|1] "" XXX - SG_ FRAME_INDEX : 7|4@0+ (1,0) [0|15] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|1] "" XXX - -BO_ 585 ADJACENT_RIGHT_LANE_LINE_1: 8 CAM - SG_ LINE_DISTANCE_VISIBLE : 39|9@0+ (1,0) [0|1] "" XXX - SG_ LINE_PROBABILITY : 46|6@0+ (0.015625,0) [0|1] "" XXX - SG_ LINE_OFFSET : 23|12@0+ (0.004,-8.192) [0|1] "Meters" XXX - SG_ LINE_ANGLE : 7|12@0+ (0.0005,-1.024) [0|1] "" XXX - SG_ FRAME_INDEX : 8|4@1+ (1,0) [0|15] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|1] "" XXX - -BO_ 586 ADJACENT_RIGHT_LANE_LINE_2: 8 CAM - SG_ LINE_FAR_EDGE_POSITION : 55|8@0+ (1,-128) [0|1] "" XXX - SG_ LINE_SOLID : 13|1@0+ (1,0) [0|1] "" XXX - SG_ LINE_DASHED : 14|1@0+ (1,0) [0|1] "" XXX - SG_ LINE_CURVATURE : 23|12@0+ (0.00001,-0.02048) [0|1] "" XXX - SG_ LINE_PARAMETER : 39|12@0+ (1,0) [0|1] "" XXX - SG_ FRAME_INDEX : 7|4@0+ (1,0) [0|15] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|1] "" XXX - -BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA - SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" EON - SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" EON - SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" EON - SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" EON - SG_ SET_TO_X55 : 39|8@0+ (1,0) [0|255] "" XXX - SG_ SET_TO_X55_2 : 47|8@0+ (1,0) [0|255] "" EON - SG_ LONG_COUNTER : 55|8@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - - BO_ 662 SCM_BUTTONS: 4 SCM - SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON - SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" EON - SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" EON - -BO_ 773 SEATBELT_STATUS: 7 BDY - SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON - SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON - SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON - -BO_ 777 CAR_SPEED: 8 PCM - SG_ ROUGH_CAR_SPEED : 23|8@0+ (1,0) [0|255] "mph" XXX - SG_ CAR_SPEED : 7|16@0+ (0.01,0) [0|65535] "kph" XXX - SG_ ROUGH_CAR_SPEED_3 : 39|16@0+ (0.01,0) [0|65535] "kph" XXX - SG_ ROUGH_CAR_SPEED_2 : 31|8@0+ (1,0) [0|255] "mph" XXX - SG_ LOCK_STATUS : 55|2@0+ (1,0) [0|255] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - SG_ IMPERIAL_UNIT : 63|1@0+ (1,0) [0|1] "" XXX - -BO_ 780 ACC_HUD: 8 ADAS - SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "kph" BDY - SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY - SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY - SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY - SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY - SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY - SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY - SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY - SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY - SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY - SG_ ZEROS_BOH : 7|24@0+ (0.002759506,0) [0|100] "m/s" BDY - SG_ FCM_OFF : 35|1@0+ (1,0) [0|1] "" BDY - SG_ SET_TO_1 : 36|1@0+ (1,0) [0|1] "" XXX - SG_ HUD_DISTANCE : 47|2@0+ (1,0) [0|3] "" BDY - SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY - SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY - SG_ ACC_ON : 52|1@0+ (1,0) [0|1] "" XXX - SG_ BOH_6 : 51|4@0+ (1,0) [0|15] "" XXX - SG_ SET_TO_X1 : 55|1@0+ (1,0) [0|1] "" XXX - SG_ IMPERIAL_UNIT : 54|1@0+ (1,0) [0|1] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 804 CRUISE: 8 PCM - SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON - -BO_ 806 SCM_FEEDBACK: 8 SCM - SG_ DRIVERS_DOOR_OPEN : 17|1@0+ (1,0) [0|1] "" XXX - SG_ MAIN_ON : 28|1@0+ (1,0) [0|1] "" EON - SG_ RIGHT_BLINKER : 27|1@0+ (1,0) [0|1] "" EON - SG_ LEFT_BLINKER : 26|1@0+ (1,0) [0|1] "" EON - SG_ CMBS_STATES : 22|2@0+ (1,0) [0|3] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 829 LKAS_HUD: 5 ADAS - SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY - SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY - SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY - SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY - SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY - SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY - SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY - SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY - SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY - SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY - SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY - SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY - SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY - SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY - SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY - -BO_ 862 CAMERA_MESSAGES: 8 CAM - SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY - SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX - SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX - SG_ ZEROS_BOH_2 : 51|4@0+ (1,0) [0|15] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 884 STALK_STATUS: 8 XXX - SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON - SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON - SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON - SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON - SG_ WIPER_SWITCH : 53|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - -BO_ 891 STALK_STATUS_2: 8 XXX - SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON - SG_ LOW_BEAMS : 35|1@0+ (1,0) [0|1] "" XXX - SG_ HIGH_BEAMS : 34|1@0+ (1,0) [0|1] "" XXX - SG_ PARK_LIGHTS : 36|1@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - -BO_ 13274 LKAS_HUD_A: 5 ADAS - SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY - SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY - SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY - SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY - SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY - SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY - SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY - SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY - SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY - SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY - SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY - SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY - SG_ SET_ME_X01 : 20|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY - SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY - -BO_ 13275 LKAS_HUD_B: 8 ADAS - SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY - SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY - SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY - SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY - SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY - SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY - SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY - SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY - SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY - SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY - SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY - SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY - SG_ SET_ME_X01 : 20|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY - SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" BDY - -CM_ SG_ 479 AEB_STATUS "set for the duration of AEB event"; -CM_ SG_ 479 AEB_BRAKING "set when braking is commanded during AEB event"; -CM_ SG_ 479 AEB_PREPARE "set 1s before AEB"; -CM_ SG_ 576 LINE_DISTANCE_VISIBLE "Length of line visible, undecoded"; -CM_ SG_ 577 LINE_FAR_EDGE_POSITION "Appears to be a measure of line thickness, indicates location of the portion of the line furthest from the car, undecoded"; -CM_ SG_ 577 LINE_PARAMETER "Unclear if this is low quality line curvature rate or if this is something else, but it is correlated with line curvature, undecoded"; -CM_ SG_ 577 LINE_DASHED "1 = line is dashed"; -CM_ SG_ 577 LINE_SOLID "1 = line is solid"; -VAL_ 399 STEER_STATUS 6 "tmp_fault" 5 "fault_1" 4 "no_torque_alert_2" 3 "low_speed_lockout" 2 "no_torque_alert_1" 0 "normal" ; - -CM_ "honda_crv_hybrid_2019_can.dbc starts here"; - - -BO_ 304 GAS_PEDAL_2: 8 PCM - SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON - SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON - SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON - -BO_ 419 GEARBOX: 8 PCM - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - SG_ GEAR_SHIFTER : 29|6@0+ (1,0) [0|63] "" EON - SG_ GEAR : 7|8@0+ (1,0) [0|255] "" EON - -BO_ 432 STANDSTILL: 7 VSA - SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON - SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON - SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" EON - -BO_ 927 RADAR_HUD: 8 RADAR - SG_ ZEROS_BOH : 7|10@0+ (1,0) [0|127] "" BDY - SG_ CMBS_OFF : 12|1@0+ (1,0) [0|1] "" BDY - SG_ ZEROS_BOH3 : 31|32@0+ (1,0) [0|4294967295] "" XXX - SG_ RESUME_INSTRUCTION : 21|1@0+ (1,0) [0|1] "" XXX - SG_ SET_TO_1 : 13|1@0+ (1,0) [0|1] "" BDY - SG_ ZEROS_BOH2 : 11|4@0+ (1,0) [0|1] "" XXX - SG_ APPLY_BRAKES_FOR_CANC : 23|1@0+ (1,0) [0|1] "" XXX - SG_ ACC_ALERTS : 20|5@0+ (1,0) [0|1] "" BDY - SG_ SET_TO_0 : 22|1@0+ (1,0) [0|1] "" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX - -BO_ 1302 ODOMETER: 8 XXX - SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - -CM_ SG_ 344 DISTANCE_COUNTER ""; -CM_ SG_ 450 EPB_STATE "3: On, 2: Disengaging, 1: Engaging, 0: Off"; -CM_ SG_ 479 CONTROL_ON "Set to 5 when car is being controlled"; -CM_ SG_ 479 RELATED_TO_GAS "bits 7, 3, and 1 set to 1 when gas not applied"; -CM_ SG_ 479 GAS_BRAKE "Signed value, negative when braking and positive when applying gas"; - -VAL_ 419 GEAR_SHIFTER 32 "D" 8 "R" 4 "P" ; -VAL_ 545 ECON_ON_2 0 "off" 3 "on" ; -VAL_ 662 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; -VAL_ 662 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; -VAL_ 806 CMBS_BUTTON 3 "pressed" 0 "released" ; -VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off" ; -VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; - diff --git a/opendbc/honda_crv_touring_2016_can_generated.dbc b/opendbc/honda_crv_touring_2016_can_generated.dbc index 45d85cad7..b32b6cb59 100644 --- a/opendbc/honda_crv_touring_2016_can_generated.dbc +++ b/opendbc/honda_crv_touring_2016_can_generated.dbc @@ -1,41 +1,36 @@ CM_ "AUTOGENERATED FILE, DO NOT EDIT"; -CM_ "Imported file _honda_2017.dbc starts here"; -VERSION "" +CM_ "Imported file _comma.dbc starts here"; +BO_ 512 GAS_COMMAND: 6 EON + SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR + SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR + SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR + SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR + SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR + +BO_ 513 GAS_SENSOR: 6 INTERCEPTOR + SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON + SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON + SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON + SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON + +VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; -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_ +CM_ "Imported file _honda_common.dbc starts here"; +BO_ 304 GAS_PEDAL_2: 8 PCM + SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON -BU_: EBCM ADAS PCM EPS VSA SCM BDY XXX EPB EON +BO_ 316 GAS_PEDAL: 8 PCM + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON BO_ 344 ENGINE_DATA: 8 PCM SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" EON @@ -49,14 +44,14 @@ BO_ 380 POWERTRAIN_DATA: 8 PCM SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" EON SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" EON - SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "rpm" EON - SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "rpm" EON - SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "rpm" EON - SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "rpm" EON + SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "" EON + SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "" EON + SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "" EON + SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "" EON SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" EON - SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "rpm" EON + SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "" EON SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON BO_ 420 VSA_STATUS: 8 VSA SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON @@ -75,14 +70,6 @@ BO_ 427 STEER_MOTOR_TORQUE: 3 EPS SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" EON -BO_ 432 STANDSTILL: 7 VSA - SG_ CONTROLLED_STANDSTILL : 0|1@0+ (1,0) [0|1] "" EON - SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON - SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON - SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON - BO_ 464 WHEEL_SPEEDS: 8 VSA SG_ WHEEL_SPEED_FL : 7|15@0+ (0.01,0) [0|250] "kph" EON SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON @@ -91,10 +78,120 @@ BO_ 464 WHEEL_SPEEDS: 8 VSA SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON BO_ 490 VEHICLE_DYNAMICS: 8 VSA - SG_ LONG_ACCEL : 23|16@0- (0.0015384,0) [-20|20] "m/s2" EON + SG_ LAT_ACCEL : 7|16@0- (0.0015,0) [-20|20] "m/s2" EON + SG_ LONG_ACCEL : 23|16@0- (0.0015,0) [-20|20] "m/s2" EON SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON +BO_ 773 SEATBELT_STATUS: 7 BDY + SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 804 CRUISE: 8 PCM + SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" EON + SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" EON + SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON + SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" EON + SG_ BOH2 : 47|8@0- (1,0) [0|255] "" EON + SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 829 LKAS_HUD: 5 ADAS + SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY + SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY + SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY + SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY + SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY + SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY + SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY + SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY + SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY + SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY + SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY + +BO_ 884 STALK_STATUS: 8 XXX + SG_ DASHBOARD_ALERT : 39|8@0+ (1,0) [0|255] "" EON + SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON + SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON + SG_ WIPER_SWITCH : 53|2@0+ (1,0) [0|3] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 891 STALK_STATUS_2: 8 XXX + SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON + SG_ LOW_BEAMS : 35|1@0+ (1,0) [0|1] "" XXX + SG_ HIGH_BEAMS : 34|1@0+ (1,0) [0|1] "" XXX + SG_ PARK_LIGHTS : 36|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 1029 DOORS_STATUS: 8 BDY + SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" EON + SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +CM_ SG_ 304 "Seems to be platform-agnostic"; +CM_ SG_ 316 "Should exist on Nidec"; +CM_ SG_ 420 BRAKE_HOLD_RELATED "On when Brake Hold engaged"; +CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; +CM_ SG_ 773 PASS_AIRBAG_ON "Might just be indicator light"; +CM_ SG_ 773 PASS_AIRBAG_OFF "Might just be indicator light"; +CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; +CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; + +VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep"; +VAL_ 884 DASHBOARD_ALERT 0 "none" 51 "acc_problem" 55 "cmbs_problem" 75 "key_not_detected" 79 "fasten_seatbelt" 111 "lkas_problem" 131 "brake_system_problem" 132 "brake_hold_problem" 139 "tbd" 161 "door_open"; +VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off"; + + +CM_ "Imported file _honda_2017.dbc starts here"; +BO_ 145 KINEMATICS: 8 XXX + SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 148 KINEMATICS_ALT: 8 XXX + SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON + SG_ LONG_ACCEL : 24|9@0- (-0.02,0) [-20|20] "m/s2" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +BO_ 432 STANDSTILL: 7 VSA + SG_ CONTROLLED_STANDSTILL : 0|1@0+ (1,0) [0|1] "" EON + SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 487 BRAKE_PRESSURE: 4 VSA + SG_ BRAKE_PRESSURE1 : 7|10@0+ (0.015625,-103) [0|1000] "" EON + SG_ BRAKE_PRESSURE2 : 9|10@0+ (0.015625,-103) [0|1000] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON + BO_ 506 BRAKE_COMMAND: 8 ADAS SG_ COMPUTER_BRAKE : 7|10@0+ (1,0) [0|1] "" EBCM SG_ SET_ME_X00 : 13|5@0+ (1,0) [0|1] "" EBCM @@ -128,17 +225,6 @@ BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON -BO_ 773 SEATBELT_STATUS: 7 BDY - SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON - SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON - SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON - BO_ 777 LOCK_STATUS: 8 XXX SG_ DOORS_UNLOCKED : 54|1@0+ (1,0) [0|1] "" EON SG_ DOORS_LOCKED : 55|1@0+ (1,0) [0|1] "" EON @@ -172,89 +258,22 @@ BO_ 780 ACC_HUD: 8 ADAS SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY -BO_ 804 CRUISE: 8 PCM - SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" EON - SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" EON - SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON - SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" EON - SG_ BOH2 : 47|8@0- (1,0) [0|255] "" EON - SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - -BO_ 829 LKAS_HUD: 5 ADAS - SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY - SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY - SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY - SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY - SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY - SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY - SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY - SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY - SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY - SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY - SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY - SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY - SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY - SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY - SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY - BO_ 892 CRUISE_PARAMS: 8 PCM SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" EON SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON -BO_ 1029 DOORS_STATUS: 8 BDY - SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" EON - SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" EON - SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" EON - SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" EON - SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - -CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; CM_ SG_ 506 AEB_REQ_1 "set for duration of suspected AEB event"; -CM_ SG_ 773 PASS_AIRBAG_ON "Might just be indicator light"; -CM_ SG_ 773 PASS_AIRBAG_OFF "Might just be indicator light"; CM_ SG_ 780 CRUISE_SPEED "255 = no speed"; -CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; -CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; - -VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw" ; -VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime" ; -VAL_ 506 AEB_STATUS 3 "aeb_prepare" 2 "aeb_ready" 1 "aeb_braking" 0 "no_aeb" ; -VAL_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped" ; -VAL_ 780 HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car" ; -VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; - - -CM_ "Imported file _comma.dbc starts here"; -BO_ 512 GAS_COMMAND: 6 EON - SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR - SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR - SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR - -BO_ 513 GAS_SENSOR: 6 INTERCEPTOR - SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON - SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON - SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON - -VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; +VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw"; +VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime"; +VAL_ 506 AEB_STATUS 3 "aeb_prepare" 2 "aeb_ready" 1 "aeb_braking" 0 "no_aeb"; +VAL_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped"; +VAL_ 780 HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car"; CM_ "honda_crv_touring_2016_can.dbc starts here"; - - BO_ 342 STEERING_SENSORS: 6 EPS SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON SG_ STEER_ANGLE_RATE : 23|16@0- (-1,0) [-3000|3000] "deg/s" EON @@ -291,12 +310,6 @@ BO_ 422 SCM_BUTTONS: 8 SCM SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON -BO_ 487 BRAKE_PRESSURE: 4 VSA - SG_ BRAKE_PRESSURE1 : 7|10@0+ (0.015625,-103) [0|1000] "" EON - SG_ BRAKE_PRESSURE2 : 9|10@0+ (0.015625,-103) [0|1000] "" EON - SG_ COUNTER : 29|2@0+ (1,0) [0|15] "" EON - SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EON - BO_ 660 SCM_FEEDBACK: 8 SCM SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" EON SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" EON @@ -304,12 +317,6 @@ BO_ 660 SCM_FEEDBACK: 8 SCM SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON -BO_ 891 WIPERS: 8 XXX - SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - - CM_ SG_ 401 GEAR "10 = reverse, 11 = transition"; 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" ; @@ -318,5 +325,3 @@ VAL_ 401 GEAR 7 "L" 10 "S" 4 "D" 3 "N" 2 "R" 1 "P" ; VAL_ 422 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; VAL_ 422 LIGHTS_SETTING 3 "high_beam" 2 "low_beam" 1 "position" 0 "no_lights" ; VAL_ 422 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; -VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off" ; - diff --git a/opendbc/honda_fit_ex_2018_can_generated.dbc b/opendbc/honda_fit_ex_2018_can_generated.dbc index df47a001d..e41b529b5 100644 --- a/opendbc/honda_fit_ex_2018_can_generated.dbc +++ b/opendbc/honda_fit_ex_2018_can_generated.dbc @@ -1,41 +1,36 @@ CM_ "AUTOGENERATED FILE, DO NOT EDIT"; -CM_ "Imported file _honda_2017.dbc starts here"; -VERSION "" +CM_ "Imported file _comma.dbc starts here"; +BO_ 512 GAS_COMMAND: 6 EON + SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR + SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR + SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR + SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR + SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR + +BO_ 513 GAS_SENSOR: 6 INTERCEPTOR + SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON + SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON + SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON + SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON + +VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; -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_ +CM_ "Imported file _honda_common.dbc starts here"; +BO_ 304 GAS_PEDAL_2: 8 PCM + SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON -BU_: EBCM ADAS PCM EPS VSA SCM BDY XXX EPB EON +BO_ 316 GAS_PEDAL: 8 PCM + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON BO_ 344 ENGINE_DATA: 8 PCM SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" EON @@ -49,14 +44,14 @@ BO_ 380 POWERTRAIN_DATA: 8 PCM SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" EON SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" EON - SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "rpm" EON - SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "rpm" EON - SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "rpm" EON - SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "rpm" EON + SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "" EON + SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "" EON + SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "" EON + SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "" EON SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" EON - SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "rpm" EON + SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "" EON SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON BO_ 420 VSA_STATUS: 8 VSA SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON @@ -75,14 +70,6 @@ BO_ 427 STEER_MOTOR_TORQUE: 3 EPS SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" EON -BO_ 432 STANDSTILL: 7 VSA - SG_ CONTROLLED_STANDSTILL : 0|1@0+ (1,0) [0|1] "" EON - SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON - SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON - SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON - BO_ 464 WHEEL_SPEEDS: 8 VSA SG_ WHEEL_SPEED_FL : 7|15@0+ (0.01,0) [0|250] "kph" EON SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON @@ -91,10 +78,120 @@ BO_ 464 WHEEL_SPEEDS: 8 VSA SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON BO_ 490 VEHICLE_DYNAMICS: 8 VSA - SG_ LONG_ACCEL : 23|16@0- (0.0015384,0) [-20|20] "m/s2" EON + SG_ LAT_ACCEL : 7|16@0- (0.0015,0) [-20|20] "m/s2" EON + SG_ LONG_ACCEL : 23|16@0- (0.0015,0) [-20|20] "m/s2" EON SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON +BO_ 773 SEATBELT_STATUS: 7 BDY + SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 804 CRUISE: 8 PCM + SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" EON + SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" EON + SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON + SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" EON + SG_ BOH2 : 47|8@0- (1,0) [0|255] "" EON + SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 829 LKAS_HUD: 5 ADAS + SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY + SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY + SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY + SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY + SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY + SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY + SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY + SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY + SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY + SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY + SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY + +BO_ 884 STALK_STATUS: 8 XXX + SG_ DASHBOARD_ALERT : 39|8@0+ (1,0) [0|255] "" EON + SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON + SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON + SG_ WIPER_SWITCH : 53|2@0+ (1,0) [0|3] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 891 STALK_STATUS_2: 8 XXX + SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON + SG_ LOW_BEAMS : 35|1@0+ (1,0) [0|1] "" XXX + SG_ HIGH_BEAMS : 34|1@0+ (1,0) [0|1] "" XXX + SG_ PARK_LIGHTS : 36|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 1029 DOORS_STATUS: 8 BDY + SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" EON + SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +CM_ SG_ 304 "Seems to be platform-agnostic"; +CM_ SG_ 316 "Should exist on Nidec"; +CM_ SG_ 420 BRAKE_HOLD_RELATED "On when Brake Hold engaged"; +CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; +CM_ SG_ 773 PASS_AIRBAG_ON "Might just be indicator light"; +CM_ SG_ 773 PASS_AIRBAG_OFF "Might just be indicator light"; +CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; +CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; + +VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep"; +VAL_ 884 DASHBOARD_ALERT 0 "none" 51 "acc_problem" 55 "cmbs_problem" 75 "key_not_detected" 79 "fasten_seatbelt" 111 "lkas_problem" 131 "brake_system_problem" 132 "brake_hold_problem" 139 "tbd" 161 "door_open"; +VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off"; + + +CM_ "Imported file _honda_2017.dbc starts here"; +BO_ 145 KINEMATICS: 8 XXX + SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 148 KINEMATICS_ALT: 8 XXX + SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON + SG_ LONG_ACCEL : 24|9@0- (-0.02,0) [-20|20] "m/s2" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +BO_ 432 STANDSTILL: 7 VSA + SG_ CONTROLLED_STANDSTILL : 0|1@0+ (1,0) [0|1] "" EON + SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 487 BRAKE_PRESSURE: 4 VSA + SG_ BRAKE_PRESSURE1 : 7|10@0+ (0.015625,-103) [0|1000] "" EON + SG_ BRAKE_PRESSURE2 : 9|10@0+ (0.015625,-103) [0|1000] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON + BO_ 506 BRAKE_COMMAND: 8 ADAS SG_ COMPUTER_BRAKE : 7|10@0+ (1,0) [0|1] "" EBCM SG_ SET_ME_X00 : 13|5@0+ (1,0) [0|1] "" EBCM @@ -128,17 +225,6 @@ BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON -BO_ 773 SEATBELT_STATUS: 7 BDY - SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON - SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON - SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON - BO_ 777 LOCK_STATUS: 8 XXX SG_ DOORS_UNLOCKED : 54|1@0+ (1,0) [0|1] "" EON SG_ DOORS_LOCKED : 55|1@0+ (1,0) [0|1] "" EON @@ -172,92 +258,22 @@ BO_ 780 ACC_HUD: 8 ADAS SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY -BO_ 804 CRUISE: 8 PCM - SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" EON - SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" EON - SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON - SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" EON - SG_ BOH2 : 47|8@0- (1,0) [0|255] "" EON - SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - -BO_ 829 LKAS_HUD: 5 ADAS - SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY - SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY - SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY - SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY - SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY - SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY - SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY - SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY - SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY - SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY - SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY - SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY - SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY - SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY - SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY - BO_ 892 CRUISE_PARAMS: 8 PCM SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" EON SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON -BO_ 1029 DOORS_STATUS: 8 BDY - SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" EON - SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" EON - SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" EON - SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" EON - SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - -CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; CM_ SG_ 506 AEB_REQ_1 "set for duration of suspected AEB event"; -CM_ SG_ 773 PASS_AIRBAG_ON "Might just be indicator light"; -CM_ SG_ 773 PASS_AIRBAG_OFF "Might just be indicator light"; CM_ SG_ 780 CRUISE_SPEED "255 = no speed"; -CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; -CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; - -VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw" ; -VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime" ; -VAL_ 506 AEB_STATUS 3 "aeb_prepare" 2 "aeb_ready" 1 "aeb_braking" 0 "no_aeb" ; -VAL_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped" ; -VAL_ 780 HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car" ; -VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; - - -CM_ "Imported file _comma.dbc starts here"; -BO_ 512 GAS_COMMAND: 6 EON - SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR - SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR - SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR - -BO_ 513 GAS_SENSOR: 6 INTERCEPTOR - SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON - SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON - SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON - -VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; +VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw"; +VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime"; +VAL_ 506 AEB_STATUS 3 "aeb_prepare" 2 "aeb_ready" 1 "aeb_braking" 0 "no_aeb"; +VAL_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped"; +VAL_ 780 HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car"; CM_ "honda_fit_ex_2018_can.dbc starts here"; - - -BO_ 145 KINEMATICS: 8 XXX - SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON - BO_ 228 STEERING_CONTROL: 5 ADAS SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS @@ -266,16 +282,6 @@ BO_ 228 STEERING_CONTROL: 5 ADAS SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" EPS -BO_ 304 GAS_PEDAL_2: 8 PCM - SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON - SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON - SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - -BO_ 316 GAS_PEDAL: 8 PCM - SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON - BO_ 342 STEERING_SENSORS: 6 EPS SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON SG_ STEER_ANGLE_RATE : 23|16@0- (-1,0) [-3000|3000] "deg/s" EON @@ -306,12 +312,6 @@ BO_ 422 SCM_BUTTONS: 8 SCM SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON -BO_ 487 BRAKE_PRESSURE: 4 VSA - SG_ BRAKE_PRESSURE1 : 7|10@0+ (0.015625,-103) [0|1000] "" EON - SG_ BRAKE_PRESSURE2 : 9|10@0+ (0.015625,-103) [0|1000] "" EON - SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EON - SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON - BO_ 660 SCM_FEEDBACK: 8 SCM SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" EON SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" EON @@ -327,16 +327,7 @@ BO_ 862 HIGHBEAM_CONTROL: 8 ADAS SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_ 884 STALK_STATUS: 8 XXX - SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON - SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON - SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON - SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - CM_ SG_ 401 GEAR "10 = reverse, 11 = transition"; -CM_ SG_ 420 BRAKE_HOLD_RELATED "On when Brake Hold engaged"; 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_ 401 GEAR_SHIFTER 32 "L" 16 "S" 8 "D" 4 "N" 2 "R" 1 "P" ; @@ -344,4 +335,3 @@ VAL_ 401 GEAR 7 "L" 10 "S" 4 "D" 3 "N" 2 "R" 1 "P" ; VAL_ 422 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; VAL_ 422 LIGHTS_SETTING 3 "high_beam" 2 "low_beam" 1 "position" 0 "no_lights" ; VAL_ 422 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; - diff --git a/opendbc/honda_insight_ex_2019_can_generated.dbc b/opendbc/honda_insight_ex_2019_can_generated.dbc index 5bb0ab01c..12ccc0873 100644 --- a/opendbc/honda_insight_ex_2019_can_generated.dbc +++ b/opendbc/honda_insight_ex_2019_can_generated.dbc @@ -1,42 +1,154 @@ CM_ "AUTOGENERATED FILE, DO NOT EDIT"; +CM_ "Imported file _honda_common.dbc starts here"; +BO_ 304 GAS_PEDAL_2: 8 PCM + SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 316 GAS_PEDAL: 8 PCM + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 344 ENGINE_DATA: 8 PCM + SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ XMISSION_SPEED2 : 39|16@0+ (0.01,0) [0|250] "kph" EON + SG_ ODOMETER : 55|8@0+ (10,0) [0|2550] "m" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 380 POWERTRAIN_DATA: 8 PCM + SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" EON + SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON + SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" EON + SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "" EON + SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "" EON + SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "" EON + SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "" EON + SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" EON + SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 420 VSA_STATUS: 8 VSA + SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON + SG_ COMPUTER_BRAKING : 23|1@0+ (1,0) [0|1] "" EON + SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_HOLD_RELATED : 52|1@0+ (1,0) [0|1] "" XXX + SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_HOLD_ENABLED : 45|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 427 STEER_MOTOR_TORQUE: 3 EPS + SG_ CONFIG_VALID : 7|1@0+ (1,0) [0|1] "" EON + SG_ MOTOR_TORQUE : 1|10@0+ (1,0) [0|256] "" EON + SG_ OUTPUT_DISABLED : 22|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" EON + +BO_ 464 WHEEL_SPEEDS: 8 VSA + SG_ WHEEL_SPEED_FL : 7|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RL : 25|15@0+ (0.01,0) [0|250] "kph" EON + SG_ WHEEL_SPEED_RR : 42|15@0+ (0.01,0) [0|250] "kph" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 490 VEHICLE_DYNAMICS: 8 VSA + SG_ LAT_ACCEL : 7|16@0- (0.0015,0) [-20|20] "m/s2" EON + SG_ LONG_ACCEL : 23|16@0- (0.0015,0) [-20|20] "m/s2" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 773 SEATBELT_STATUS: 7 BDY + SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 804 CRUISE: 8 PCM + SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" EON + SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" EON + SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON + SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" EON + SG_ BOH2 : 47|8@0- (1,0) [0|255] "" EON + SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 829 LKAS_HUD: 5 ADAS + SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY + SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY + SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY + SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY + SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY + SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY + SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY + SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY + SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY + SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY + SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY + +BO_ 884 STALK_STATUS: 8 XXX + SG_ DASHBOARD_ALERT : 39|8@0+ (1,0) [0|255] "" EON + SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON + SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON + SG_ WIPER_SWITCH : 53|2@0+ (1,0) [0|3] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 891 STALK_STATUS_2: 8 XXX + SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON + SG_ LOW_BEAMS : 35|1@0+ (1,0) [0|1] "" XXX + SG_ HIGH_BEAMS : 34|1@0+ (1,0) [0|1] "" XXX + SG_ PARK_LIGHTS : 36|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 1029 DOORS_STATUS: 8 BDY + SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" EON + SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +CM_ SG_ 304 "Seems to be platform-agnostic"; +CM_ SG_ 316 "Should exist on Nidec"; +CM_ SG_ 420 BRAKE_HOLD_RELATED "On when Brake Hold engaged"; +CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; +CM_ SG_ 773 PASS_AIRBAG_ON "Might just be indicator light"; +CM_ SG_ 773 PASS_AIRBAG_OFF "Might just be indicator light"; +CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; +CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; + +VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep"; +VAL_ 884 DASHBOARD_ALERT 0 "none" 51 "acc_problem" 55 "cmbs_problem" 75 "key_not_detected" 79 "fasten_seatbelt" 111 "lkas_problem" 131 "brake_system_problem" 132 "brake_hold_problem" 139 "tbd" 161 "door_open"; +VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off"; + + CM_ "Imported file _bosch_2018.dbc starts here"; -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_ - -BU_: EBCM EON CAM RADAR PCM EPS VSA SCM BDY XXX EPB - BO_ 148 KINEMATICS: 8 XXX SG_ LAT_ACCEL : 7|10@0+ (-0.035,17.92) [-20|20] "m/s2" EON SG_ LONG_ACCEL : 25|10@0+ (-0.035,17.92) [-20|20] "m/s2" EON @@ -67,37 +179,6 @@ BO_ 232 BRAKE_HOLD: 7 XXX SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" XXX -BO_ 330 STEERING_SENSORS: 8 EPS - SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON - SG_ STEER_ANGLE_RATE : 23|16@0- (-1,0) [-3000|3000] "deg/s" EON - SG_ STEER_SENSOR_STATUS_1 : 34|1@0+ (1,0) [0|1] "" EON - SG_ STEER_SENSOR_STATUS_2 : 33|1@0+ (1,0) [0|1] "" EON - SG_ STEER_SENSOR_STATUS_3 : 32|1@0+ (1,0) [0|1] "" EON - SG_ STEER_WHEEL_ANGLE : 47|16@0- (-0.1,0) [-500|500] "deg" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON - -BO_ 344 ENGINE_DATA: 8 PCM - SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" EON - SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON - SG_ XMISSION_SPEED2 : 39|16@0+ (0.01,0) [0|250] "kph" EON - SG_ ODOMETER : 55|8@0+ (10,0) [0|2550] "m" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON - -BO_ 380 POWERTRAIN_DATA: 8 PCM - SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" EON - SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON - SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" EON - SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "" EON - SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "" EON - SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "" EON - SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "" EON - SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" EON - SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON - BO_ 399 STEER_STATUS: 7 EPS SG_ STEER_TORQUE_SENSOR : 7|16@0- (-1,0) [-31000|31000] "tbd" EON SG_ STEER_ANGLE_RATE : 23|16@0- (-0.1,0) [-31000|31000] "deg/s" EON @@ -107,34 +188,12 @@ BO_ 399 STEER_STATUS: 7 EPS SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" EON -BO_ 420 VSA_STATUS: 8 VSA - SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON - SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON - SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" EON - SG_ BRAKE_HOLD_ENABLED : 45|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON - -BO_ 427 STEER_MOTOR_TORQUE: 3 EPS - SG_ CONFIG_VALID : 7|1@0+ (1,0) [0|1] "" EON - SG_ MOTOR_TORQUE : 1|10@0+ (1,0) [0|256] "" EON - SG_ OUTPUT_DISABLED : 22|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" EON - BO_ 450 EPB_STATUS: 8 EPB SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" EON SG_ EPB_STATE : 29|2@0+ (1,0) [0|3] "" EON SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_ 464 WHEEL_SPEEDS: 8 VSA - SG_ WHEEL_SPEED_FL : 7|15@0+ (0.01,0) [0|250] "kph" EON - SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON - SG_ WHEEL_SPEED_RL : 25|15@0+ (0.01,0) [0|250] "kph" EON - SG_ WHEEL_SPEED_RR : 42|15@0+ (0.01,0) [0|250] "kph" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - BO_ 479 ACC_CONTROL: 8 EON SG_ SET_TO_0 : 20|5@0+ (1,0) [0|1] "" XXX SG_ CONTROL_ON : 23|3@0+ (1,0) [0|5] "" XXX @@ -150,12 +209,6 @@ BO_ 479 ACC_CONTROL: 8 EON SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_ 490 VEHICLE_DYNAMICS: 8 VSA - SG_ LAT_ACCEL : 7|16@0- (0.0015,0) [-20|20] "m/s2" EON - SG_ LONG_ACCEL : 23|16@0- (0.0015,0) [-20|20] "m/s2" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - BO_ 495 ACC_CONTROL_ON: 8 XXX SG_ SET_TO_75 : 31|8@0+ (1,0) [0|255] "" XXX SG_ SET_TO_30 : 39|8@0+ (1,0) [0|255] "" XXX @@ -260,22 +313,11 @@ BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX - BO_ 662 SCM_BUTTONS: 4 SCM - SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON - SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" EON - SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" EON - -BO_ 773 SEATBELT_STATUS: 7 BDY - SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON - SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON - SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON +BO_ 662 SCM_BUTTONS: 4 SCM + SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON + SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" EON BO_ 777 CAR_SPEED: 8 PCM SG_ ROUGH_CAR_SPEED : 23|8@0+ (1,0) [0|255] "mph" XXX @@ -311,11 +353,6 @@ BO_ 780 ACC_HUD: 8 ADAS SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_ 804 CRUISE: 8 PCM - SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON - BO_ 806 SCM_FEEDBACK: 8 SCM SG_ DRIVERS_DOOR_OPEN : 17|1@0+ (1,0) [0|1] "" XXX SG_ MAIN_ON : 28|1@0+ (1,0) [0|1] "" EON @@ -325,27 +362,6 @@ BO_ 806 SCM_FEEDBACK: 8 SCM SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_ 829 LKAS_HUD: 5 ADAS - SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY - SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY - SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY - SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY - SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY - SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY - SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY - SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY - SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY - SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY - SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY - SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY - SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY - SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY - SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY - 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 @@ -354,23 +370,6 @@ BO_ 862 CAMERA_MESSAGES: 8 CAM SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_ 884 STALK_STATUS: 8 XXX - SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON - SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON - SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON - SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON - SG_ WIPER_SWITCH : 53|2@0+ (1,0) [0|3] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - -BO_ 891 STALK_STATUS_2: 8 XXX - SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON - SG_ LOW_BEAMS : 35|1@0+ (1,0) [0|1] "" XXX - SG_ HIGH_BEAMS : 34|1@0+ (1,0) [0|1] "" XXX - SG_ PARK_LIGHTS : 36|1@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - BO_ 13274 LKAS_HUD_A: 5 ADAS SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY @@ -413,6 +412,8 @@ BO_ 13275 LKAS_HUD_B: 8 ADAS SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" BDY +CM_ SG_ 450 EPB_STATE "3: On, 2: Disengaging, 1: Engaging, 0: Off"; +CM_ SG_ 479 CONTROL_ON "Set to 5 when car is being controlled"; CM_ SG_ 479 AEB_STATUS "set for the duration of AEB event"; CM_ SG_ 479 AEB_BRAKING "set when braking is commanded during AEB event"; CM_ SG_ 479 AEB_PREPARE "set 1s before AEB"; @@ -421,18 +422,21 @@ CM_ SG_ 577 LINE_FAR_EDGE_POSITION "Appears to be a measure of line thickness, i CM_ SG_ 577 LINE_PARAMETER "Unclear if this is low quality line curvature rate or if this is something else, but it is correlated with line curvature, undecoded"; CM_ SG_ 577 LINE_DASHED "1 = line is dashed"; CM_ SG_ 577 LINE_SOLID "1 = line is solid"; -VAL_ 399 STEER_STATUS 6 "tmp_fault" 5 "fault_1" 4 "no_torque_alert_2" 3 "low_speed_lockout" 2 "no_torque_alert_1" 0 "normal" ; + +VAL_ 399 STEER_STATUS 6 "tmp_fault" 5 "fault_1" 4 "no_torque_alert_2" 3 "low_speed_lockout" 2 "no_torque_alert_1" 0 "normal"; CM_ "honda_insight_ex_2019_can.dbc starts here"; - -BO_ 304 GAS_PEDAL_2: 8 PCM - SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON - SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON - SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON +BO_ 330 STEERING_SENSORS: 8 EPS + SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON + SG_ STEER_ANGLE_RATE : 23|16@0- (-1,0) [-3000|3000] "deg/s" EON + SG_ STEER_SENSOR_STATUS_1 : 34|1@0+ (1,0) [0|1] "" EON + SG_ STEER_SENSOR_STATUS_2 : 33|1@0+ (1,0) [0|1] "" EON + SG_ STEER_SENSOR_STATUS_3 : 32|1@0+ (1,0) [0|1] "" EON + SG_ STEER_WHEEL_ANGLE : 47|16@0- (-0.1,0) [-500|500] "deg" EON SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON - + BO_ 419 GEARBOX: 8 PCM SG_ GEAR : 7|8@0+ (1,0) [0|255] "" EON SG_ GEAR_SHIFTER : 29|6@0+ (1,0) [0|63] "" EON @@ -462,15 +466,5 @@ BO_ 927 RADAR_HUD: 8 RADAR SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX -BO_ 1029 DOORS_STATUS: 8 BDY - SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" EON - SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" EON - SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" EON - SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" EON - SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON - - VAL_ 419 GEAR 10 "R" 1 "D" 0 "P"; - VAL_ 419 GEAR_SHIFTER 32 "D" 16 "N" 8 "R" 4 "P" ; - +VAL_ 419 GEAR 10 "R" 1 "D" 0 "P"; +VAL_ 419 GEAR_SHIFTER 32 "D" 16 "N" 8 "R" 4 "P"; diff --git a/opendbc/honda_odyssey_exl_2018_generated.dbc b/opendbc/honda_odyssey_exl_2018_generated.dbc index 586d2f8ab..a684234c5 100644 --- a/opendbc/honda_odyssey_exl_2018_generated.dbc +++ b/opendbc/honda_odyssey_exl_2018_generated.dbc @@ -1,41 +1,36 @@ CM_ "AUTOGENERATED FILE, DO NOT EDIT"; -CM_ "Imported file _honda_2017.dbc starts here"; -VERSION "" +CM_ "Imported file _comma.dbc starts here"; +BO_ 512 GAS_COMMAND: 6 EON + SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR + SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR + SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR + SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR + SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR + +BO_ 513 GAS_SENSOR: 6 INTERCEPTOR + SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON + SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON + SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON + SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON + +VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; -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_ +CM_ "Imported file _honda_common.dbc starts here"; +BO_ 304 GAS_PEDAL_2: 8 PCM + SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON -BU_: EBCM ADAS PCM EPS VSA SCM BDY XXX EPB EON +BO_ 316 GAS_PEDAL: 8 PCM + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON BO_ 344 ENGINE_DATA: 8 PCM SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" EON @@ -49,14 +44,14 @@ BO_ 380 POWERTRAIN_DATA: 8 PCM SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" EON SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" EON - SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "rpm" EON - SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "rpm" EON - SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "rpm" EON - SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "rpm" EON + SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "" EON + SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "" EON + SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "" EON + SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "" EON SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" EON - SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "rpm" EON + SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "" EON SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON BO_ 420 VSA_STATUS: 8 VSA SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON @@ -75,14 +70,6 @@ BO_ 427 STEER_MOTOR_TORQUE: 3 EPS SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" EON -BO_ 432 STANDSTILL: 7 VSA - SG_ CONTROLLED_STANDSTILL : 0|1@0+ (1,0) [0|1] "" EON - SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON - SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON - SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON - BO_ 464 WHEEL_SPEEDS: 8 VSA SG_ WHEEL_SPEED_FL : 7|15@0+ (0.01,0) [0|250] "kph" EON SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON @@ -91,10 +78,120 @@ BO_ 464 WHEEL_SPEEDS: 8 VSA SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON BO_ 490 VEHICLE_DYNAMICS: 8 VSA - SG_ LONG_ACCEL : 23|16@0- (0.0015384,0) [-20|20] "m/s2" EON + SG_ LAT_ACCEL : 7|16@0- (0.0015,0) [-20|20] "m/s2" EON + SG_ LONG_ACCEL : 23|16@0- (0.0015,0) [-20|20] "m/s2" EON SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON +BO_ 773 SEATBELT_STATUS: 7 BDY + SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 804 CRUISE: 8 PCM + SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" EON + SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" EON + SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON + SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" EON + SG_ BOH2 : 47|8@0- (1,0) [0|255] "" EON + SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 829 LKAS_HUD: 5 ADAS + SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY + SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY + SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY + SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY + SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY + SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY + SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY + SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY + SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY + SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY + SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY + +BO_ 884 STALK_STATUS: 8 XXX + SG_ DASHBOARD_ALERT : 39|8@0+ (1,0) [0|255] "" EON + SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON + SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON + SG_ WIPER_SWITCH : 53|2@0+ (1,0) [0|3] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 891 STALK_STATUS_2: 8 XXX + SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON + SG_ LOW_BEAMS : 35|1@0+ (1,0) [0|1] "" XXX + SG_ HIGH_BEAMS : 34|1@0+ (1,0) [0|1] "" XXX + SG_ PARK_LIGHTS : 36|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 1029 DOORS_STATUS: 8 BDY + SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" EON + SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +CM_ SG_ 304 "Seems to be platform-agnostic"; +CM_ SG_ 316 "Should exist on Nidec"; +CM_ SG_ 420 BRAKE_HOLD_RELATED "On when Brake Hold engaged"; +CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; +CM_ SG_ 773 PASS_AIRBAG_ON "Might just be indicator light"; +CM_ SG_ 773 PASS_AIRBAG_OFF "Might just be indicator light"; +CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; +CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; + +VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep"; +VAL_ 884 DASHBOARD_ALERT 0 "none" 51 "acc_problem" 55 "cmbs_problem" 75 "key_not_detected" 79 "fasten_seatbelt" 111 "lkas_problem" 131 "brake_system_problem" 132 "brake_hold_problem" 139 "tbd" 161 "door_open"; +VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off"; + + +CM_ "Imported file _honda_2017.dbc starts here"; +BO_ 145 KINEMATICS: 8 XXX + SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 148 KINEMATICS_ALT: 8 XXX + SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON + SG_ LONG_ACCEL : 24|9@0- (-0.02,0) [-20|20] "m/s2" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +BO_ 432 STANDSTILL: 7 VSA + SG_ CONTROLLED_STANDSTILL : 0|1@0+ (1,0) [0|1] "" EON + SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 487 BRAKE_PRESSURE: 4 VSA + SG_ BRAKE_PRESSURE1 : 7|10@0+ (0.015625,-103) [0|1000] "" EON + SG_ BRAKE_PRESSURE2 : 9|10@0+ (0.015625,-103) [0|1000] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON + BO_ 506 BRAKE_COMMAND: 8 ADAS SG_ COMPUTER_BRAKE : 7|10@0+ (1,0) [0|1] "" EBCM SG_ SET_ME_X00 : 13|5@0+ (1,0) [0|1] "" EBCM @@ -128,17 +225,6 @@ BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON -BO_ 773 SEATBELT_STATUS: 7 BDY - SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON - SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON - SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON - BO_ 777 LOCK_STATUS: 8 XXX SG_ DOORS_UNLOCKED : 54|1@0+ (1,0) [0|1] "" EON SG_ DOORS_LOCKED : 55|1@0+ (1,0) [0|1] "" EON @@ -172,89 +258,22 @@ BO_ 780 ACC_HUD: 8 ADAS SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY -BO_ 804 CRUISE: 8 PCM - SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" EON - SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" EON - SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON - SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" EON - SG_ BOH2 : 47|8@0- (1,0) [0|255] "" EON - SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - -BO_ 829 LKAS_HUD: 5 ADAS - SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY - SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY - SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY - SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY - SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY - SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY - SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY - SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY - SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY - SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY - SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY - SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY - SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY - SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY - SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY - BO_ 892 CRUISE_PARAMS: 8 PCM SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" EON SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON -BO_ 1029 DOORS_STATUS: 8 BDY - SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" EON - SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" EON - SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" EON - SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" EON - SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - -CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; CM_ SG_ 506 AEB_REQ_1 "set for duration of suspected AEB event"; -CM_ SG_ 773 PASS_AIRBAG_ON "Might just be indicator light"; -CM_ SG_ 773 PASS_AIRBAG_OFF "Might just be indicator light"; CM_ SG_ 780 CRUISE_SPEED "255 = no speed"; -CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; -CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; - -VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw" ; -VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime" ; -VAL_ 506 AEB_STATUS 3 "aeb_prepare" 2 "aeb_ready" 1 "aeb_braking" 0 "no_aeb" ; -VAL_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped" ; -VAL_ 780 HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car" ; -VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; - - -CM_ "Imported file _comma.dbc starts here"; -BO_ 512 GAS_COMMAND: 6 EON - SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR - SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR - SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR - -BO_ 513 GAS_SENSOR: 6 INTERCEPTOR - SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON - SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON - SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON - -VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; +VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw"; +VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime"; +VAL_ 506 AEB_STATUS 3 "aeb_prepare" 2 "aeb_ready" 1 "aeb_braking" 0 "no_aeb"; +VAL_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped"; +VAL_ 780 HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car"; CM_ "honda_odyssey_exl_2018.dbc starts here"; - - BO_ 228 STEERING_CONTROL: 5 ADAS SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS @@ -262,9 +281,6 @@ BO_ 228 STEERING_CONTROL: 5 ADAS SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" EPS -BO_ 316 GAS_PEDAL: 8 PCM - SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON - BO_ 342 STEERING_SENSORS: 6 EPS SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON SG_ STEER_ANGLE_RATE : 23|16@0- (-1,0) [-3000|3000] "deg/s" EON @@ -308,11 +324,6 @@ BO_ 806 SCM_FEEDBACK: 8 SCM SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON -BO_ 891 WIPERS: 8 XXX - SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - BO_ 862 HIGHBEAM_CONTROL: 8 ADAS SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY SG_ ZEROS_BOH_2 : 48|4@1+ (1,0) [0|15] "" XXX @@ -340,11 +351,8 @@ BO_ 1302 ODOMETER: 8 XXX SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON CM_ SG_ 419 GEAR "10 = reverse, 11 = transition"; -CM_ SG_ 420 BRAKE_HOLD_RELATED "On when Brake Hold engaged"; CM_ SG_ 780 CRUISE_SPEED "255 = no speed"; -CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; CM_ SG_ 806 REVERSE_LIGHT "Might be reverse gear selected and not the lights"; -CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnings etc..."; 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_ 419 GEAR_SHIFTER 10 "S" 4 "D" 3 "N" 2 "R" 1 "P" ; @@ -352,8 +360,5 @@ VAL_ 450 EPB_STATE 3 "engaged" 2 "disengaging" 1 "engaging" 0 "disengaged" ; VAL_ 662 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; VAL_ 662 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; VAL_ 780 HUD_LEAD 3 "no_car" 2 "solid_car" 1 "dashed_car" 0 "no_car" ; -VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; -VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off" ; VAL_ 927 ACC_ALERTS 29 "esp_active_acc_canceled" 10 "b_pedal_applied" 9 "speed_too_low" 8 "speed_too_high" 7 "p_brake_applied" 6 "gear_no_d" 5 "seatbelt" 4 "too_steep_downhill" 3 "too_steep_uphill" 2 "too_close" 1 "no_vehicle_ahead" ; VAL_ 806 CMBS_BUTTON 3 "pressed" 0 "released" ; - diff --git a/opendbc/honda_odyssey_extreme_edition_2018_china_can_generated.dbc b/opendbc/honda_odyssey_extreme_edition_2018_china_can_generated.dbc index db99d2184..f0c5c2708 100644 --- a/opendbc/honda_odyssey_extreme_edition_2018_china_can_generated.dbc +++ b/opendbc/honda_odyssey_extreme_edition_2018_china_can_generated.dbc @@ -1,41 +1,36 @@ CM_ "AUTOGENERATED FILE, DO NOT EDIT"; -CM_ "Imported file _honda_2017.dbc starts here"; -VERSION "" +CM_ "Imported file _comma.dbc starts here"; +BO_ 512 GAS_COMMAND: 6 EON + SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR + SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR + SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR + SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR + SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR + +BO_ 513 GAS_SENSOR: 6 INTERCEPTOR + SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON + SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON + SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON + SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON + +VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; -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_ +CM_ "Imported file _honda_common.dbc starts here"; +BO_ 304 GAS_PEDAL_2: 8 PCM + SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON -BU_: EBCM ADAS PCM EPS VSA SCM BDY XXX EPB EON +BO_ 316 GAS_PEDAL: 8 PCM + SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON BO_ 344 ENGINE_DATA: 8 PCM SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" EON @@ -49,14 +44,14 @@ BO_ 380 POWERTRAIN_DATA: 8 PCM SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" EON SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" EON - SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "rpm" EON - SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "rpm" EON - SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "rpm" EON - SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "rpm" EON + SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "" EON + SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "" EON + SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "" EON + SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "" EON SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" EON - SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "rpm" EON + SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "" EON SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON BO_ 420 VSA_STATUS: 8 VSA SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON @@ -75,14 +70,6 @@ BO_ 427 STEER_MOTOR_TORQUE: 3 EPS SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" EON -BO_ 432 STANDSTILL: 7 VSA - SG_ CONTROLLED_STANDSTILL : 0|1@0+ (1,0) [0|1] "" EON - SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON - SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON - SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON - BO_ 464 WHEEL_SPEEDS: 8 VSA SG_ WHEEL_SPEED_FL : 7|15@0+ (0.01,0) [0|250] "kph" EON SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON @@ -91,10 +78,120 @@ BO_ 464 WHEEL_SPEEDS: 8 VSA SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON BO_ 490 VEHICLE_DYNAMICS: 8 VSA - SG_ LONG_ACCEL : 23|16@0- (0.0015384,0) [-20|20] "m/s2" EON + SG_ LAT_ACCEL : 7|16@0- (0.0015,0) [-20|20] "m/s2" EON + SG_ LONG_ACCEL : 23|16@0- (0.0015,0) [-20|20] "m/s2" EON SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON +BO_ 773 SEATBELT_STATUS: 7 BDY + SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON + SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON + SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 804 CRUISE: 8 PCM + SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" EON + SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" EON + SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON + SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" EON + SG_ BOH2 : 47|8@0- (1,0) [0|255] "" EON + SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 829 LKAS_HUD: 5 ADAS + SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY + SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY + SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY + SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY + SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY + SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY + SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY + SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY + SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY + SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY + SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY + SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY + SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY + SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY + SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY + SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY + SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY + +BO_ 884 STALK_STATUS: 8 XXX + SG_ DASHBOARD_ALERT : 39|8@0+ (1,0) [0|255] "" EON + SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON + SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON + SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON + SG_ WIPER_SWITCH : 53|2@0+ (1,0) [0|3] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 891 STALK_STATUS_2: 8 XXX + SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON + SG_ LOW_BEAMS : 35|1@0+ (1,0) [0|1] "" XXX + SG_ HIGH_BEAMS : 34|1@0+ (1,0) [0|1] "" XXX + SG_ PARK_LIGHTS : 36|1@0+ (1,0) [0|1] "" XXX + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +BO_ 1029 DOORS_STATUS: 8 BDY + SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" EON + SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" EON + SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON + +CM_ SG_ 304 "Seems to be platform-agnostic"; +CM_ SG_ 316 "Should exist on Nidec"; +CM_ SG_ 420 BRAKE_HOLD_RELATED "On when Brake Hold engaged"; +CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; +CM_ SG_ 773 PASS_AIRBAG_ON "Might just be indicator light"; +CM_ SG_ 773 PASS_AIRBAG_OFF "Might just be indicator light"; +CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; +CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; + +VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep"; +VAL_ 884 DASHBOARD_ALERT 0 "none" 51 "acc_problem" 55 "cmbs_problem" 75 "key_not_detected" 79 "fasten_seatbelt" 111 "lkas_problem" 131 "brake_system_problem" 132 "brake_hold_problem" 139 "tbd" 161 "door_open"; +VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off"; + + +CM_ "Imported file _honda_2017.dbc starts here"; +BO_ 145 KINEMATICS: 8 XXX + SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + +BO_ 148 KINEMATICS_ALT: 8 XXX + SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON + SG_ LONG_ACCEL : 24|9@0- (-0.02,0) [-20|20] "m/s2" EON + SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON + SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON + +BO_ 432 STANDSTILL: 7 VSA + SG_ CONTROLLED_STANDSTILL : 0|1@0+ (1,0) [0|1] "" EON + SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON + SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON + SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON + SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON + +BO_ 487 BRAKE_PRESSURE: 4 VSA + SG_ BRAKE_PRESSURE1 : 7|10@0+ (0.015625,-103) [0|1000] "" EON + SG_ BRAKE_PRESSURE2 : 9|10@0+ (0.015625,-103) [0|1000] "" EON + SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON + BO_ 506 BRAKE_COMMAND: 8 ADAS SG_ COMPUTER_BRAKE : 7|10@0+ (1,0) [0|1] "" EBCM SG_ SET_ME_X00 : 13|5@0+ (1,0) [0|1] "" EBCM @@ -128,17 +225,6 @@ BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON -BO_ 773 SEATBELT_STATUS: 7 BDY - SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON - SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON - SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON - BO_ 777 LOCK_STATUS: 8 XXX SG_ DOORS_UNLOCKED : 54|1@0+ (1,0) [0|1] "" EON SG_ DOORS_LOCKED : 55|1@0+ (1,0) [0|1] "" EON @@ -172,92 +258,22 @@ BO_ 780 ACC_HUD: 8 ADAS SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY -BO_ 804 CRUISE: 8 PCM - SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" EON - SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" EON - SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON - SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" EON - SG_ BOH2 : 47|8@0- (1,0) [0|255] "" EON - SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - -BO_ 829 LKAS_HUD: 5 ADAS - SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY - SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY - SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY - SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY - SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY - SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY - SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY - SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY - SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY - SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY - SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY - SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY - SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY - SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY - SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY - BO_ 892 CRUISE_PARAMS: 8 PCM SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" EON SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON -BO_ 1029 DOORS_STATUS: 8 BDY - SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" EON - SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" EON - SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" EON - SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" EON - SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - -CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; CM_ SG_ 506 AEB_REQ_1 "set for duration of suspected AEB event"; -CM_ SG_ 773 PASS_AIRBAG_ON "Might just be indicator light"; -CM_ SG_ 773 PASS_AIRBAG_OFF "Might just be indicator light"; CM_ SG_ 780 CRUISE_SPEED "255 = no speed"; -CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; -CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; - -VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw" ; -VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime" ; -VAL_ 506 AEB_STATUS 3 "aeb_prepare" 2 "aeb_ready" 1 "aeb_braking" 0 "no_aeb" ; -VAL_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped" ; -VAL_ 780 HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car" ; -VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; - - -CM_ "Imported file _comma.dbc starts here"; -BO_ 512 GAS_COMMAND: 6 EON - SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR - SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR - SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR - -BO_ 513 GAS_SENSOR: 6 INTERCEPTOR - SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON - SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON - SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON - -VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; +VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw"; +VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime"; +VAL_ 506 AEB_STATUS 3 "aeb_prepare" 2 "aeb_ready" 1 "aeb_braking" 0 "no_aeb"; +VAL_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped"; +VAL_ 780 HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car"; CM_ "honda_odyssey_extreme_edition_2018_china_can.dbc starts here"; - - -BO_ 316 GAS_PEDAL: 8 PCM - SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON - BO_ 342 STEERING_SENSORS: 6 EPS SG_ STEER_ANGLE_RATE : 23|16@0- (1,0) [-3000|3000] "deg/s" EON SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON diff --git a/opendbc/honda_pilot_touring_2017_can_generated.dbc b/opendbc/honda_pilot_touring_2017_can_generated.dbc deleted file mode 100644 index 2cc61de8b..000000000 --- a/opendbc/honda_pilot_touring_2017_can_generated.dbc +++ /dev/null @@ -1,315 +0,0 @@ -CM_ "AUTOGENERATED FILE, DO NOT EDIT"; - - -CM_ "Imported file _honda_2017.dbc starts here"; -VERSION "" - - -NS_ : - NS_DESC_ - CM_ - BA_DEF_ - BA_ - VAL_ - CAT_DEF_ - CAT_ - FILTER - BA_DEF_DEF_ - EV_DATA_ - ENVVAR_DATA_ - SGTYPE_ - SGTYPE_VAL_ - BA_DEF_SGTYPE_ - BA_SGTYPE_ - SIG_TYPE_REF_ - VAL_TABLE_ - SIG_GROUP_ - SIG_VALTYPE_ - SIGTYPE_VALTYPE_ - BO_TX_BU_ - BA_DEF_REL_ - BA_REL_ - BA_DEF_DEF_REL_ - BU_SG_REL_ - BU_EV_REL_ - BU_BO_REL_ - SG_MUL_VAL_ - -BU_: EBCM ADAS PCM EPS VSA SCM BDY XXX EPB EON - -BO_ 344 ENGINE_DATA: 8 PCM - SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" EON - SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON - SG_ XMISSION_SPEED2 : 39|16@0+ (0.01,0) [0|250] "kph" EON - SG_ ODOMETER : 55|8@0+ (10,0) [0|2550] "m" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON - -BO_ 380 POWERTRAIN_DATA: 8 PCM - SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" EON - SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON - SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" EON - SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "rpm" EON - SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "rpm" EON - SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "rpm" EON - SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "rpm" EON - SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" EON - SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "rpm" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - -BO_ 420 VSA_STATUS: 8 VSA - SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON - SG_ COMPUTER_BRAKING : 23|1@0+ (1,0) [0|1] "" EON - SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON - SG_ BRAKE_HOLD_RELATED : 52|1@0+ (1,0) [0|1] "" XXX - SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" EON - SG_ BRAKE_HOLD_ENABLED : 45|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON - -BO_ 427 STEER_MOTOR_TORQUE: 3 EPS - SG_ CONFIG_VALID : 7|1@0+ (1,0) [0|1] "" EON - SG_ MOTOR_TORQUE : 1|10@0+ (1,0) [0|256] "" EON - SG_ OUTPUT_DISABLED : 22|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" EON - -BO_ 432 STANDSTILL: 7 VSA - SG_ CONTROLLED_STANDSTILL : 0|1@0+ (1,0) [0|1] "" EON - SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON - SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON - SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON - -BO_ 464 WHEEL_SPEEDS: 8 VSA - SG_ WHEEL_SPEED_FL : 7|15@0+ (0.01,0) [0|250] "kph" EON - SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON - SG_ WHEEL_SPEED_RL : 25|15@0+ (0.01,0) [0|250] "kph" EON - SG_ WHEEL_SPEED_RR : 42|15@0+ (0.01,0) [0|250] "kph" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - -BO_ 490 VEHICLE_DYNAMICS: 8 VSA - SG_ LONG_ACCEL : 23|16@0- (0.0015384,0) [-20|20] "m/s2" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - -BO_ 506 BRAKE_COMMAND: 8 ADAS - SG_ COMPUTER_BRAKE : 7|10@0+ (1,0) [0|1] "" EBCM - SG_ SET_ME_X00 : 13|5@0+ (1,0) [0|1] "" EBCM - SG_ BRAKE_PUMP_REQUEST : 8|1@0+ (1,0) [0|1] "" EBCM - SG_ SET_ME_X00_2 : 23|3@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_OVERRIDE : 20|1@0+ (1,0) [0|1] "" EBCM - SG_ SET_ME_X00_3 : 19|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_FAULT_CMD : 18|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_CANCEL_CMD : 17|1@0+ (1,0) [0|1] "" EBCM - SG_ COMPUTER_BRAKE_REQUEST : 16|1@0+ (1,0) [0|1] "" EBCM - SG_ SET_ME_1 : 31|1@0+ (1,0) [0|1] "" EBCM - SG_ AEB_REQ_1 : 29|1@0+ (1,0) [0|1] "" XXX - SG_ AEB_REQ_2 : 26|3@0+ (1,0) [0|7] "" XXX - SG_ BRAKE_LIGHTS : 39|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_STATES : 38|7@0+ (1,0) [0|1] "" EBCM - SG_ CHIME : 47|3@0+ (1,0) [0|7] "" EBCM - SG_ SET_ME_X00_4 : 44|1@0+ (1,0) [0|1] "" EBCM - SG_ FCW : 43|2@0+ (1,0) [0|3] "" EBCM - SG_ AEB_STATUS : 41|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X00_5 : 55|8@0+ (1,0) [0|0] "" EBCM - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EBCM - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EBCM - -BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA - SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" EON - SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" EON - SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" EON - SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" EON - SG_ SET_TO_X55 : 39|8@0+ (1,0) [0|255] "" EON - SG_ SET_TO_X55_2 : 47|8@0+ (1,0) [0|255] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON - -BO_ 773 SEATBELT_STATUS: 7 BDY - SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON - SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON - SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON - -BO_ 777 LOCK_STATUS: 8 XXX - SG_ DOORS_UNLOCKED : 54|1@0+ (1,0) [0|1] "" EON - SG_ DOORS_LOCKED : 55|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - -BO_ 780 ACC_HUD: 8 ADAS - SG_ PCM_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" BDY - SG_ PCM_GAS : 23|8@0+ (1,0) [0|127] "" BDY - SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY - SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY - SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY - SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY - SG_ FCM_OFF : 36|1@0+ (1,0) [0|1] "" BDY - SG_ FCM_OFF_2 : 35|1@0+ (1,0) [0|1] "" BDY - SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY - SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY - SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY - SG_ HUD_DISTANCE : 47|2@0+ (1,0) [0|3] "" BDY - SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY - SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY - SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY - SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY - SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY - SG_ SET_ME_X01_2 : 55|1@0+ (1,0) [0|1] "" BDY - SG_ IMPERIAL_UNIT : 54|1@0+ (1,0) [0|1] "" BDY - SG_ HUD_DISTANCE_3 : 52|1@0+ (1,0) [0|1] "" BDY - SG_ CHIME : 51|3@0+ (1,0) [0|1] "" BDY - SG_ SET_ME_X01 : 48|1@0+ (1,0) [0|1] "" BDY - SG_ ICONS : 63|2@0+ (1,0) [0|1] "" BDY - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY - -BO_ 804 CRUISE: 8 PCM - SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" EON - SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" EON - SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON - SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" EON - SG_ BOH2 : 47|8@0- (1,0) [0|255] "" EON - SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - -BO_ 829 LKAS_HUD: 5 ADAS - SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY - SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY - SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY - SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY - SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY - SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY - SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY - SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY - SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY - SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY - SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY - SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY - SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY - SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY - SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY - -BO_ 892 CRUISE_PARAMS: 8 PCM - SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - -BO_ 1029 DOORS_STATUS: 8 BDY - SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" EON - SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" EON - SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" EON - SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" EON - SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - -CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; -CM_ SG_ 506 AEB_REQ_1 "set for duration of suspected AEB event"; -CM_ SG_ 773 PASS_AIRBAG_ON "Might just be indicator light"; -CM_ SG_ 773 PASS_AIRBAG_OFF "Might just be indicator light"; -CM_ SG_ 780 CRUISE_SPEED "255 = no speed"; -CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; -CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; - - -VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw" ; -VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime" ; -VAL_ 506 AEB_STATUS 3 "aeb_prepare" 2 "aeb_ready" 1 "aeb_braking" 0 "no_aeb" ; -VAL_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped" ; -VAL_ 780 HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car" ; -VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; - - -CM_ "Imported file _comma.dbc starts here"; -BO_ 512 GAS_COMMAND: 6 EON - SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR - SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR - SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR - -BO_ 513 GAS_SENSOR: 6 INTERCEPTOR - SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON - SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON - SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON - -VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; - -CM_ "honda_pilot_touring_2017_can.dbc starts here"; - - - -BO_ 145 KINEMATICS: 8 XXX - SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON - -BO_ 228 STEERING_CONTROL: 5 ADAS - SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS - SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS - SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|0] "" EPS - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS - SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" EPS - -BO_ 304 GAS_PEDAL_2: 8 PCM - SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON - SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON - SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON - -BO_ 316 GAS_PEDAL: 8 PCM - SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON - -BO_ 342 STEERING_SENSORS: 6 EPS - SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON - SG_ STEER_ANGLE_RATE : 23|16@0- (-1,0) [-3000|3000] "deg/s" EON - SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON - -BO_ 399 STEER_STATUS: 7 EPS - SG_ STEER_TORQUE_SENSOR : 7|16@0- (-1,0) [-31000|31000] "tbd" EON - SG_ STEER_ANGLE_RATE : 23|16@0- (-0.1,0) [-31000|31000] "deg/s" EON - SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" EON - SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" EON - SG_ STEER_CONFIG_INDEX : 43|4@0+ (1,0) [0|15] "" EON - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON - -BO_ 419 GEARBOX: 8 PCM - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - SG_ GEAR_SHIFTER : 29|6@0+ (1,0) [0|63] "" EON - SG_ GEAR : 7|8@0+ (1,0) [0|255] "" EON - -BO_ 422 SCM_BUTTONS: 8 SCM - SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON - SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" EON - SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" EON - SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - -BO_ 660 SCM_FEEDBACK: 8 SCM - SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" EON - SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" EON - SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" EON - -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_ 419 GEAR_SHIFTER 32 "D" 8 "R" 4 "P" ; -VAL_ 422 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; -VAL_ 422 LIGHTS_SETTING 3 "high_beam" 2 "low_beam" 1 "position" 0 "no_lights" ; -VAL_ 422 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; - diff --git a/opendbc/honda_ridgeline_black_edition_2017_can_generated.dbc b/opendbc/honda_ridgeline_black_edition_2017_can_generated.dbc deleted file mode 100644 index 19ded5414..000000000 --- a/opendbc/honda_ridgeline_black_edition_2017_can_generated.dbc +++ /dev/null @@ -1,310 +0,0 @@ -CM_ "AUTOGENERATED FILE, DO NOT EDIT"; - - -CM_ "Imported file _honda_2017.dbc starts here"; -VERSION "" - - -NS_ : - NS_DESC_ - CM_ - BA_DEF_ - BA_ - VAL_ - CAT_DEF_ - CAT_ - FILTER - BA_DEF_DEF_ - EV_DATA_ - ENVVAR_DATA_ - SGTYPE_ - SGTYPE_VAL_ - BA_DEF_SGTYPE_ - BA_SGTYPE_ - SIG_TYPE_REF_ - VAL_TABLE_ - SIG_GROUP_ - SIG_VALTYPE_ - SIGTYPE_VALTYPE_ - BO_TX_BU_ - BA_DEF_REL_ - BA_REL_ - BA_DEF_DEF_REL_ - BU_SG_REL_ - BU_EV_REL_ - BU_BO_REL_ - SG_MUL_VAL_ - -BU_: EBCM ADAS PCM EPS VSA SCM BDY XXX EPB EON - -BO_ 344 ENGINE_DATA: 8 PCM - SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" EON - SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON - SG_ XMISSION_SPEED2 : 39|16@0+ (0.01,0) [0|250] "kph" EON - SG_ ODOMETER : 55|8@0+ (10,0) [0|2550] "m" XXX - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON - -BO_ 380 POWERTRAIN_DATA: 8 PCM - SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" EON - SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON - SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" EON - SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "rpm" EON - SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "rpm" EON - SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "rpm" EON - SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "rpm" EON - SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" EON - SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "rpm" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - -BO_ 420 VSA_STATUS: 8 VSA - SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON - SG_ COMPUTER_BRAKING : 23|1@0+ (1,0) [0|1] "" EON - SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON - SG_ BRAKE_HOLD_RELATED : 52|1@0+ (1,0) [0|1] "" XXX - SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" EON - SG_ BRAKE_HOLD_ENABLED : 45|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON - -BO_ 427 STEER_MOTOR_TORQUE: 3 EPS - SG_ CONFIG_VALID : 7|1@0+ (1,0) [0|1] "" EON - SG_ MOTOR_TORQUE : 1|10@0+ (1,0) [0|256] "" EON - SG_ OUTPUT_DISABLED : 22|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" EON - -BO_ 432 STANDSTILL: 7 VSA - SG_ CONTROLLED_STANDSTILL : 0|1@0+ (1,0) [0|1] "" EON - SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON - SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON - SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON - -BO_ 464 WHEEL_SPEEDS: 8 VSA - SG_ WHEEL_SPEED_FL : 7|15@0+ (0.01,0) [0|250] "kph" EON - SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON - SG_ WHEEL_SPEED_RL : 25|15@0+ (0.01,0) [0|250] "kph" EON - SG_ WHEEL_SPEED_RR : 42|15@0+ (0.01,0) [0|250] "kph" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - -BO_ 490 VEHICLE_DYNAMICS: 8 VSA - SG_ LONG_ACCEL : 23|16@0- (0.0015384,0) [-20|20] "m/s2" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - -BO_ 506 BRAKE_COMMAND: 8 ADAS - SG_ COMPUTER_BRAKE : 7|10@0+ (1,0) [0|1] "" EBCM - SG_ SET_ME_X00 : 13|5@0+ (1,0) [0|1] "" EBCM - SG_ BRAKE_PUMP_REQUEST : 8|1@0+ (1,0) [0|1] "" EBCM - SG_ SET_ME_X00_2 : 23|3@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_OVERRIDE : 20|1@0+ (1,0) [0|1] "" EBCM - SG_ SET_ME_X00_3 : 19|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_FAULT_CMD : 18|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_CANCEL_CMD : 17|1@0+ (1,0) [0|1] "" EBCM - SG_ COMPUTER_BRAKE_REQUEST : 16|1@0+ (1,0) [0|1] "" EBCM - SG_ SET_ME_1 : 31|1@0+ (1,0) [0|1] "" EBCM - SG_ AEB_REQ_1 : 29|1@0+ (1,0) [0|1] "" XXX - SG_ AEB_REQ_2 : 26|3@0+ (1,0) [0|7] "" XXX - SG_ BRAKE_LIGHTS : 39|1@0+ (1,0) [0|1] "" EBCM - SG_ CRUISE_STATES : 38|7@0+ (1,0) [0|1] "" EBCM - SG_ CHIME : 47|3@0+ (1,0) [0|7] "" EBCM - SG_ SET_ME_X00_4 : 44|1@0+ (1,0) [0|1] "" EBCM - SG_ FCW : 43|2@0+ (1,0) [0|3] "" EBCM - SG_ AEB_STATUS : 41|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X00_5 : 55|8@0+ (1,0) [0|0] "" EBCM - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EBCM - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EBCM - -BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA - SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" EON - SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" EON - SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" EON - SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" EON - SG_ SET_TO_X55 : 39|8@0+ (1,0) [0|255] "" EON - SG_ SET_TO_X55_2 : 47|8@0+ (1,0) [0|255] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON - -BO_ 773 SEATBELT_STATUS: 7 BDY - SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON - SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON - SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON - SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON - -BO_ 777 LOCK_STATUS: 8 XXX - SG_ DOORS_UNLOCKED : 54|1@0+ (1,0) [0|1] "" EON - SG_ DOORS_LOCKED : 55|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - -BO_ 780 ACC_HUD: 8 ADAS - SG_ PCM_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" BDY - SG_ PCM_GAS : 23|8@0+ (1,0) [0|127] "" BDY - SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY - SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY - SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY - SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY - SG_ FCM_OFF : 36|1@0+ (1,0) [0|1] "" BDY - SG_ FCM_OFF_2 : 35|1@0+ (1,0) [0|1] "" BDY - SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY - SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY - SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY - SG_ HUD_DISTANCE : 47|2@0+ (1,0) [0|3] "" BDY - SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY - SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY - SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY - SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY - SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY - SG_ SET_ME_X01_2 : 55|1@0+ (1,0) [0|1] "" BDY - SG_ IMPERIAL_UNIT : 54|1@0+ (1,0) [0|1] "" BDY - SG_ HUD_DISTANCE_3 : 52|1@0+ (1,0) [0|1] "" BDY - SG_ CHIME : 51|3@0+ (1,0) [0|1] "" BDY - SG_ SET_ME_X01 : 48|1@0+ (1,0) [0|1] "" BDY - SG_ ICONS : 63|2@0+ (1,0) [0|1] "" BDY - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY - -BO_ 804 CRUISE: 8 PCM - SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" EON - SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" EON - SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON - SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" EON - SG_ BOH2 : 47|8@0- (1,0) [0|255] "" EON - SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - -BO_ 829 LKAS_HUD: 5 ADAS - SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY - SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY - SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY - SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY - SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY - SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY - SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY - SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY - SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY - SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY - SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY - SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY - SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY - SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY - SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY - SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY - SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY - -BO_ 892 CRUISE_PARAMS: 8 PCM - SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - -BO_ 1029 DOORS_STATUS: 8 BDY - SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" EON - SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" EON - SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" EON - SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" EON - SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - -CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping"; -CM_ SG_ 506 AEB_REQ_1 "set for duration of suspected AEB event"; -CM_ SG_ 773 PASS_AIRBAG_ON "Might just be indicator light"; -CM_ SG_ 773 PASS_AIRBAG_OFF "Might just be indicator light"; -CM_ SG_ 780 CRUISE_SPEED "255 = no speed"; -CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed"; -CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc..."; - - -VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw" ; -VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime" ; -VAL_ 506 AEB_STATUS 3 "aeb_prepare" 2 "aeb_ready" 1 "aeb_braking" 0 "no_aeb" ; -VAL_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped" ; -VAL_ 780 HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car" ; -VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ; - - -CM_ "Imported file _comma.dbc starts here"; -BO_ 512 GAS_COMMAND: 6 EON - SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR - SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR - SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR - -BO_ 513 GAS_SENSOR: 6 INTERCEPTOR - SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON - SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON - SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON - -VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; - -CM_ "honda_ridgeline_black_edition_2017_can.dbc starts here"; - - - -BO_ 145 KINEMATICS: 8 XXX - SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON - -BO_ 228 STEERING_CONTROL: 5 ADAS - SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS - SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS - SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|0] "" EPS - SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS - SG_ CHECKSUM : 35|4@0+ (1,0) [0|3] "" EPS - -BO_ 316 GAS_PEDAL: 8 PCM - SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON - -BO_ 342 STEERING_SENSORS: 6 EPS - SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON - SG_ STEER_ANGLE_RATE : 23|16@0- (-1,0) [-3000|3000] "deg/s" EON - SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON - -BO_ 399 STEER_STATUS: 7 EPS - SG_ STEER_TORQUE_SENSOR : 7|16@0- (-1,0) [-31000|31000] "tbd" EON - SG_ STEER_ANGLE_RATE : 23|16@0- (-0.1,0) [-31000|31000] "deg/s" EON - SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" EON - SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" EON - SG_ STEER_CONFIG_INDEX : 43|4@0+ (1,0) [0|15] "" EON - SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON - -BO_ 419 GEARBOX: 8 PCM - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - SG_ GEAR_SHIFTER : 29|6@0+ (1,0) [0|63] "" EON - SG_ GEAR : 7|8@0+ (1,0) [0|255] "" EON - -BO_ 422 SCM_BUTTONS: 8 SCM - SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON - SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" EON - SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" EON - SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" EON - SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON - SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON - -BO_ 660 SCM_FEEDBACK: 8 SCM - SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" EON - SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" EON - SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" EON - -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_ 419 GEAR_SHIFTER 32 "D" 8 "R" 4 "P" ; -VAL_ 422 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ; -VAL_ 422 LIGHTS_SETTING 3 "high_beam" 2 "low_beam" 1 "position" 0 "no_lights" ; -VAL_ 422 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ; - diff --git a/opendbc/hyundai_kia_generic.dbc b/opendbc/hyundai_kia_generic.dbc index 3ae17aab6..4f54bac54 100644 --- a/opendbc/hyundai_kia_generic.dbc +++ b/opendbc/hyundai_kia_generic.dbc @@ -1641,17 +1641,17 @@ BO_ 1042 ICM_412h: 8 ICM BO_ 1348 Navi_HU: 8 XXX SG_ SpeedLim_Nav_Clu : 7|8@0+ (1,0) [0|255] "" XXX - - - -VAL_ 871 CF_Lvr_Gear 5 "D" 8 "S" 6 "N" 7 "R" 0 "P" ; -VAL_ 1322 CF_Clu_Gear 1 "P" 2 "R" 4 "N" 8 "D" ; -VAL_ 274 CUR_GR 1 "D" 2 "D" 3 "D" 4 "D" 5 "D" 6 "D" 7 "D" 8 "D" 14 "R" 0 "P" ; -VAL_ 909 CF_VSM_Warn 2 "FCW" 3 "AEB" ; -VAL_ 1157 HDA_Icon_State 0 "no_hda" 1 "white_hda" 2 "green_hda" ; -VAL_ 1157 LFA_SysWarning 0 "no_message" 1 "switching_to_hda" 2 "switching_to_scc" 3 "lfa_error" 4 "check_hda" 5 "keep_hands_on_wheel_orange" 6 "keep_hands_on_wheel_red" ; -VAL_ 1157 LFA_Icon_State 0 "no_wheel" 1 "white_wheel" 2 "green_wheel" 3 "green_wheel_blink" ; -VAL_ 1157 HDA_SysWarning 0 "no_message" 1 "driving_convenience_systems_cancelled" 2 "highway_drive_assist_system_cancelled" ; -VAL_ 882 Elect_Gear_Shifter 5 "D" 8 "S" 6 "N" 7 "R" 0 "P" ; CM_ "BO_ E_EMS11: All (plug-in) hybrids use this gas signal: CR_Vcu_AccPedDep_Pos, and all EVs use the Accel_Pedal_Pos signal. See hyundai/values.py for a specific car list"; -CM_ SG_ 1348 SpeedLim_Nav_Clu "Speed limit displayed on Nav, Cluster and HUD"; \ No newline at end of file +CM_ SG_ 1348 SpeedLim_Nav_Clu "Speed limit displayed on Nav, Cluster and HUD"; + +VAL_ 274 CUR_GR 1 "D" 2 "D" 3 "D" 4 "D" 5 "D" 6 "D" 7 "D" 8 "D" 14 "R" 0 "P"; +VAL_ 871 CF_Lvr_Gear 5 "D" 8 "S" 6 "N" 7 "R" 0 "P"; +VAL_ 882 Elect_Gear_Shifter 5 "D" 8 "S" 6 "N" 7 "R" 0 "P"; +VAL_ 905 ACCMode 0 "off" 1 "enabled" 2 "driver_override" 3 "off_maybe_fault" 4 "cancelled"; +VAL_ 909 CF_VSM_Warn 2 "FCW" 3 "AEB"; +VAL_ 1057 ACCMode 0 "off" 1 "enabled" 2 "driver_override" 3 "off_maybe_fault"; +VAL_ 1157 HDA_Icon_State 0 "no_hda" 1 "white_hda" 2 "green_hda"; +VAL_ 1157 LFA_SysWarning 0 "no_message" 1 "switching_to_hda" 2 "switching_to_scc" 3 "lfa_error" 4 "check_hda" 5 "keep_hands_on_wheel_orange" 6 "keep_hands_on_wheel_red"; +VAL_ 1157 LFA_Icon_State 0 "no_wheel" 1 "white_wheel" 2 "green_wheel" 3 "green_wheel_blink"; +VAL_ 1157 HDA_SysWarning 0 "no_message" 1 "driving_convenience_systems_cancelled" 2 "highway_drive_assist_system_cancelled"; +VAL_ 1322 CF_Clu_Gear 1 "P" 2 "R" 4 "N" 8 "D"; diff --git a/opendbc/lexus_is_2018_pt_generated.dbc b/opendbc/lexus_is_2018_pt_generated.dbc deleted file mode 100644 index 571dfee5d..000000000 --- a/opendbc/lexus_is_2018_pt_generated.dbc +++ /dev/null @@ -1,462 +0,0 @@ -CM_ "AUTOGENERATED FILE, DO NOT EDIT"; - - -CM_ "Imported file _toyota_2017.dbc starts here"; -VERSION "" - - -NS_ : - NS_DESC_ - CM_ - BA_DEF_ - BA_ - VAL_ - CAT_DEF_ - CAT_ - FILTER - BA_DEF_DEF_ - EV_DATA_ - ENVVAR_DATA_ - SGTYPE_ - SGTYPE_VAL_ - BA_DEF_SGTYPE_ - BA_SGTYPE_ - SIG_TYPE_REF_ - VAL_TABLE_ - SIG_GROUP_ - SIG_VALTYPE_ - SIGTYPE_VALTYPE_ - BO_TX_BU_ - BA_DEF_REL_ - BA_REL_ - BA_DEF_DEF_REL_ - BU_SG_REL_ - BU_EV_REL_ - BU_BO_REL_ - SG_MUL_VAL_ - -BS_: - -BU_: XXX DSU HCU EPS IPAS CGW - -BO_ 36 KINEMATICS: 8 XXX - SG_ ACCEL_Y : 33|10@0+ (0.03589,-18.375) [0|65535] "m/s^2" XXX - SG_ YAW_RATE : 1|10@0+ (0.244,-125) [0|65535] "deg/sec" XXX - SG_ STEERING_TORQUE : 17|10@0+ (1,-512) [0|65535] "" XXX - -BO_ 37 STEER_ANGLE_SENSOR: 8 XXX - SG_ STEER_ANGLE : 3|12@0- (1.5,0) [-500|500] "deg" XXX - SG_ STEER_FRACTION : 39|4@0- (0.1,0) [-0.7|0.7] "deg" XXX - SG_ STEER_RATE : 35|12@0- (1,0) [-2000|2000] "deg/s" XXX - -BO_ 166 BRAKE: 8 XXX - SG_ BRAKE_AMOUNT : 7|8@0+ (1,0) [0|255] "" XXX - SG_ BRAKE_PEDAL : 23|8@0+ (1,0) [0|255] "" XXX - -BO_ 170 WHEEL_SPEEDS: 8 XXX - SG_ WHEEL_SPEED_FR : 7|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_FL : 23|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_RR : 39|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_RL : 55|16@0+ (0.01,-67.67) [0|250] "kph" XXX - -BO_ 180 SPEED: 8 XXX - SG_ ENCODER : 39|8@0+ (1,0) [0|255] "" XXX - SG_ SPEED : 47|16@0+ (0.01,0) [0|250] "kph" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 353 DSU_SPEED: 7 XXX - SG_ FORWARD_SPEED : 15|16@0- (0.00390625,-30) [0|255] "kph" XXX - -BO_ 452 ENGINE_RPM: 8 CGW - SG_ RPM : 7|16@0- (0.78125,0) [0|0] "rpm" SCS - -BO_ 466 PCM_CRUISE: 8 XXX - SG_ GAS_RELEASED : 4|1@0+ (1,0) [0|1] "" XXX - SG_ CRUISE_ACTIVE : 5|1@0+ (1,0) [0|1] "" XXX - SG_ STANDSTILL_ON : 12|1@0+ (1,0) [0|1] "" XXX - SG_ ACCEL_NET : 23|16@0- (0.001,0) [-20|20] "m/s2" XXX - SG_ CRUISE_STATE : 55|4@0+ (1,0) [0|15] "" XXX - SG_ CANCEL_REQ : 49|1@1+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 467 PCM_CRUISE_2: 8 XXX - SG_ MAIN_ON : 15|1@0+ (1,0) [0|1] "" XXX - SG_ LOW_SPEED_LOCKOUT : 14|2@0+ (1,0) [0|3] "kph" XXX - SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "kph" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 552 ACCELEROMETER: 8 XXX - SG_ ACCEL_Z : 22|15@0- (1,0) [0|32767] "" XXX - SG_ ACCEL_X : 6|15@0- (0.001,0) [-20|20] "m/s2" XXX - -BO_ 560 BRAKE_MODULE2: 7 XXX - SG_ BRAKE_PRESSED : 26|1@0+ (1,0) [0|1] "" XXX - -BO_ 614 STEERING_IPAS: 8 IPAS - SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX - SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX - SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX - SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 643 PRE_COLLISION: 7 DSU - SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 15|8@0+ (1,0) [0|255] "" XXX - SG_ FORCE : 23|16@0- (2,0) [0|255] "N" XXX - SG_ SET_ME_X002 : 33|8@0+ (1,0) [0|3] "" XXX - SG_ BRAKE_STATUS : 39|3@0+ (1,0) [0|255] "" XXX - SG_ STATE : 36|3@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X003 : 40|1@0+ (1,0) [0|1] "" XXX - SG_ PRECOLLISION_ACTIVE : 41|1@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 55|8@0+ (1,0) [0|255] "" XXX - -BO_ 740 STEERING_LKA: 5 XXX - SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX - SG_ STEER_REQUEST : 0|1@0+ (1,0) [0|1] "" XXX - SG_ COUNTER : 6|6@0+ (1,0) [0|63] "" XXX - SG_ SET_ME_1 : 7|1@0+ (1,0) [0|1] "" XXX - SG_ STEER_TORQUE_CMD : 15|16@0- (1,0) [0|65535] "" XXX - SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX - -BO_ 742 LEAD_INFO: 8 DSU - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" HCU - SG_ LEAD_REL_SPEED : 23|12@0- (0.025,0) [-100|100] "m/s" HCU - SG_ LEAD_LONG_DIST : 7|13@0+ (0.05,0) [0|300] "m" HCU - -BO_ 835 ACC_CONTROL: 8 DSU - SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU - SG_ ACC_MALFUNCTION : 18|1@0+ (1,0) [0|0] "" XXX - SG_ ACC_CUT_IN : 25|1@0+ (1,0) [0|1] "" XXX - SG_ ALLOW_LONG_PRESS : 17|2@0+ (1,0) [0|2] "" XXX - SG_ ACC_TYPE : 23|2@0+ (1,0) [0|3] "" HCU - SG_ DISTANCE : 20|1@0+ (1,0) [0|1] "" XXX - SG_ MINI_CAR : 21|1@0+ (1,0) [0|1] "" XXX - SG_ PERMIT_BRAKING : 30|1@0+ (1,0) [0|1] "" HCU - SG_ RELEASE_STANDSTILL : 31|1@0+ (1,0) [0|1] "" HCU - SG_ CANCEL_REQ : 24|1@0+ (1,0) [0|1] "" HCU - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - SG_ ACCEL_CMD_ALT : 47|8@0- (0.05,0) [0|0] "m/s^2" XXX - SG_ RADAR_DIRTY : 19|1@0+ (1,0) [0|1] "" XXX - -BO_ 836 PRE_COLLISION_2: 8 DSU - SG_ CHECKSUM : 63|8@0+ (1,0) [0|0] "" XXX - -BO_ 869 DSU_CRUISE : 7 DSU - SG_ RES_BTN : 3|1@0+ (1,0) [0|0] "" XXX - SG_ SET_BTN : 2|1@0+ (1,0) [0|0] "" XXX - SG_ CANCEL_BTN : 1|1@0+ (1,0) [0|0] "" XXX - SG_ MAIN_ON : 0|1@0+ (1,0) [0|0] "" XXX - SG_ SET_SPEED : 15|8@0+ (1,0) [0|0] "km/h" XXX - SG_ CRUISE_REQUEST : 31|8@0+ (100,-12800) [0|0] "N" XXX - SG_ LEAD_DISTANCE : 39|8@0+ (1,0) [0|0] "m" XXX - -BO_ 921 PCM_CRUISE_SM: 8 XXX - SG_ MAIN_ON : 4|1@0+ (1,0) [0|1] "" XXX - SG_ CRUISE_CONTROL_STATE : 11|4@0+ (1,0) [0|15] "" XXX - SG_ DISTANCE_LINES : 14|2@0+ (1,0) [0|3] "" XXX - SG_ UI_SET_SPEED : 31|8@0+ (1,0) [0|255] "" XXX - -BO_ 951 ESP_CONTROL: 8 ESP - SG_ TC_DISABLED : 13|1@0+ (1,0) [0|1] "" XXX - SG_ VSC_DISABLED : 12|2@0+ (1,0) [0|1] "" XXX - SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" XXX - SG_ BRAKE_HOLD_ENABLED : 33|1@1+ (1,0) [0|1] "" XXX - SG_ BRAKE_HOLD_ACTIVE : 36|1@0+ (1,0) [0|1] "" XXX - -BO_ 1020 SOLAR_SENSOR: 8 XXX - SG_ LUX_SENSOR : 55|13@0+ (1,0) [0|0] "" XXX - -BO_ 1041 ACC_HUD: 8 DSU - SG_ PCS_INDICATOR : 7|2@0+ (1,0) [0|3] "" XXX - SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X20 : 15|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X10 : 39|8@0+ (1,0) [0|1] "" XXX - SG_ PCS_OFF : 40|1@0+ (1,0) [0|0] "" XXX - SG_ PCS_SENSITIVITY : 55|8@0+ (1,0) [0|1] "" XXX - -BO_ 1042 LKAS_HUD: 8 XXX - SG_ BARRIERS : 1|2@0+ (1,0) [0|3] "" XXX - SG_ RIGHT_LINE : 3|2@0+ (1,0) [0|3] "" XXX - SG_ LEFT_LINE : 5|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X01 : 7|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X01_2 : 11|2@0+ (1,0) [0|3] "" XXX - SG_ LDA_ALERT : 9|2@0+ (1,0) [0|3] "" XXX - SG_ TWO_BEEPS : 12|1@0+ (1,0) [0|1] "" XXX - SG_ ADJUSTING_CAMERA : 13|1@0+ (1,0) [0|1] "" XXX - SG_ LDA_MALFUNCTION : 15|1@0+ (1,0) [0|1] "" XXX - SG_ REPEATED_BEEPS : 32|1@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X0C : 23|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X2C : 47|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X38 : 55|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X02 : 63|8@0+ (1,0) [0|1] "" XXX - -BO_ 1043 TIME : 8 CGW - SG_ YEAR : 7|8@0+ (1,0) [0|0] "year" XXX - SG_ MONTH : 15|8@0+ (1,0) [0|0] "month" XXX - SG_ DAY : 23|8@0+ (1,0) [0|0] "day" XXX - SG_ HOUR : 31|8@0+ (1,0) [0|0] "hour" XXX - SG_ MINUTE : 39|8@0+ (1,0) [0|0] "minute" XXX - SG_ GMT_DIFF : 55|1@0+ (1,0) [0|0] "" XXX - SG_ GMTDIFF_HOURS : 54|4@0+ (1,0) [0|0] "hours" XXX - SG_ GMTDIFF_MINUTES : 50|6@0+ (1,0) [0|0] "minutes" XXX - SG_ SUMMER : 60|1@0+ (1,0) [0|0] "" XXX - -BO_ 1408 VIN_PART_1: 8 CGW - SG_ VIN_1 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_2 : 15|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_3 : 23|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_4 : 31|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_5 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_6 : 47|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_7 : 55|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_8 : 63|8@0+ (1,0) [0|0] "" XXX - -BO_ 1409 VIN_PART_2: 8 CGW - SG_ VIN_9 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_10 : 15|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_11 : 23|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_12 : 31|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_13 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_14 : 47|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_15 : 55|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_16 : 63|8@0+ (1,0) [0|0] "" XXX - -BO_ 1410 VIN_PART_3: 8 CGW - SG_ VIN_17 : 7|8@0+ (1,0) [0|0] "" XXX - -BO_ 1553 UI_SETTING: 8 XXX - SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX - SG_ ODOMETER : 43|20@0+ (1,0) [0|1048575] "" XXX - -BO_ 1556 STEERING_LEVERS: 8 XXX - SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX - SG_ HAZARD_LIGHT : 27|1@0+ (1,0) [0|1] "" XXX - -BO_ 1568 SEATS_DOORS: 8 XXX - SG_ METER_DIMMED : 38|1@0+ (1,0) [0|1] "" XXX - SG_ PARKING_BRAKE : 60|1@0+ (1,0) [0|1] "" XXX - SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_RR : 43|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_FR : 44|1@0+ (1,0) [0|1] "" XXX - -BO_ 1570 LIGHT_STALK: 8 SCM - SG_ AUTO_HIGH_BEAM : 37|1@0+ (1,0) [0|1] "" XXX - SG_ FRONT_FOG : 27|1@0+ (1,0) [0|1] "" XXX - SG_ PARKING_LIGHT : 28|1@0+ (1,0) [0|1] "" XXX - SG_ LOW_BEAM : 29|1@0+ (1,0) [0|1] "" XXX - SG_ HIGH_BEAM : 30|1@0+ (1,0) [0|1] "" XXX - SG_ DAYTIME_RUNNING_LIGHT : 31|1@0+ (1,0) [0|1] "" XXX - -BO_ 1161 RSA1: 8 FCM - SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY1 : 12|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT1 : 9|2@0+ (1,0) [0|0] "" XXX - SG_ SPDVAL1 : 23|8@0+ (1,0) [0|0] "kph" XXX - SG_ SPLSGN1 : 31|4@0+ (1,0) [0|0] "" XXX - SG_ SPLSGN2 : 27|4@0+ (1,0) [0|0] "" XXX - SG_ TSGN2 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY2 : 44|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT2 : 41|2@0+ (1,0) [0|0] "" XXX - SG_ SPDVAL2 : 55|8@0+ (1,0) [0|0] "" XXX - SG_ BZRRQ_P : 63|2@0+ (1,0) [0|0] "" XXX - SG_ BZRRQ_A : 61|2@0+ (1,0) [0|0] "" XXX - SG_ SYNCID1 : 59|4@0+ (1,0) [0|0] "" XXX - -BO_ 1162 RSA2: 8 FCM - SG_ TSGN3 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY3 : 12|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT3 : 9|2@0+ (1,0) [0|0] "" XXX - SG_ SPLSGN3 : 31|4@0+ (1,0) [0|0] "" XXX - SG_ SPLSGN4 : 27|4@0+ (1,0) [0|0] "" XXX - SG_ TSGN4 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY4 : 44|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT4 : 41|2@0+ (1,0) [0|0] "" XXX - SG_ DPSGNREQ : 54|1@0+ (1,0) [0|0] "" XXX - SG_ SGNNUMP : 53|3@0+ (1,0) [0|0] "" XXX - SG_ SGNNUMA : 50|3@0+ (1,0) [0|0] "" XXX - SG_ SPDUNT : 63|2@0+ (1,0) [0|0] "" XXX - SG_ TSRWMSG : 61|2@0+ (1,0) [0|0] "" XXX - SG_ SYNCID2 : 59|4@0+ (1,0) [0|0] "" XXX - -BO_ 1163 RSA3: 8 FCM - SG_ TSREQPD : 7|1@0+ (1,0) [0|0] "" XXX - SG_ TSRMSW : 6|1@0+ (1,0) [0|0] "" XXX - SG_ OTSGNNTM : 5|2@0+ (1,0) [0|0] "" XXX - SG_ NTLVLSPD : 3|2@0+ (1,0) [0|0] "" XXX - SG_ OVSPNTM : 1|2@0+ (1,0) [0|0] "" XXX - SG_ OVSPVALL : 11|4@0+ (1,-5) [0|0] "" XXX - SG_ OVSPVALM : 19|4@0+ (1,-5) [0|0] "" XXX - SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX - SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" XXX - -BO_ 1571 CENTRAL_GATEWAY_UNIT: 8 CGW - SG_ DOOR_LOCK_FEEDBACK_LIGHT : 15|1@0+ (1,0) [0|0] "" XXX - SG_ KEYFOB_LOCKING_FEEDBACK_LIGHT : 61|1@0+ (1,0) [0|0] "" XXX - SG_ KEYFOB_UNLOCKING_FEEDBACK_LIGHT : 62|1@0+ (1,0) [0|0] "" XXX - -CM_ SG_ 36 ACCEL_Y "unit is tbd"; -CM_ SG_ 36 YAW_RATE "verify"; -CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; -CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; -CM_ SG_ 37 STEER_RATE "factor is tbd"; -CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; -CM_ SG_ 466 CRUISE_STATE "Active state is 8, if standstill is requested will switch to state 11(3 sec timer), after timer is elapsed will switch into state 7(standstill). If plus button was pressed - status 9, minus button pressed - status 10"; -CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isn't perfect"; -CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; -CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; -CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; -CM_ SG_ 608 STEER_OVERRIDE "set when driver torque exceeds a certain value"; -CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; -CM_ SG_ 643 COUNTER "only used on cars that use this msg for cruise control"; -CM_ SG_ 643 BRAKE_STATUS "only used on cars that use this msg for cruise control"; -CM_ SG_ 643 PRECOLLISION_ACTIVE "set 0.5s before any braking"; -CM_ SG_ 835 ACC_TYPE "if 2, car is likely to have a permanent low speed lockout. 1 is ok"; -CM_ SG_ 835 RADAR_DIRTY "Display Clean Radar Sensor message on HUD"; -CM_ SG_ 835 ACC_MALFUNCTION "display ACC fault on dash if set to 1"; -CM_ SG_ 835 ACC_CUT_IN "Display blinking yellow lead if set to 1"; -CM_ SG_ 835 DISTANCE "Display Distance Bars on HUD Permanently"; -CM_ SG_ 835 ALLOW_LONG_PRESS "Enable Toyota's factory set speed increment behaviour, available on both metrics cars and imperial unit cars"; -CM_ SG_ 835 PERMIT_BRAKING "Original ACC has this going high when a car in front is detected. In openpilot and before the PERMIT_BRAKING name, this was 'SET_ME_1' and is hardcoded to be high. Unsure if only informational or has an effect though existing usage in openpilot is to always set it to 1. Originally 'PMTBRKG' in the leaked toyota_2017_ref_pt.dbc file and name expansion speculated to be PerMiT BRaKinG."; -CM_ SG_ 835 ACCEL_CMD_ALT "Copy of main ACCEL_CMD, but across 8 bits instead of 16 bits like ACCEL_CMD. Unsure if only informational or has an effect. Likely informational as existing openpilot sets this to 0 and no loss of functionality observed. Originally 'AT_RAW' in leaked toyota_2017_ref_pt.dbc file."; -CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; -CM_ SG_ 951 BRAKE_LIGHTS_ACC "brake lights when ACC commands decel"; -CM_ SG_ 1041 PCS_INDICATOR "Pre-Collision System Indicator"; -CM_ SG_ 1041 PCS_SENSITIVITY "Pre-Collision System Sensitivity"; -CM_ SG_ 1042 SET_ME_1 "unclear what this is, but it's always 1 in drive traces"; -CM_ SG_ 1042 REPEATED_BEEPS "recommended for fcw and other important alerts"; -CM_ SG_ 1161 SPDVAL1 "Numbers 0-199 is displayed, 200-254 displays circle without number and 255 is for no limit."; -CM_ SG_ 1161 SYNCID1 "counter from 1 to f at 1 Hz"; -CM_ SG_ 1161 SPDVAL2 "conditional speed value 70"; -CM_ SG_ 1162 SGNNUMP "1 if SPDVAL1 is set, otherwise 0"; -CM_ SG_ 1162 SYNCID2 "counter from 1 to f at 1 Hz"; -CM_ SG_ 1163 TSREQPD "always 1"; -CM_ SG_ 1163 TSRMSW "always 1"; -CM_ SG_ 1163 OTSGNNTM "always 3"; -CM_ SG_ 1163 NTLVLSPD "always 3"; -CM_ SG_ 1163 OVSPNTM "always 3"; -CM_ SG_ 1163 OVSPVALL "-5 at start then 2 after 2 seconds"; -CM_ SG_ 1163 OVSPVALM "-5 at start then 5 after 2 seconds"; -CM_ SG_ 1163 OVSPVALH "-5 at start then 10 after 2 seconds"; -CM_ SG_ 1163 TSRSPU "always 1"; -CM_ SG_ 1553 ODOMETER "Unit is dependent upon units signal"; - -VAL_ 466 CRUISE_STATE 11 "timer_3sec" 10 "adaptive click down" 9 "adaptive click up" 8 "adaptive engaged" 7 "standstill" 6 "non-adaptive click up" 5 "non-adaptive click down" 4 "non-adaptive hold down" 3 "non-adaptive hold up" 2 "non-adaptive being engaged" 1 "non-adaptive engaged" 0 "off"; -VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok"; -VAL_ 614 STATE 3 "enabled" 1 "disabled"; -VAL_ 614 DIRECTION_CMD 3 "right" 2 "center" 1 "left"; -VAL_ 643 STATE 0 "normal" 1 "adaptive_cruise_control" 3 "emergency_braking"; -VAL_ 835 ACC_TYPE 2 "permanent low speed lockout" 1 "ok"; -VAL_ 835 ACC_MALFUNCTION 1 "faulted" 0 "ok"; -VAL_ 835 ACC_CUT_IN 1 "CUT-IN Detected" 0 "clear"; -VAL_ 835 ALLOW_LONG_PRESS 2 "set speed increase by 5 speed units regardless" 1 "set speed increase by 1 speed unit on short press, 5 speed units on long press"; -VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted"; -VAL_ 1041 PCS_INDICATOR 2 "PCS Faulted" 1 "PCS Turned Off By User" 0 "PCS Enabled"; -VAL_ 1041 PCS_SENSITIVITY 64 "high sensitivity" 128 "mid sensitivity" 192 "low sensitivity" 0 "off"; -VAL_ 1042 LDA_ALERT 3 "hold with continuous beep" 2 "LDA unavailable" 1 "hold" 0 "none"; -VAL_ 1042 BARRIERS 3 "both" 2 "right" 1 "left" 0 "none"; -VAL_ 1042 RIGHT_LINE 3 "orange" 2 "faded" 1 "solid" 0 "none"; -VAL_ 1042 LEFT_LINE 3 "orange" 2 "faded" 1 "solid" 0 "none"; -VAL_ 1553 UNITS 1 "km" 2 "miles"; -VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left"; -VAL_ 1161 TSGN1 1 "speed sign" 0 "none"; -VAL_ 1161 TSGN2 1 "speed sign" 0 "none"; -VAL_ 1161 SPLSGN2 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none"; -VAL_ 1162 TSGN3 0 "none" 1 "speed sign" 2 "0 unlimited" 7 "unlimited" 16 "highway" 17 "no highway" 18 "motorway" 19 "no motorway" 20 "in city" 21 "outside city" 22 "pedestrian area" 23 "no pedestrian area" 65 "no overtaking left" 66 "no overtaking right" 67 "overtaking allowed again" 81 "no right turn" 97 "stop" 105 "yield" 113 "stop" 114 "yield us" 129 "no entry" 138 "no entry tss2" 145 "do not enter"; -VAL_ 1162 SPLSGN3 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none"; - - - - -CM_ "Imported file _comma.dbc starts here"; -BO_ 359 STEERING_IPAS_COMMA: 8 IPAS - SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX - SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX - SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX - SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant"; - - BO_ 512 GAS_COMMAND: 6 EON - SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR - SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR - SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR - - BO_ 513 GAS_SENSOR: 6 INTERCEPTOR - SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON - SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON - SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON - - VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; - -BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX - SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX - -CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss"; - -BO_ 767 SDSU: 8 XXX - SG_ FD_BUTTON : 7|1@0+ (1,0) [0|1] "" XXX - -CM_ "BO_ SDSU: The sDSU is a modified DSU for use in TSS1 Toyotas. Learn more: https://github.com/wocsor/panda/tree/smart_dsu"; - -CM_ SG_ 767 FD_BUTTON "The follow distance button signal as forwarded by the sdsu"; - -CM_ "lexus_is_2018_pt.dbc starts here"; - - - -BO_ 550 BRAKE_MODULE: 8 XXX - SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|511] "" XXX - SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|511] "" XXX - SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|1] "" XXX - -BO_ 581 GAS_PEDAL_ALT: 5 XXX - SG_ GAS_PEDAL : 23|8@0+ (0.005,0) [0|1] "" XXX - -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 - -BO_ 608 STEER_TORQUE_SENSOR: 8 XXX - SG_ STEER_TORQUE_EPS : 47|16@0- (0.77,0) [-20000|20000] "" XXX - SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX - SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - SG_ STEER_ANGLE : 31|16@0- (0.0573,0) [-500|500] "" XXX - -BO_ 610 EPS_STATUS: 5 EPS - SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX - SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX - SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX - -BO_ 956 GEAR_PACKET: 8 XXX - SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX - -BO_ 1009 PCM_CRUISE_ALT: 8 XXX - SG_ MAIN_ON : 13|1@0+ (1,0) [0|3] "" XXX - SG_ CRUISE_STATE : 10|1@0+ (1,0) [0|1] "" XXX - SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "mph" XXX - -BO_ 1599 LIGHT_STALK_ISH: 8 SCM - SG_ AUTO_HIGH_BEAM : 19|1@0+ (1,0) [0|1] "" XXX - -CM_ SG_ 550 BRAKE_PRESSURE "seems prop to pedal force"; -CM_ SG_ 550 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; -CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; -CM_ SG_ 1009 SET_SPEED "units seem to be whatever the car is set to"; -VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; -VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled"; -VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby"; diff --git a/opendbc/lexus_nx300_2018_pt_generated.dbc b/opendbc/lexus_nx300_2018_pt_generated.dbc deleted file mode 100644 index 5351a4f49..000000000 --- a/opendbc/lexus_nx300_2018_pt_generated.dbc +++ /dev/null @@ -1,455 +0,0 @@ -CM_ "AUTOGENERATED FILE, DO NOT EDIT"; - - -CM_ "Imported file _toyota_2017.dbc starts here"; -VERSION "" - - -NS_ : - NS_DESC_ - CM_ - BA_DEF_ - BA_ - VAL_ - CAT_DEF_ - CAT_ - FILTER - BA_DEF_DEF_ - EV_DATA_ - ENVVAR_DATA_ - SGTYPE_ - SGTYPE_VAL_ - BA_DEF_SGTYPE_ - BA_SGTYPE_ - SIG_TYPE_REF_ - VAL_TABLE_ - SIG_GROUP_ - SIG_VALTYPE_ - SIGTYPE_VALTYPE_ - BO_TX_BU_ - BA_DEF_REL_ - BA_REL_ - BA_DEF_DEF_REL_ - BU_SG_REL_ - BU_EV_REL_ - BU_BO_REL_ - SG_MUL_VAL_ - -BS_: - -BU_: XXX DSU HCU EPS IPAS CGW - -BO_ 36 KINEMATICS: 8 XXX - SG_ ACCEL_Y : 33|10@0+ (0.03589,-18.375) [0|65535] "m/s^2" XXX - SG_ YAW_RATE : 1|10@0+ (0.244,-125) [0|65535] "deg/sec" XXX - SG_ STEERING_TORQUE : 17|10@0+ (1,-512) [0|65535] "" XXX - -BO_ 37 STEER_ANGLE_SENSOR: 8 XXX - SG_ STEER_ANGLE : 3|12@0- (1.5,0) [-500|500] "deg" XXX - SG_ STEER_FRACTION : 39|4@0- (0.1,0) [-0.7|0.7] "deg" XXX - SG_ STEER_RATE : 35|12@0- (1,0) [-2000|2000] "deg/s" XXX - -BO_ 166 BRAKE: 8 XXX - SG_ BRAKE_AMOUNT : 7|8@0+ (1,0) [0|255] "" XXX - SG_ BRAKE_PEDAL : 23|8@0+ (1,0) [0|255] "" XXX - -BO_ 170 WHEEL_SPEEDS: 8 XXX - SG_ WHEEL_SPEED_FR : 7|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_FL : 23|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_RR : 39|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_RL : 55|16@0+ (0.01,-67.67) [0|250] "kph" XXX - -BO_ 180 SPEED: 8 XXX - SG_ ENCODER : 39|8@0+ (1,0) [0|255] "" XXX - SG_ SPEED : 47|16@0+ (0.01,0) [0|250] "kph" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 353 DSU_SPEED: 7 XXX - SG_ FORWARD_SPEED : 15|16@0- (0.00390625,-30) [0|255] "kph" XXX - -BO_ 452 ENGINE_RPM: 8 CGW - SG_ RPM : 7|16@0- (0.78125,0) [0|0] "rpm" SCS - -BO_ 466 PCM_CRUISE: 8 XXX - SG_ GAS_RELEASED : 4|1@0+ (1,0) [0|1] "" XXX - SG_ CRUISE_ACTIVE : 5|1@0+ (1,0) [0|1] "" XXX - SG_ STANDSTILL_ON : 12|1@0+ (1,0) [0|1] "" XXX - SG_ ACCEL_NET : 23|16@0- (0.001,0) [-20|20] "m/s2" XXX - SG_ CRUISE_STATE : 55|4@0+ (1,0) [0|15] "" XXX - SG_ CANCEL_REQ : 49|1@1+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 467 PCM_CRUISE_2: 8 XXX - SG_ MAIN_ON : 15|1@0+ (1,0) [0|1] "" XXX - SG_ LOW_SPEED_LOCKOUT : 14|2@0+ (1,0) [0|3] "kph" XXX - SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "kph" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 552 ACCELEROMETER: 8 XXX - SG_ ACCEL_Z : 22|15@0- (1,0) [0|32767] "" XXX - SG_ ACCEL_X : 6|15@0- (0.001,0) [-20|20] "m/s2" XXX - -BO_ 560 BRAKE_MODULE2: 7 XXX - SG_ BRAKE_PRESSED : 26|1@0+ (1,0) [0|1] "" XXX - -BO_ 614 STEERING_IPAS: 8 IPAS - SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX - SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX - SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX - SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 643 PRE_COLLISION: 7 DSU - SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 15|8@0+ (1,0) [0|255] "" XXX - SG_ FORCE : 23|16@0- (2,0) [0|255] "N" XXX - SG_ SET_ME_X002 : 33|8@0+ (1,0) [0|3] "" XXX - SG_ BRAKE_STATUS : 39|3@0+ (1,0) [0|255] "" XXX - SG_ STATE : 36|3@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X003 : 40|1@0+ (1,0) [0|1] "" XXX - SG_ PRECOLLISION_ACTIVE : 41|1@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 55|8@0+ (1,0) [0|255] "" XXX - -BO_ 740 STEERING_LKA: 5 XXX - SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX - SG_ STEER_REQUEST : 0|1@0+ (1,0) [0|1] "" XXX - SG_ COUNTER : 6|6@0+ (1,0) [0|63] "" XXX - SG_ SET_ME_1 : 7|1@0+ (1,0) [0|1] "" XXX - SG_ STEER_TORQUE_CMD : 15|16@0- (1,0) [0|65535] "" XXX - SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX - -BO_ 742 LEAD_INFO: 8 DSU - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" HCU - SG_ LEAD_REL_SPEED : 23|12@0- (0.025,0) [-100|100] "m/s" HCU - SG_ LEAD_LONG_DIST : 7|13@0+ (0.05,0) [0|300] "m" HCU - -BO_ 835 ACC_CONTROL: 8 DSU - SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU - SG_ ACC_MALFUNCTION : 18|1@0+ (1,0) [0|0] "" XXX - SG_ ACC_CUT_IN : 25|1@0+ (1,0) [0|1] "" XXX - SG_ ALLOW_LONG_PRESS : 17|2@0+ (1,0) [0|2] "" XXX - SG_ ACC_TYPE : 23|2@0+ (1,0) [0|3] "" HCU - SG_ DISTANCE : 20|1@0+ (1,0) [0|1] "" XXX - SG_ MINI_CAR : 21|1@0+ (1,0) [0|1] "" XXX - SG_ PERMIT_BRAKING : 30|1@0+ (1,0) [0|1] "" HCU - SG_ RELEASE_STANDSTILL : 31|1@0+ (1,0) [0|1] "" HCU - SG_ CANCEL_REQ : 24|1@0+ (1,0) [0|1] "" HCU - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - SG_ ACCEL_CMD_ALT : 47|8@0- (0.05,0) [0|0] "m/s^2" XXX - SG_ RADAR_DIRTY : 19|1@0+ (1,0) [0|1] "" XXX - -BO_ 836 PRE_COLLISION_2: 8 DSU - SG_ CHECKSUM : 63|8@0+ (1,0) [0|0] "" XXX - -BO_ 869 DSU_CRUISE : 7 DSU - SG_ RES_BTN : 3|1@0+ (1,0) [0|0] "" XXX - SG_ SET_BTN : 2|1@0+ (1,0) [0|0] "" XXX - SG_ CANCEL_BTN : 1|1@0+ (1,0) [0|0] "" XXX - SG_ MAIN_ON : 0|1@0+ (1,0) [0|0] "" XXX - SG_ SET_SPEED : 15|8@0+ (1,0) [0|0] "km/h" XXX - SG_ CRUISE_REQUEST : 31|8@0+ (100,-12800) [0|0] "N" XXX - SG_ LEAD_DISTANCE : 39|8@0+ (1,0) [0|0] "m" XXX - -BO_ 921 PCM_CRUISE_SM: 8 XXX - SG_ MAIN_ON : 4|1@0+ (1,0) [0|1] "" XXX - SG_ CRUISE_CONTROL_STATE : 11|4@0+ (1,0) [0|15] "" XXX - SG_ DISTANCE_LINES : 14|2@0+ (1,0) [0|3] "" XXX - SG_ UI_SET_SPEED : 31|8@0+ (1,0) [0|255] "" XXX - -BO_ 951 ESP_CONTROL: 8 ESP - SG_ TC_DISABLED : 13|1@0+ (1,0) [0|1] "" XXX - SG_ VSC_DISABLED : 12|2@0+ (1,0) [0|1] "" XXX - SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" XXX - SG_ BRAKE_HOLD_ENABLED : 33|1@1+ (1,0) [0|1] "" XXX - SG_ BRAKE_HOLD_ACTIVE : 36|1@0+ (1,0) [0|1] "" XXX - -BO_ 1020 SOLAR_SENSOR: 8 XXX - SG_ LUX_SENSOR : 55|13@0+ (1,0) [0|0] "" XXX - -BO_ 1041 ACC_HUD: 8 DSU - SG_ PCS_INDICATOR : 7|2@0+ (1,0) [0|3] "" XXX - SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X20 : 15|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X10 : 39|8@0+ (1,0) [0|1] "" XXX - SG_ PCS_OFF : 40|1@0+ (1,0) [0|0] "" XXX - SG_ PCS_SENSITIVITY : 55|8@0+ (1,0) [0|1] "" XXX - -BO_ 1042 LKAS_HUD: 8 XXX - SG_ BARRIERS : 1|2@0+ (1,0) [0|3] "" XXX - SG_ RIGHT_LINE : 3|2@0+ (1,0) [0|3] "" XXX - SG_ LEFT_LINE : 5|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X01 : 7|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X01_2 : 11|2@0+ (1,0) [0|3] "" XXX - SG_ LDA_ALERT : 9|2@0+ (1,0) [0|3] "" XXX - SG_ TWO_BEEPS : 12|1@0+ (1,0) [0|1] "" XXX - SG_ ADJUSTING_CAMERA : 13|1@0+ (1,0) [0|1] "" XXX - SG_ LDA_MALFUNCTION : 15|1@0+ (1,0) [0|1] "" XXX - SG_ REPEATED_BEEPS : 32|1@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X0C : 23|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X2C : 47|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X38 : 55|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X02 : 63|8@0+ (1,0) [0|1] "" XXX - -BO_ 1043 TIME : 8 CGW - SG_ YEAR : 7|8@0+ (1,0) [0|0] "year" XXX - SG_ MONTH : 15|8@0+ (1,0) [0|0] "month" XXX - SG_ DAY : 23|8@0+ (1,0) [0|0] "day" XXX - SG_ HOUR : 31|8@0+ (1,0) [0|0] "hour" XXX - SG_ MINUTE : 39|8@0+ (1,0) [0|0] "minute" XXX - SG_ GMT_DIFF : 55|1@0+ (1,0) [0|0] "" XXX - SG_ GMTDIFF_HOURS : 54|4@0+ (1,0) [0|0] "hours" XXX - SG_ GMTDIFF_MINUTES : 50|6@0+ (1,0) [0|0] "minutes" XXX - SG_ SUMMER : 60|1@0+ (1,0) [0|0] "" XXX - -BO_ 1408 VIN_PART_1: 8 CGW - SG_ VIN_1 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_2 : 15|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_3 : 23|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_4 : 31|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_5 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_6 : 47|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_7 : 55|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_8 : 63|8@0+ (1,0) [0|0] "" XXX - -BO_ 1409 VIN_PART_2: 8 CGW - SG_ VIN_9 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_10 : 15|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_11 : 23|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_12 : 31|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_13 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_14 : 47|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_15 : 55|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_16 : 63|8@0+ (1,0) [0|0] "" XXX - -BO_ 1410 VIN_PART_3: 8 CGW - SG_ VIN_17 : 7|8@0+ (1,0) [0|0] "" XXX - -BO_ 1553 UI_SETTING: 8 XXX - SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX - SG_ ODOMETER : 43|20@0+ (1,0) [0|1048575] "" XXX - -BO_ 1556 STEERING_LEVERS: 8 XXX - SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX - SG_ HAZARD_LIGHT : 27|1@0+ (1,0) [0|1] "" XXX - -BO_ 1568 SEATS_DOORS: 8 XXX - SG_ METER_DIMMED : 38|1@0+ (1,0) [0|1] "" XXX - SG_ PARKING_BRAKE : 60|1@0+ (1,0) [0|1] "" XXX - SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_RR : 43|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_FR : 44|1@0+ (1,0) [0|1] "" XXX - -BO_ 1570 LIGHT_STALK: 8 SCM - SG_ AUTO_HIGH_BEAM : 37|1@0+ (1,0) [0|1] "" XXX - SG_ FRONT_FOG : 27|1@0+ (1,0) [0|1] "" XXX - SG_ PARKING_LIGHT : 28|1@0+ (1,0) [0|1] "" XXX - SG_ LOW_BEAM : 29|1@0+ (1,0) [0|1] "" XXX - SG_ HIGH_BEAM : 30|1@0+ (1,0) [0|1] "" XXX - SG_ DAYTIME_RUNNING_LIGHT : 31|1@0+ (1,0) [0|1] "" XXX - -BO_ 1161 RSA1: 8 FCM - SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY1 : 12|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT1 : 9|2@0+ (1,0) [0|0] "" XXX - SG_ SPDVAL1 : 23|8@0+ (1,0) [0|0] "kph" XXX - SG_ SPLSGN1 : 31|4@0+ (1,0) [0|0] "" XXX - SG_ SPLSGN2 : 27|4@0+ (1,0) [0|0] "" XXX - SG_ TSGN2 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY2 : 44|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT2 : 41|2@0+ (1,0) [0|0] "" XXX - SG_ SPDVAL2 : 55|8@0+ (1,0) [0|0] "" XXX - SG_ BZRRQ_P : 63|2@0+ (1,0) [0|0] "" XXX - SG_ BZRRQ_A : 61|2@0+ (1,0) [0|0] "" XXX - SG_ SYNCID1 : 59|4@0+ (1,0) [0|0] "" XXX - -BO_ 1162 RSA2: 8 FCM - SG_ TSGN3 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY3 : 12|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT3 : 9|2@0+ (1,0) [0|0] "" XXX - SG_ SPLSGN3 : 31|4@0+ (1,0) [0|0] "" XXX - SG_ SPLSGN4 : 27|4@0+ (1,0) [0|0] "" XXX - SG_ TSGN4 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY4 : 44|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT4 : 41|2@0+ (1,0) [0|0] "" XXX - SG_ DPSGNREQ : 54|1@0+ (1,0) [0|0] "" XXX - SG_ SGNNUMP : 53|3@0+ (1,0) [0|0] "" XXX - SG_ SGNNUMA : 50|3@0+ (1,0) [0|0] "" XXX - SG_ SPDUNT : 63|2@0+ (1,0) [0|0] "" XXX - SG_ TSRWMSG : 61|2@0+ (1,0) [0|0] "" XXX - SG_ SYNCID2 : 59|4@0+ (1,0) [0|0] "" XXX - -BO_ 1163 RSA3: 8 FCM - SG_ TSREQPD : 7|1@0+ (1,0) [0|0] "" XXX - SG_ TSRMSW : 6|1@0+ (1,0) [0|0] "" XXX - SG_ OTSGNNTM : 5|2@0+ (1,0) [0|0] "" XXX - SG_ NTLVLSPD : 3|2@0+ (1,0) [0|0] "" XXX - SG_ OVSPNTM : 1|2@0+ (1,0) [0|0] "" XXX - SG_ OVSPVALL : 11|4@0+ (1,-5) [0|0] "" XXX - SG_ OVSPVALM : 19|4@0+ (1,-5) [0|0] "" XXX - SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX - SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" XXX - -BO_ 1571 CENTRAL_GATEWAY_UNIT: 8 CGW - SG_ DOOR_LOCK_FEEDBACK_LIGHT : 15|1@0+ (1,0) [0|0] "" XXX - SG_ KEYFOB_LOCKING_FEEDBACK_LIGHT : 61|1@0+ (1,0) [0|0] "" XXX - SG_ KEYFOB_UNLOCKING_FEEDBACK_LIGHT : 62|1@0+ (1,0) [0|0] "" XXX - -CM_ SG_ 36 ACCEL_Y "unit is tbd"; -CM_ SG_ 36 YAW_RATE "verify"; -CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; -CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; -CM_ SG_ 37 STEER_RATE "factor is tbd"; -CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; -CM_ SG_ 466 CRUISE_STATE "Active state is 8, if standstill is requested will switch to state 11(3 sec timer), after timer is elapsed will switch into state 7(standstill). If plus button was pressed - status 9, minus button pressed - status 10"; -CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isn't perfect"; -CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; -CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; -CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; -CM_ SG_ 608 STEER_OVERRIDE "set when driver torque exceeds a certain value"; -CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; -CM_ SG_ 643 COUNTER "only used on cars that use this msg for cruise control"; -CM_ SG_ 643 BRAKE_STATUS "only used on cars that use this msg for cruise control"; -CM_ SG_ 643 PRECOLLISION_ACTIVE "set 0.5s before any braking"; -CM_ SG_ 835 ACC_TYPE "if 2, car is likely to have a permanent low speed lockout. 1 is ok"; -CM_ SG_ 835 RADAR_DIRTY "Display Clean Radar Sensor message on HUD"; -CM_ SG_ 835 ACC_MALFUNCTION "display ACC fault on dash if set to 1"; -CM_ SG_ 835 ACC_CUT_IN "Display blinking yellow lead if set to 1"; -CM_ SG_ 835 DISTANCE "Display Distance Bars on HUD Permanently"; -CM_ SG_ 835 ALLOW_LONG_PRESS "Enable Toyota's factory set speed increment behaviour, available on both metrics cars and imperial unit cars"; -CM_ SG_ 835 PERMIT_BRAKING "Original ACC has this going high when a car in front is detected. In openpilot and before the PERMIT_BRAKING name, this was 'SET_ME_1' and is hardcoded to be high. Unsure if only informational or has an effect though existing usage in openpilot is to always set it to 1. Originally 'PMTBRKG' in the leaked toyota_2017_ref_pt.dbc file and name expansion speculated to be PerMiT BRaKinG."; -CM_ SG_ 835 ACCEL_CMD_ALT "Copy of main ACCEL_CMD, but across 8 bits instead of 16 bits like ACCEL_CMD. Unsure if only informational or has an effect. Likely informational as existing openpilot sets this to 0 and no loss of functionality observed. Originally 'AT_RAW' in leaked toyota_2017_ref_pt.dbc file."; -CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; -CM_ SG_ 951 BRAKE_LIGHTS_ACC "brake lights when ACC commands decel"; -CM_ SG_ 1041 PCS_INDICATOR "Pre-Collision System Indicator"; -CM_ SG_ 1041 PCS_SENSITIVITY "Pre-Collision System Sensitivity"; -CM_ SG_ 1042 SET_ME_1 "unclear what this is, but it's always 1 in drive traces"; -CM_ SG_ 1042 REPEATED_BEEPS "recommended for fcw and other important alerts"; -CM_ SG_ 1161 SPDVAL1 "Numbers 0-199 is displayed, 200-254 displays circle without number and 255 is for no limit."; -CM_ SG_ 1161 SYNCID1 "counter from 1 to f at 1 Hz"; -CM_ SG_ 1161 SPDVAL2 "conditional speed value 70"; -CM_ SG_ 1162 SGNNUMP "1 if SPDVAL1 is set, otherwise 0"; -CM_ SG_ 1162 SYNCID2 "counter from 1 to f at 1 Hz"; -CM_ SG_ 1163 TSREQPD "always 1"; -CM_ SG_ 1163 TSRMSW "always 1"; -CM_ SG_ 1163 OTSGNNTM "always 3"; -CM_ SG_ 1163 NTLVLSPD "always 3"; -CM_ SG_ 1163 OVSPNTM "always 3"; -CM_ SG_ 1163 OVSPVALL "-5 at start then 2 after 2 seconds"; -CM_ SG_ 1163 OVSPVALM "-5 at start then 5 after 2 seconds"; -CM_ SG_ 1163 OVSPVALH "-5 at start then 10 after 2 seconds"; -CM_ SG_ 1163 TSRSPU "always 1"; -CM_ SG_ 1553 ODOMETER "Unit is dependent upon units signal"; - -VAL_ 466 CRUISE_STATE 11 "timer_3sec" 10 "adaptive click down" 9 "adaptive click up" 8 "adaptive engaged" 7 "standstill" 6 "non-adaptive click up" 5 "non-adaptive click down" 4 "non-adaptive hold down" 3 "non-adaptive hold up" 2 "non-adaptive being engaged" 1 "non-adaptive engaged" 0 "off"; -VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok"; -VAL_ 614 STATE 3 "enabled" 1 "disabled"; -VAL_ 614 DIRECTION_CMD 3 "right" 2 "center" 1 "left"; -VAL_ 643 STATE 0 "normal" 1 "adaptive_cruise_control" 3 "emergency_braking"; -VAL_ 835 ACC_TYPE 2 "permanent low speed lockout" 1 "ok"; -VAL_ 835 ACC_MALFUNCTION 1 "faulted" 0 "ok"; -VAL_ 835 ACC_CUT_IN 1 "CUT-IN Detected" 0 "clear"; -VAL_ 835 ALLOW_LONG_PRESS 2 "set speed increase by 5 speed units regardless" 1 "set speed increase by 1 speed unit on short press, 5 speed units on long press"; -VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted"; -VAL_ 1041 PCS_INDICATOR 2 "PCS Faulted" 1 "PCS Turned Off By User" 0 "PCS Enabled"; -VAL_ 1041 PCS_SENSITIVITY 64 "high sensitivity" 128 "mid sensitivity" 192 "low sensitivity" 0 "off"; -VAL_ 1042 LDA_ALERT 3 "hold with continuous beep" 2 "LDA unavailable" 1 "hold" 0 "none"; -VAL_ 1042 BARRIERS 3 "both" 2 "right" 1 "left" 0 "none"; -VAL_ 1042 RIGHT_LINE 3 "orange" 2 "faded" 1 "solid" 0 "none"; -VAL_ 1042 LEFT_LINE 3 "orange" 2 "faded" 1 "solid" 0 "none"; -VAL_ 1553 UNITS 1 "km" 2 "miles"; -VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left"; -VAL_ 1161 TSGN1 1 "speed sign" 0 "none"; -VAL_ 1161 TSGN2 1 "speed sign" 0 "none"; -VAL_ 1161 SPLSGN2 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none"; -VAL_ 1162 TSGN3 0 "none" 1 "speed sign" 2 "0 unlimited" 7 "unlimited" 16 "highway" 17 "no highway" 18 "motorway" 19 "no motorway" 20 "in city" 21 "outside city" 22 "pedestrian area" 23 "no pedestrian area" 65 "no overtaking left" 66 "no overtaking right" 67 "overtaking allowed again" 81 "no right turn" 97 "stop" 105 "yield" 113 "stop" 114 "yield us" 129 "no entry" 138 "no entry tss2" 145 "do not enter"; -VAL_ 1162 SPLSGN3 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none"; - - - - -CM_ "Imported file _comma.dbc starts here"; -BO_ 359 STEERING_IPAS_COMMA: 8 IPAS - SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX - SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX - SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX - SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant"; - - BO_ 512 GAS_COMMAND: 6 EON - SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR - SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR - SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR - - BO_ 513 GAS_SENSOR: 6 INTERCEPTOR - SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON - SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON - SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON - - VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; - -BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX - SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX - -CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss"; - -BO_ 767 SDSU: 8 XXX - SG_ FD_BUTTON : 7|1@0+ (1,0) [0|1] "" XXX - -CM_ "BO_ SDSU: The sDSU is a modified DSU for use in TSS1 Toyotas. Learn more: https://github.com/wocsor/panda/tree/smart_dsu"; - -CM_ SG_ 767 FD_BUTTON "The follow distance button signal as forwarded by the sdsu"; - -CM_ "lexus_nx300_2018_pt.dbc starts here"; - - - -BO_ 550 BRAKE_MODULE: 8 XXX - SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|511] "" XXX - SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|511] "" XXX - SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|1] "" XXX - -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 - -BO_ 608 STEER_TORQUE_SENSOR: 8 XXX - SG_ STEER_TORQUE_EPS : 47|16@0- (0.73,0) [-20000|20000] "" XXX - SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX - SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - SG_ STEER_ANGLE : 31|16@0- (0.0573,0) [-500|500] "" XXX - -BO_ 610 EPS_STATUS: 5 EPS - SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX - SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX - SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX - -BO_ 956 GEAR_PACKET: 8 XXX - SG_ SPORT_ON : 2|1@0+ (1,0) [0|1] "" XXX - SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX - SG_ ECON_ON : 40|1@0+ (1,0) [0|1] "" XXX - -CM_ SG_ 550 BRAKE_PRESSURE "seems prop to pedal force"; -CM_ SG_ 550 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; -CM_ SG_ 581 GAS_PEDAL "it seems slightly filtered"; -CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; -VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled"; -VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby"; -VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; -VAL_ 956 SPORT_ON 0 "off" 1 "on"; -VAL_ 956 ECON_ON 0 "off" 1 "on"; diff --git a/opendbc/lexus_nx300h_2018_pt_generated.dbc b/opendbc/lexus_nx300h_2018_pt_generated.dbc deleted file mode 100644 index 0ec03a45c..000000000 --- a/opendbc/lexus_nx300h_2018_pt_generated.dbc +++ /dev/null @@ -1,454 +0,0 @@ -CM_ "AUTOGENERATED FILE, DO NOT EDIT"; - - -CM_ "Imported file _toyota_2017.dbc starts here"; -VERSION "" - - -NS_ : - NS_DESC_ - CM_ - BA_DEF_ - BA_ - VAL_ - CAT_DEF_ - CAT_ - FILTER - BA_DEF_DEF_ - EV_DATA_ - ENVVAR_DATA_ - SGTYPE_ - SGTYPE_VAL_ - BA_DEF_SGTYPE_ - BA_SGTYPE_ - SIG_TYPE_REF_ - VAL_TABLE_ - SIG_GROUP_ - SIG_VALTYPE_ - SIGTYPE_VALTYPE_ - BO_TX_BU_ - BA_DEF_REL_ - BA_REL_ - BA_DEF_DEF_REL_ - BU_SG_REL_ - BU_EV_REL_ - BU_BO_REL_ - SG_MUL_VAL_ - -BS_: - -BU_: XXX DSU HCU EPS IPAS CGW - -BO_ 36 KINEMATICS: 8 XXX - SG_ ACCEL_Y : 33|10@0+ (0.03589,-18.375) [0|65535] "m/s^2" XXX - SG_ YAW_RATE : 1|10@0+ (0.244,-125) [0|65535] "deg/sec" XXX - SG_ STEERING_TORQUE : 17|10@0+ (1,-512) [0|65535] "" XXX - -BO_ 37 STEER_ANGLE_SENSOR: 8 XXX - SG_ STEER_ANGLE : 3|12@0- (1.5,0) [-500|500] "deg" XXX - SG_ STEER_FRACTION : 39|4@0- (0.1,0) [-0.7|0.7] "deg" XXX - SG_ STEER_RATE : 35|12@0- (1,0) [-2000|2000] "deg/s" XXX - -BO_ 166 BRAKE: 8 XXX - SG_ BRAKE_AMOUNT : 7|8@0+ (1,0) [0|255] "" XXX - SG_ BRAKE_PEDAL : 23|8@0+ (1,0) [0|255] "" XXX - -BO_ 170 WHEEL_SPEEDS: 8 XXX - SG_ WHEEL_SPEED_FR : 7|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_FL : 23|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_RR : 39|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_RL : 55|16@0+ (0.01,-67.67) [0|250] "kph" XXX - -BO_ 180 SPEED: 8 XXX - SG_ ENCODER : 39|8@0+ (1,0) [0|255] "" XXX - SG_ SPEED : 47|16@0+ (0.01,0) [0|250] "kph" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 353 DSU_SPEED: 7 XXX - SG_ FORWARD_SPEED : 15|16@0- (0.00390625,-30) [0|255] "kph" XXX - -BO_ 452 ENGINE_RPM: 8 CGW - SG_ RPM : 7|16@0- (0.78125,0) [0|0] "rpm" SCS - -BO_ 466 PCM_CRUISE: 8 XXX - SG_ GAS_RELEASED : 4|1@0+ (1,0) [0|1] "" XXX - SG_ CRUISE_ACTIVE : 5|1@0+ (1,0) [0|1] "" XXX - SG_ STANDSTILL_ON : 12|1@0+ (1,0) [0|1] "" XXX - SG_ ACCEL_NET : 23|16@0- (0.001,0) [-20|20] "m/s2" XXX - SG_ CRUISE_STATE : 55|4@0+ (1,0) [0|15] "" XXX - SG_ CANCEL_REQ : 49|1@1+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 467 PCM_CRUISE_2: 8 XXX - SG_ MAIN_ON : 15|1@0+ (1,0) [0|1] "" XXX - SG_ LOW_SPEED_LOCKOUT : 14|2@0+ (1,0) [0|3] "kph" XXX - SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "kph" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 552 ACCELEROMETER: 8 XXX - SG_ ACCEL_Z : 22|15@0- (1,0) [0|32767] "" XXX - SG_ ACCEL_X : 6|15@0- (0.001,0) [-20|20] "m/s2" XXX - -BO_ 560 BRAKE_MODULE2: 7 XXX - SG_ BRAKE_PRESSED : 26|1@0+ (1,0) [0|1] "" XXX - -BO_ 614 STEERING_IPAS: 8 IPAS - SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX - SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX - SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX - SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 643 PRE_COLLISION: 7 DSU - SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 15|8@0+ (1,0) [0|255] "" XXX - SG_ FORCE : 23|16@0- (2,0) [0|255] "N" XXX - SG_ SET_ME_X002 : 33|8@0+ (1,0) [0|3] "" XXX - SG_ BRAKE_STATUS : 39|3@0+ (1,0) [0|255] "" XXX - SG_ STATE : 36|3@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X003 : 40|1@0+ (1,0) [0|1] "" XXX - SG_ PRECOLLISION_ACTIVE : 41|1@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 55|8@0+ (1,0) [0|255] "" XXX - -BO_ 740 STEERING_LKA: 5 XXX - SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX - SG_ STEER_REQUEST : 0|1@0+ (1,0) [0|1] "" XXX - SG_ COUNTER : 6|6@0+ (1,0) [0|63] "" XXX - SG_ SET_ME_1 : 7|1@0+ (1,0) [0|1] "" XXX - SG_ STEER_TORQUE_CMD : 15|16@0- (1,0) [0|65535] "" XXX - SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX - -BO_ 742 LEAD_INFO: 8 DSU - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" HCU - SG_ LEAD_REL_SPEED : 23|12@0- (0.025,0) [-100|100] "m/s" HCU - SG_ LEAD_LONG_DIST : 7|13@0+ (0.05,0) [0|300] "m" HCU - -BO_ 835 ACC_CONTROL: 8 DSU - SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU - SG_ ACC_MALFUNCTION : 18|1@0+ (1,0) [0|0] "" XXX - SG_ ACC_CUT_IN : 25|1@0+ (1,0) [0|1] "" XXX - SG_ ALLOW_LONG_PRESS : 17|2@0+ (1,0) [0|2] "" XXX - SG_ ACC_TYPE : 23|2@0+ (1,0) [0|3] "" HCU - SG_ DISTANCE : 20|1@0+ (1,0) [0|1] "" XXX - SG_ MINI_CAR : 21|1@0+ (1,0) [0|1] "" XXX - SG_ PERMIT_BRAKING : 30|1@0+ (1,0) [0|1] "" HCU - SG_ RELEASE_STANDSTILL : 31|1@0+ (1,0) [0|1] "" HCU - SG_ CANCEL_REQ : 24|1@0+ (1,0) [0|1] "" HCU - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - SG_ ACCEL_CMD_ALT : 47|8@0- (0.05,0) [0|0] "m/s^2" XXX - SG_ RADAR_DIRTY : 19|1@0+ (1,0) [0|1] "" XXX - -BO_ 836 PRE_COLLISION_2: 8 DSU - SG_ CHECKSUM : 63|8@0+ (1,0) [0|0] "" XXX - -BO_ 869 DSU_CRUISE : 7 DSU - SG_ RES_BTN : 3|1@0+ (1,0) [0|0] "" XXX - SG_ SET_BTN : 2|1@0+ (1,0) [0|0] "" XXX - SG_ CANCEL_BTN : 1|1@0+ (1,0) [0|0] "" XXX - SG_ MAIN_ON : 0|1@0+ (1,0) [0|0] "" XXX - SG_ SET_SPEED : 15|8@0+ (1,0) [0|0] "km/h" XXX - SG_ CRUISE_REQUEST : 31|8@0+ (100,-12800) [0|0] "N" XXX - SG_ LEAD_DISTANCE : 39|8@0+ (1,0) [0|0] "m" XXX - -BO_ 921 PCM_CRUISE_SM: 8 XXX - SG_ MAIN_ON : 4|1@0+ (1,0) [0|1] "" XXX - SG_ CRUISE_CONTROL_STATE : 11|4@0+ (1,0) [0|15] "" XXX - SG_ DISTANCE_LINES : 14|2@0+ (1,0) [0|3] "" XXX - SG_ UI_SET_SPEED : 31|8@0+ (1,0) [0|255] "" XXX - -BO_ 951 ESP_CONTROL: 8 ESP - SG_ TC_DISABLED : 13|1@0+ (1,0) [0|1] "" XXX - SG_ VSC_DISABLED : 12|2@0+ (1,0) [0|1] "" XXX - SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" XXX - SG_ BRAKE_HOLD_ENABLED : 33|1@1+ (1,0) [0|1] "" XXX - SG_ BRAKE_HOLD_ACTIVE : 36|1@0+ (1,0) [0|1] "" XXX - -BO_ 1020 SOLAR_SENSOR: 8 XXX - SG_ LUX_SENSOR : 55|13@0+ (1,0) [0|0] "" XXX - -BO_ 1041 ACC_HUD: 8 DSU - SG_ PCS_INDICATOR : 7|2@0+ (1,0) [0|3] "" XXX - SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X20 : 15|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X10 : 39|8@0+ (1,0) [0|1] "" XXX - SG_ PCS_OFF : 40|1@0+ (1,0) [0|0] "" XXX - SG_ PCS_SENSITIVITY : 55|8@0+ (1,0) [0|1] "" XXX - -BO_ 1042 LKAS_HUD: 8 XXX - SG_ BARRIERS : 1|2@0+ (1,0) [0|3] "" XXX - SG_ RIGHT_LINE : 3|2@0+ (1,0) [0|3] "" XXX - SG_ LEFT_LINE : 5|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X01 : 7|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X01_2 : 11|2@0+ (1,0) [0|3] "" XXX - SG_ LDA_ALERT : 9|2@0+ (1,0) [0|3] "" XXX - SG_ TWO_BEEPS : 12|1@0+ (1,0) [0|1] "" XXX - SG_ ADJUSTING_CAMERA : 13|1@0+ (1,0) [0|1] "" XXX - SG_ LDA_MALFUNCTION : 15|1@0+ (1,0) [0|1] "" XXX - SG_ REPEATED_BEEPS : 32|1@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X0C : 23|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X2C : 47|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X38 : 55|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X02 : 63|8@0+ (1,0) [0|1] "" XXX - -BO_ 1043 TIME : 8 CGW - SG_ YEAR : 7|8@0+ (1,0) [0|0] "year" XXX - SG_ MONTH : 15|8@0+ (1,0) [0|0] "month" XXX - SG_ DAY : 23|8@0+ (1,0) [0|0] "day" XXX - SG_ HOUR : 31|8@0+ (1,0) [0|0] "hour" XXX - SG_ MINUTE : 39|8@0+ (1,0) [0|0] "minute" XXX - SG_ GMT_DIFF : 55|1@0+ (1,0) [0|0] "" XXX - SG_ GMTDIFF_HOURS : 54|4@0+ (1,0) [0|0] "hours" XXX - SG_ GMTDIFF_MINUTES : 50|6@0+ (1,0) [0|0] "minutes" XXX - SG_ SUMMER : 60|1@0+ (1,0) [0|0] "" XXX - -BO_ 1408 VIN_PART_1: 8 CGW - SG_ VIN_1 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_2 : 15|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_3 : 23|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_4 : 31|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_5 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_6 : 47|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_7 : 55|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_8 : 63|8@0+ (1,0) [0|0] "" XXX - -BO_ 1409 VIN_PART_2: 8 CGW - SG_ VIN_9 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_10 : 15|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_11 : 23|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_12 : 31|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_13 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_14 : 47|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_15 : 55|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_16 : 63|8@0+ (1,0) [0|0] "" XXX - -BO_ 1410 VIN_PART_3: 8 CGW - SG_ VIN_17 : 7|8@0+ (1,0) [0|0] "" XXX - -BO_ 1553 UI_SETTING: 8 XXX - SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX - SG_ ODOMETER : 43|20@0+ (1,0) [0|1048575] "" XXX - -BO_ 1556 STEERING_LEVERS: 8 XXX - SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX - SG_ HAZARD_LIGHT : 27|1@0+ (1,0) [0|1] "" XXX - -BO_ 1568 SEATS_DOORS: 8 XXX - SG_ METER_DIMMED : 38|1@0+ (1,0) [0|1] "" XXX - SG_ PARKING_BRAKE : 60|1@0+ (1,0) [0|1] "" XXX - SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_RR : 43|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_FR : 44|1@0+ (1,0) [0|1] "" XXX - -BO_ 1570 LIGHT_STALK: 8 SCM - SG_ AUTO_HIGH_BEAM : 37|1@0+ (1,0) [0|1] "" XXX - SG_ FRONT_FOG : 27|1@0+ (1,0) [0|1] "" XXX - SG_ PARKING_LIGHT : 28|1@0+ (1,0) [0|1] "" XXX - SG_ LOW_BEAM : 29|1@0+ (1,0) [0|1] "" XXX - SG_ HIGH_BEAM : 30|1@0+ (1,0) [0|1] "" XXX - SG_ DAYTIME_RUNNING_LIGHT : 31|1@0+ (1,0) [0|1] "" XXX - -BO_ 1161 RSA1: 8 FCM - SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY1 : 12|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT1 : 9|2@0+ (1,0) [0|0] "" XXX - SG_ SPDVAL1 : 23|8@0+ (1,0) [0|0] "kph" XXX - SG_ SPLSGN1 : 31|4@0+ (1,0) [0|0] "" XXX - SG_ SPLSGN2 : 27|4@0+ (1,0) [0|0] "" XXX - SG_ TSGN2 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY2 : 44|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT2 : 41|2@0+ (1,0) [0|0] "" XXX - SG_ SPDVAL2 : 55|8@0+ (1,0) [0|0] "" XXX - SG_ BZRRQ_P : 63|2@0+ (1,0) [0|0] "" XXX - SG_ BZRRQ_A : 61|2@0+ (1,0) [0|0] "" XXX - SG_ SYNCID1 : 59|4@0+ (1,0) [0|0] "" XXX - -BO_ 1162 RSA2: 8 FCM - SG_ TSGN3 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY3 : 12|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT3 : 9|2@0+ (1,0) [0|0] "" XXX - SG_ SPLSGN3 : 31|4@0+ (1,0) [0|0] "" XXX - SG_ SPLSGN4 : 27|4@0+ (1,0) [0|0] "" XXX - SG_ TSGN4 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY4 : 44|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT4 : 41|2@0+ (1,0) [0|0] "" XXX - SG_ DPSGNREQ : 54|1@0+ (1,0) [0|0] "" XXX - SG_ SGNNUMP : 53|3@0+ (1,0) [0|0] "" XXX - SG_ SGNNUMA : 50|3@0+ (1,0) [0|0] "" XXX - SG_ SPDUNT : 63|2@0+ (1,0) [0|0] "" XXX - SG_ TSRWMSG : 61|2@0+ (1,0) [0|0] "" XXX - SG_ SYNCID2 : 59|4@0+ (1,0) [0|0] "" XXX - -BO_ 1163 RSA3: 8 FCM - SG_ TSREQPD : 7|1@0+ (1,0) [0|0] "" XXX - SG_ TSRMSW : 6|1@0+ (1,0) [0|0] "" XXX - SG_ OTSGNNTM : 5|2@0+ (1,0) [0|0] "" XXX - SG_ NTLVLSPD : 3|2@0+ (1,0) [0|0] "" XXX - SG_ OVSPNTM : 1|2@0+ (1,0) [0|0] "" XXX - SG_ OVSPVALL : 11|4@0+ (1,-5) [0|0] "" XXX - SG_ OVSPVALM : 19|4@0+ (1,-5) [0|0] "" XXX - SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX - SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" XXX - -BO_ 1571 CENTRAL_GATEWAY_UNIT: 8 CGW - SG_ DOOR_LOCK_FEEDBACK_LIGHT : 15|1@0+ (1,0) [0|0] "" XXX - SG_ KEYFOB_LOCKING_FEEDBACK_LIGHT : 61|1@0+ (1,0) [0|0] "" XXX - SG_ KEYFOB_UNLOCKING_FEEDBACK_LIGHT : 62|1@0+ (1,0) [0|0] "" XXX - -CM_ SG_ 36 ACCEL_Y "unit is tbd"; -CM_ SG_ 36 YAW_RATE "verify"; -CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; -CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; -CM_ SG_ 37 STEER_RATE "factor is tbd"; -CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; -CM_ SG_ 466 CRUISE_STATE "Active state is 8, if standstill is requested will switch to state 11(3 sec timer), after timer is elapsed will switch into state 7(standstill). If plus button was pressed - status 9, minus button pressed - status 10"; -CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isn't perfect"; -CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; -CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; -CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; -CM_ SG_ 608 STEER_OVERRIDE "set when driver torque exceeds a certain value"; -CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; -CM_ SG_ 643 COUNTER "only used on cars that use this msg for cruise control"; -CM_ SG_ 643 BRAKE_STATUS "only used on cars that use this msg for cruise control"; -CM_ SG_ 643 PRECOLLISION_ACTIVE "set 0.5s before any braking"; -CM_ SG_ 835 ACC_TYPE "if 2, car is likely to have a permanent low speed lockout. 1 is ok"; -CM_ SG_ 835 RADAR_DIRTY "Display Clean Radar Sensor message on HUD"; -CM_ SG_ 835 ACC_MALFUNCTION "display ACC fault on dash if set to 1"; -CM_ SG_ 835 ACC_CUT_IN "Display blinking yellow lead if set to 1"; -CM_ SG_ 835 DISTANCE "Display Distance Bars on HUD Permanently"; -CM_ SG_ 835 ALLOW_LONG_PRESS "Enable Toyota's factory set speed increment behaviour, available on both metrics cars and imperial unit cars"; -CM_ SG_ 835 PERMIT_BRAKING "Original ACC has this going high when a car in front is detected. In openpilot and before the PERMIT_BRAKING name, this was 'SET_ME_1' and is hardcoded to be high. Unsure if only informational or has an effect though existing usage in openpilot is to always set it to 1. Originally 'PMTBRKG' in the leaked toyota_2017_ref_pt.dbc file and name expansion speculated to be PerMiT BRaKinG."; -CM_ SG_ 835 ACCEL_CMD_ALT "Copy of main ACCEL_CMD, but across 8 bits instead of 16 bits like ACCEL_CMD. Unsure if only informational or has an effect. Likely informational as existing openpilot sets this to 0 and no loss of functionality observed. Originally 'AT_RAW' in leaked toyota_2017_ref_pt.dbc file."; -CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; -CM_ SG_ 951 BRAKE_LIGHTS_ACC "brake lights when ACC commands decel"; -CM_ SG_ 1041 PCS_INDICATOR "Pre-Collision System Indicator"; -CM_ SG_ 1041 PCS_SENSITIVITY "Pre-Collision System Sensitivity"; -CM_ SG_ 1042 SET_ME_1 "unclear what this is, but it's always 1 in drive traces"; -CM_ SG_ 1042 REPEATED_BEEPS "recommended for fcw and other important alerts"; -CM_ SG_ 1161 SPDVAL1 "Numbers 0-199 is displayed, 200-254 displays circle without number and 255 is for no limit."; -CM_ SG_ 1161 SYNCID1 "counter from 1 to f at 1 Hz"; -CM_ SG_ 1161 SPDVAL2 "conditional speed value 70"; -CM_ SG_ 1162 SGNNUMP "1 if SPDVAL1 is set, otherwise 0"; -CM_ SG_ 1162 SYNCID2 "counter from 1 to f at 1 Hz"; -CM_ SG_ 1163 TSREQPD "always 1"; -CM_ SG_ 1163 TSRMSW "always 1"; -CM_ SG_ 1163 OTSGNNTM "always 3"; -CM_ SG_ 1163 NTLVLSPD "always 3"; -CM_ SG_ 1163 OVSPNTM "always 3"; -CM_ SG_ 1163 OVSPVALL "-5 at start then 2 after 2 seconds"; -CM_ SG_ 1163 OVSPVALM "-5 at start then 5 after 2 seconds"; -CM_ SG_ 1163 OVSPVALH "-5 at start then 10 after 2 seconds"; -CM_ SG_ 1163 TSRSPU "always 1"; -CM_ SG_ 1553 ODOMETER "Unit is dependent upon units signal"; - -VAL_ 466 CRUISE_STATE 11 "timer_3sec" 10 "adaptive click down" 9 "adaptive click up" 8 "adaptive engaged" 7 "standstill" 6 "non-adaptive click up" 5 "non-adaptive click down" 4 "non-adaptive hold down" 3 "non-adaptive hold up" 2 "non-adaptive being engaged" 1 "non-adaptive engaged" 0 "off"; -VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok"; -VAL_ 614 STATE 3 "enabled" 1 "disabled"; -VAL_ 614 DIRECTION_CMD 3 "right" 2 "center" 1 "left"; -VAL_ 643 STATE 0 "normal" 1 "adaptive_cruise_control" 3 "emergency_braking"; -VAL_ 835 ACC_TYPE 2 "permanent low speed lockout" 1 "ok"; -VAL_ 835 ACC_MALFUNCTION 1 "faulted" 0 "ok"; -VAL_ 835 ACC_CUT_IN 1 "CUT-IN Detected" 0 "clear"; -VAL_ 835 ALLOW_LONG_PRESS 2 "set speed increase by 5 speed units regardless" 1 "set speed increase by 1 speed unit on short press, 5 speed units on long press"; -VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted"; -VAL_ 1041 PCS_INDICATOR 2 "PCS Faulted" 1 "PCS Turned Off By User" 0 "PCS Enabled"; -VAL_ 1041 PCS_SENSITIVITY 64 "high sensitivity" 128 "mid sensitivity" 192 "low sensitivity" 0 "off"; -VAL_ 1042 LDA_ALERT 3 "hold with continuous beep" 2 "LDA unavailable" 1 "hold" 0 "none"; -VAL_ 1042 BARRIERS 3 "both" 2 "right" 1 "left" 0 "none"; -VAL_ 1042 RIGHT_LINE 3 "orange" 2 "faded" 1 "solid" 0 "none"; -VAL_ 1042 LEFT_LINE 3 "orange" 2 "faded" 1 "solid" 0 "none"; -VAL_ 1553 UNITS 1 "km" 2 "miles"; -VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left"; -VAL_ 1161 TSGN1 1 "speed sign" 0 "none"; -VAL_ 1161 TSGN2 1 "speed sign" 0 "none"; -VAL_ 1161 SPLSGN2 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none"; -VAL_ 1162 TSGN3 0 "none" 1 "speed sign" 2 "0 unlimited" 7 "unlimited" 16 "highway" 17 "no highway" 18 "motorway" 19 "no motorway" 20 "in city" 21 "outside city" 22 "pedestrian area" 23 "no pedestrian area" 65 "no overtaking left" 66 "no overtaking right" 67 "overtaking allowed again" 81 "no right turn" 97 "stop" 105 "yield" 113 "stop" 114 "yield us" 129 "no entry" 138 "no entry tss2" 145 "do not enter"; -VAL_ 1162 SPLSGN3 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none"; - - - - -CM_ "Imported file _comma.dbc starts here"; -BO_ 359 STEERING_IPAS_COMMA: 8 IPAS - SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX - SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX - SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX - SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant"; - - BO_ 512 GAS_COMMAND: 6 EON - SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR - SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR - SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR - - BO_ 513 GAS_SENSOR: 6 INTERCEPTOR - SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON - SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON - SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON - - VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; - -BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX - SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX - -CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss"; - -BO_ 767 SDSU: 8 XXX - SG_ FD_BUTTON : 7|1@0+ (1,0) [0|1] "" XXX - -CM_ "BO_ SDSU: The sDSU is a modified DSU for use in TSS1 Toyotas. Learn more: https://github.com/wocsor/panda/tree/smart_dsu"; - -CM_ SG_ 767 FD_BUTTON "The follow distance button signal as forwarded by the sdsu"; - -CM_ "lexus_nx300h_2018_pt.dbc starts here"; - - - -BO_ 550 BRAKE_MODULE: 8 XXX - SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|511] "" XXX - SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|511] "" XXX - SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|1] "" XXX - -BO_ 581 GAS_PEDAL: 5 XXX - SG_ GAS_PEDAL : 23|8@0+ (0.005,0) [0|1] "" XXX - -BO_ 608 STEER_TORQUE_SENSOR: 8 XXX - SG_ STEER_TORQUE_EPS : 47|16@0- (0.73,0) [-20000|20000] "" XXX - SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX - SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - SG_ STEER_ANGLE : 31|16@0- (0.0573,0) [-500|500] "" XXX - -BO_ 610 EPS_STATUS: 5 EPS - SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX - SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX - SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX - -BO_ 956 GEAR_PACKET: 8 XXX - SG_ SPORT_ON : 2|1@0+ (1,0) [0|1] "" XXX - SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX - SG_ ECON_ON : 40|1@0+ (1,0) [0|1] "" XXX - -CM_ SG_ 550 BRAKE_PRESSURE "seems prop to pedal force"; -CM_ SG_ 550 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; -CM_ SG_ 581 GAS_PEDAL "it seems slightly filtered"; -CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; -VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled"; -VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby"; -VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; -VAL_ 956 SPORT_ON 0 "off" 1 "on"; -VAL_ 956 ECON_ON 0 "off" 1 "on"; diff --git a/opendbc/lexus_rx_350_2016_pt_generated.dbc b/opendbc/lexus_rx_350_2016_pt_generated.dbc deleted file mode 100644 index e4ea2289b..000000000 --- a/opendbc/lexus_rx_350_2016_pt_generated.dbc +++ /dev/null @@ -1,454 +0,0 @@ -CM_ "AUTOGENERATED FILE, DO NOT EDIT"; - - -CM_ "Imported file _toyota_2017.dbc starts here"; -VERSION "" - - -NS_ : - NS_DESC_ - CM_ - BA_DEF_ - BA_ - VAL_ - CAT_DEF_ - CAT_ - FILTER - BA_DEF_DEF_ - EV_DATA_ - ENVVAR_DATA_ - SGTYPE_ - SGTYPE_VAL_ - BA_DEF_SGTYPE_ - BA_SGTYPE_ - SIG_TYPE_REF_ - VAL_TABLE_ - SIG_GROUP_ - SIG_VALTYPE_ - SIGTYPE_VALTYPE_ - BO_TX_BU_ - BA_DEF_REL_ - BA_REL_ - BA_DEF_DEF_REL_ - BU_SG_REL_ - BU_EV_REL_ - BU_BO_REL_ - SG_MUL_VAL_ - -BS_: - -BU_: XXX DSU HCU EPS IPAS CGW - -BO_ 36 KINEMATICS: 8 XXX - SG_ ACCEL_Y : 33|10@0+ (0.03589,-18.375) [0|65535] "m/s^2" XXX - SG_ YAW_RATE : 1|10@0+ (0.244,-125) [0|65535] "deg/sec" XXX - SG_ STEERING_TORQUE : 17|10@0+ (1,-512) [0|65535] "" XXX - -BO_ 37 STEER_ANGLE_SENSOR: 8 XXX - SG_ STEER_ANGLE : 3|12@0- (1.5,0) [-500|500] "deg" XXX - SG_ STEER_FRACTION : 39|4@0- (0.1,0) [-0.7|0.7] "deg" XXX - SG_ STEER_RATE : 35|12@0- (1,0) [-2000|2000] "deg/s" XXX - -BO_ 166 BRAKE: 8 XXX - SG_ BRAKE_AMOUNT : 7|8@0+ (1,0) [0|255] "" XXX - SG_ BRAKE_PEDAL : 23|8@0+ (1,0) [0|255] "" XXX - -BO_ 170 WHEEL_SPEEDS: 8 XXX - SG_ WHEEL_SPEED_FR : 7|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_FL : 23|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_RR : 39|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_RL : 55|16@0+ (0.01,-67.67) [0|250] "kph" XXX - -BO_ 180 SPEED: 8 XXX - SG_ ENCODER : 39|8@0+ (1,0) [0|255] "" XXX - SG_ SPEED : 47|16@0+ (0.01,0) [0|250] "kph" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 353 DSU_SPEED: 7 XXX - SG_ FORWARD_SPEED : 15|16@0- (0.00390625,-30) [0|255] "kph" XXX - -BO_ 452 ENGINE_RPM: 8 CGW - SG_ RPM : 7|16@0- (0.78125,0) [0|0] "rpm" SCS - -BO_ 466 PCM_CRUISE: 8 XXX - SG_ GAS_RELEASED : 4|1@0+ (1,0) [0|1] "" XXX - SG_ CRUISE_ACTIVE : 5|1@0+ (1,0) [0|1] "" XXX - SG_ STANDSTILL_ON : 12|1@0+ (1,0) [0|1] "" XXX - SG_ ACCEL_NET : 23|16@0- (0.001,0) [-20|20] "m/s2" XXX - SG_ CRUISE_STATE : 55|4@0+ (1,0) [0|15] "" XXX - SG_ CANCEL_REQ : 49|1@1+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 467 PCM_CRUISE_2: 8 XXX - SG_ MAIN_ON : 15|1@0+ (1,0) [0|1] "" XXX - SG_ LOW_SPEED_LOCKOUT : 14|2@0+ (1,0) [0|3] "kph" XXX - SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "kph" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 552 ACCELEROMETER: 8 XXX - SG_ ACCEL_Z : 22|15@0- (1,0) [0|32767] "" XXX - SG_ ACCEL_X : 6|15@0- (0.001,0) [-20|20] "m/s2" XXX - -BO_ 560 BRAKE_MODULE2: 7 XXX - SG_ BRAKE_PRESSED : 26|1@0+ (1,0) [0|1] "" XXX - -BO_ 614 STEERING_IPAS: 8 IPAS - SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX - SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX - SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX - SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 643 PRE_COLLISION: 7 DSU - SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 15|8@0+ (1,0) [0|255] "" XXX - SG_ FORCE : 23|16@0- (2,0) [0|255] "N" XXX - SG_ SET_ME_X002 : 33|8@0+ (1,0) [0|3] "" XXX - SG_ BRAKE_STATUS : 39|3@0+ (1,0) [0|255] "" XXX - SG_ STATE : 36|3@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X003 : 40|1@0+ (1,0) [0|1] "" XXX - SG_ PRECOLLISION_ACTIVE : 41|1@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 55|8@0+ (1,0) [0|255] "" XXX - -BO_ 740 STEERING_LKA: 5 XXX - SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX - SG_ STEER_REQUEST : 0|1@0+ (1,0) [0|1] "" XXX - SG_ COUNTER : 6|6@0+ (1,0) [0|63] "" XXX - SG_ SET_ME_1 : 7|1@0+ (1,0) [0|1] "" XXX - SG_ STEER_TORQUE_CMD : 15|16@0- (1,0) [0|65535] "" XXX - SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX - -BO_ 742 LEAD_INFO: 8 DSU - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" HCU - SG_ LEAD_REL_SPEED : 23|12@0- (0.025,0) [-100|100] "m/s" HCU - SG_ LEAD_LONG_DIST : 7|13@0+ (0.05,0) [0|300] "m" HCU - -BO_ 835 ACC_CONTROL: 8 DSU - SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU - SG_ ACC_MALFUNCTION : 18|1@0+ (1,0) [0|0] "" XXX - SG_ ACC_CUT_IN : 25|1@0+ (1,0) [0|1] "" XXX - SG_ ALLOW_LONG_PRESS : 17|2@0+ (1,0) [0|2] "" XXX - SG_ ACC_TYPE : 23|2@0+ (1,0) [0|3] "" HCU - SG_ DISTANCE : 20|1@0+ (1,0) [0|1] "" XXX - SG_ MINI_CAR : 21|1@0+ (1,0) [0|1] "" XXX - SG_ PERMIT_BRAKING : 30|1@0+ (1,0) [0|1] "" HCU - SG_ RELEASE_STANDSTILL : 31|1@0+ (1,0) [0|1] "" HCU - SG_ CANCEL_REQ : 24|1@0+ (1,0) [0|1] "" HCU - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - SG_ ACCEL_CMD_ALT : 47|8@0- (0.05,0) [0|0] "m/s^2" XXX - SG_ RADAR_DIRTY : 19|1@0+ (1,0) [0|1] "" XXX - -BO_ 836 PRE_COLLISION_2: 8 DSU - SG_ CHECKSUM : 63|8@0+ (1,0) [0|0] "" XXX - -BO_ 869 DSU_CRUISE : 7 DSU - SG_ RES_BTN : 3|1@0+ (1,0) [0|0] "" XXX - SG_ SET_BTN : 2|1@0+ (1,0) [0|0] "" XXX - SG_ CANCEL_BTN : 1|1@0+ (1,0) [0|0] "" XXX - SG_ MAIN_ON : 0|1@0+ (1,0) [0|0] "" XXX - SG_ SET_SPEED : 15|8@0+ (1,0) [0|0] "km/h" XXX - SG_ CRUISE_REQUEST : 31|8@0+ (100,-12800) [0|0] "N" XXX - SG_ LEAD_DISTANCE : 39|8@0+ (1,0) [0|0] "m" XXX - -BO_ 921 PCM_CRUISE_SM: 8 XXX - SG_ MAIN_ON : 4|1@0+ (1,0) [0|1] "" XXX - SG_ CRUISE_CONTROL_STATE : 11|4@0+ (1,0) [0|15] "" XXX - SG_ DISTANCE_LINES : 14|2@0+ (1,0) [0|3] "" XXX - SG_ UI_SET_SPEED : 31|8@0+ (1,0) [0|255] "" XXX - -BO_ 951 ESP_CONTROL: 8 ESP - SG_ TC_DISABLED : 13|1@0+ (1,0) [0|1] "" XXX - SG_ VSC_DISABLED : 12|2@0+ (1,0) [0|1] "" XXX - SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" XXX - SG_ BRAKE_HOLD_ENABLED : 33|1@1+ (1,0) [0|1] "" XXX - SG_ BRAKE_HOLD_ACTIVE : 36|1@0+ (1,0) [0|1] "" XXX - -BO_ 1020 SOLAR_SENSOR: 8 XXX - SG_ LUX_SENSOR : 55|13@0+ (1,0) [0|0] "" XXX - -BO_ 1041 ACC_HUD: 8 DSU - SG_ PCS_INDICATOR : 7|2@0+ (1,0) [0|3] "" XXX - SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X20 : 15|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X10 : 39|8@0+ (1,0) [0|1] "" XXX - SG_ PCS_OFF : 40|1@0+ (1,0) [0|0] "" XXX - SG_ PCS_SENSITIVITY : 55|8@0+ (1,0) [0|1] "" XXX - -BO_ 1042 LKAS_HUD: 8 XXX - SG_ BARRIERS : 1|2@0+ (1,0) [0|3] "" XXX - SG_ RIGHT_LINE : 3|2@0+ (1,0) [0|3] "" XXX - SG_ LEFT_LINE : 5|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X01 : 7|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X01_2 : 11|2@0+ (1,0) [0|3] "" XXX - SG_ LDA_ALERT : 9|2@0+ (1,0) [0|3] "" XXX - SG_ TWO_BEEPS : 12|1@0+ (1,0) [0|1] "" XXX - SG_ ADJUSTING_CAMERA : 13|1@0+ (1,0) [0|1] "" XXX - SG_ LDA_MALFUNCTION : 15|1@0+ (1,0) [0|1] "" XXX - SG_ REPEATED_BEEPS : 32|1@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X0C : 23|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X2C : 47|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X38 : 55|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X02 : 63|8@0+ (1,0) [0|1] "" XXX - -BO_ 1043 TIME : 8 CGW - SG_ YEAR : 7|8@0+ (1,0) [0|0] "year" XXX - SG_ MONTH : 15|8@0+ (1,0) [0|0] "month" XXX - SG_ DAY : 23|8@0+ (1,0) [0|0] "day" XXX - SG_ HOUR : 31|8@0+ (1,0) [0|0] "hour" XXX - SG_ MINUTE : 39|8@0+ (1,0) [0|0] "minute" XXX - SG_ GMT_DIFF : 55|1@0+ (1,0) [0|0] "" XXX - SG_ GMTDIFF_HOURS : 54|4@0+ (1,0) [0|0] "hours" XXX - SG_ GMTDIFF_MINUTES : 50|6@0+ (1,0) [0|0] "minutes" XXX - SG_ SUMMER : 60|1@0+ (1,0) [0|0] "" XXX - -BO_ 1408 VIN_PART_1: 8 CGW - SG_ VIN_1 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_2 : 15|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_3 : 23|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_4 : 31|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_5 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_6 : 47|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_7 : 55|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_8 : 63|8@0+ (1,0) [0|0] "" XXX - -BO_ 1409 VIN_PART_2: 8 CGW - SG_ VIN_9 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_10 : 15|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_11 : 23|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_12 : 31|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_13 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_14 : 47|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_15 : 55|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_16 : 63|8@0+ (1,0) [0|0] "" XXX - -BO_ 1410 VIN_PART_3: 8 CGW - SG_ VIN_17 : 7|8@0+ (1,0) [0|0] "" XXX - -BO_ 1553 UI_SETTING: 8 XXX - SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX - SG_ ODOMETER : 43|20@0+ (1,0) [0|1048575] "" XXX - -BO_ 1556 STEERING_LEVERS: 8 XXX - SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX - SG_ HAZARD_LIGHT : 27|1@0+ (1,0) [0|1] "" XXX - -BO_ 1568 SEATS_DOORS: 8 XXX - SG_ METER_DIMMED : 38|1@0+ (1,0) [0|1] "" XXX - SG_ PARKING_BRAKE : 60|1@0+ (1,0) [0|1] "" XXX - SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_RR : 43|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_FR : 44|1@0+ (1,0) [0|1] "" XXX - -BO_ 1570 LIGHT_STALK: 8 SCM - SG_ AUTO_HIGH_BEAM : 37|1@0+ (1,0) [0|1] "" XXX - SG_ FRONT_FOG : 27|1@0+ (1,0) [0|1] "" XXX - SG_ PARKING_LIGHT : 28|1@0+ (1,0) [0|1] "" XXX - SG_ LOW_BEAM : 29|1@0+ (1,0) [0|1] "" XXX - SG_ HIGH_BEAM : 30|1@0+ (1,0) [0|1] "" XXX - SG_ DAYTIME_RUNNING_LIGHT : 31|1@0+ (1,0) [0|1] "" XXX - -BO_ 1161 RSA1: 8 FCM - SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY1 : 12|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT1 : 9|2@0+ (1,0) [0|0] "" XXX - SG_ SPDVAL1 : 23|8@0+ (1,0) [0|0] "kph" XXX - SG_ SPLSGN1 : 31|4@0+ (1,0) [0|0] "" XXX - SG_ SPLSGN2 : 27|4@0+ (1,0) [0|0] "" XXX - SG_ TSGN2 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY2 : 44|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT2 : 41|2@0+ (1,0) [0|0] "" XXX - SG_ SPDVAL2 : 55|8@0+ (1,0) [0|0] "" XXX - SG_ BZRRQ_P : 63|2@0+ (1,0) [0|0] "" XXX - SG_ BZRRQ_A : 61|2@0+ (1,0) [0|0] "" XXX - SG_ SYNCID1 : 59|4@0+ (1,0) [0|0] "" XXX - -BO_ 1162 RSA2: 8 FCM - SG_ TSGN3 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY3 : 12|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT3 : 9|2@0+ (1,0) [0|0] "" XXX - SG_ SPLSGN3 : 31|4@0+ (1,0) [0|0] "" XXX - SG_ SPLSGN4 : 27|4@0+ (1,0) [0|0] "" XXX - SG_ TSGN4 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY4 : 44|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT4 : 41|2@0+ (1,0) [0|0] "" XXX - SG_ DPSGNREQ : 54|1@0+ (1,0) [0|0] "" XXX - SG_ SGNNUMP : 53|3@0+ (1,0) [0|0] "" XXX - SG_ SGNNUMA : 50|3@0+ (1,0) [0|0] "" XXX - SG_ SPDUNT : 63|2@0+ (1,0) [0|0] "" XXX - SG_ TSRWMSG : 61|2@0+ (1,0) [0|0] "" XXX - SG_ SYNCID2 : 59|4@0+ (1,0) [0|0] "" XXX - -BO_ 1163 RSA3: 8 FCM - SG_ TSREQPD : 7|1@0+ (1,0) [0|0] "" XXX - SG_ TSRMSW : 6|1@0+ (1,0) [0|0] "" XXX - SG_ OTSGNNTM : 5|2@0+ (1,0) [0|0] "" XXX - SG_ NTLVLSPD : 3|2@0+ (1,0) [0|0] "" XXX - SG_ OVSPNTM : 1|2@0+ (1,0) [0|0] "" XXX - SG_ OVSPVALL : 11|4@0+ (1,-5) [0|0] "" XXX - SG_ OVSPVALM : 19|4@0+ (1,-5) [0|0] "" XXX - SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX - SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" XXX - -BO_ 1571 CENTRAL_GATEWAY_UNIT: 8 CGW - SG_ DOOR_LOCK_FEEDBACK_LIGHT : 15|1@0+ (1,0) [0|0] "" XXX - SG_ KEYFOB_LOCKING_FEEDBACK_LIGHT : 61|1@0+ (1,0) [0|0] "" XXX - SG_ KEYFOB_UNLOCKING_FEEDBACK_LIGHT : 62|1@0+ (1,0) [0|0] "" XXX - -CM_ SG_ 36 ACCEL_Y "unit is tbd"; -CM_ SG_ 36 YAW_RATE "verify"; -CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; -CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; -CM_ SG_ 37 STEER_RATE "factor is tbd"; -CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; -CM_ SG_ 466 CRUISE_STATE "Active state is 8, if standstill is requested will switch to state 11(3 sec timer), after timer is elapsed will switch into state 7(standstill). If plus button was pressed - status 9, minus button pressed - status 10"; -CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isn't perfect"; -CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; -CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; -CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; -CM_ SG_ 608 STEER_OVERRIDE "set when driver torque exceeds a certain value"; -CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; -CM_ SG_ 643 COUNTER "only used on cars that use this msg for cruise control"; -CM_ SG_ 643 BRAKE_STATUS "only used on cars that use this msg for cruise control"; -CM_ SG_ 643 PRECOLLISION_ACTIVE "set 0.5s before any braking"; -CM_ SG_ 835 ACC_TYPE "if 2, car is likely to have a permanent low speed lockout. 1 is ok"; -CM_ SG_ 835 RADAR_DIRTY "Display Clean Radar Sensor message on HUD"; -CM_ SG_ 835 ACC_MALFUNCTION "display ACC fault on dash if set to 1"; -CM_ SG_ 835 ACC_CUT_IN "Display blinking yellow lead if set to 1"; -CM_ SG_ 835 DISTANCE "Display Distance Bars on HUD Permanently"; -CM_ SG_ 835 ALLOW_LONG_PRESS "Enable Toyota's factory set speed increment behaviour, available on both metrics cars and imperial unit cars"; -CM_ SG_ 835 PERMIT_BRAKING "Original ACC has this going high when a car in front is detected. In openpilot and before the PERMIT_BRAKING name, this was 'SET_ME_1' and is hardcoded to be high. Unsure if only informational or has an effect though existing usage in openpilot is to always set it to 1. Originally 'PMTBRKG' in the leaked toyota_2017_ref_pt.dbc file and name expansion speculated to be PerMiT BRaKinG."; -CM_ SG_ 835 ACCEL_CMD_ALT "Copy of main ACCEL_CMD, but across 8 bits instead of 16 bits like ACCEL_CMD. Unsure if only informational or has an effect. Likely informational as existing openpilot sets this to 0 and no loss of functionality observed. Originally 'AT_RAW' in leaked toyota_2017_ref_pt.dbc file."; -CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; -CM_ SG_ 951 BRAKE_LIGHTS_ACC "brake lights when ACC commands decel"; -CM_ SG_ 1041 PCS_INDICATOR "Pre-Collision System Indicator"; -CM_ SG_ 1041 PCS_SENSITIVITY "Pre-Collision System Sensitivity"; -CM_ SG_ 1042 SET_ME_1 "unclear what this is, but it's always 1 in drive traces"; -CM_ SG_ 1042 REPEATED_BEEPS "recommended for fcw and other important alerts"; -CM_ SG_ 1161 SPDVAL1 "Numbers 0-199 is displayed, 200-254 displays circle without number and 255 is for no limit."; -CM_ SG_ 1161 SYNCID1 "counter from 1 to f at 1 Hz"; -CM_ SG_ 1161 SPDVAL2 "conditional speed value 70"; -CM_ SG_ 1162 SGNNUMP "1 if SPDVAL1 is set, otherwise 0"; -CM_ SG_ 1162 SYNCID2 "counter from 1 to f at 1 Hz"; -CM_ SG_ 1163 TSREQPD "always 1"; -CM_ SG_ 1163 TSRMSW "always 1"; -CM_ SG_ 1163 OTSGNNTM "always 3"; -CM_ SG_ 1163 NTLVLSPD "always 3"; -CM_ SG_ 1163 OVSPNTM "always 3"; -CM_ SG_ 1163 OVSPVALL "-5 at start then 2 after 2 seconds"; -CM_ SG_ 1163 OVSPVALM "-5 at start then 5 after 2 seconds"; -CM_ SG_ 1163 OVSPVALH "-5 at start then 10 after 2 seconds"; -CM_ SG_ 1163 TSRSPU "always 1"; -CM_ SG_ 1553 ODOMETER "Unit is dependent upon units signal"; - -VAL_ 466 CRUISE_STATE 11 "timer_3sec" 10 "adaptive click down" 9 "adaptive click up" 8 "adaptive engaged" 7 "standstill" 6 "non-adaptive click up" 5 "non-adaptive click down" 4 "non-adaptive hold down" 3 "non-adaptive hold up" 2 "non-adaptive being engaged" 1 "non-adaptive engaged" 0 "off"; -VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok"; -VAL_ 614 STATE 3 "enabled" 1 "disabled"; -VAL_ 614 DIRECTION_CMD 3 "right" 2 "center" 1 "left"; -VAL_ 643 STATE 0 "normal" 1 "adaptive_cruise_control" 3 "emergency_braking"; -VAL_ 835 ACC_TYPE 2 "permanent low speed lockout" 1 "ok"; -VAL_ 835 ACC_MALFUNCTION 1 "faulted" 0 "ok"; -VAL_ 835 ACC_CUT_IN 1 "CUT-IN Detected" 0 "clear"; -VAL_ 835 ALLOW_LONG_PRESS 2 "set speed increase by 5 speed units regardless" 1 "set speed increase by 1 speed unit on short press, 5 speed units on long press"; -VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted"; -VAL_ 1041 PCS_INDICATOR 2 "PCS Faulted" 1 "PCS Turned Off By User" 0 "PCS Enabled"; -VAL_ 1041 PCS_SENSITIVITY 64 "high sensitivity" 128 "mid sensitivity" 192 "low sensitivity" 0 "off"; -VAL_ 1042 LDA_ALERT 3 "hold with continuous beep" 2 "LDA unavailable" 1 "hold" 0 "none"; -VAL_ 1042 BARRIERS 3 "both" 2 "right" 1 "left" 0 "none"; -VAL_ 1042 RIGHT_LINE 3 "orange" 2 "faded" 1 "solid" 0 "none"; -VAL_ 1042 LEFT_LINE 3 "orange" 2 "faded" 1 "solid" 0 "none"; -VAL_ 1553 UNITS 1 "km" 2 "miles"; -VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left"; -VAL_ 1161 TSGN1 1 "speed sign" 0 "none"; -VAL_ 1161 TSGN2 1 "speed sign" 0 "none"; -VAL_ 1161 SPLSGN2 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none"; -VAL_ 1162 TSGN3 0 "none" 1 "speed sign" 2 "0 unlimited" 7 "unlimited" 16 "highway" 17 "no highway" 18 "motorway" 19 "no motorway" 20 "in city" 21 "outside city" 22 "pedestrian area" 23 "no pedestrian area" 65 "no overtaking left" 66 "no overtaking right" 67 "overtaking allowed again" 81 "no right turn" 97 "stop" 105 "yield" 113 "stop" 114 "yield us" 129 "no entry" 138 "no entry tss2" 145 "do not enter"; -VAL_ 1162 SPLSGN3 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none"; - - - - -CM_ "Imported file _comma.dbc starts here"; -BO_ 359 STEERING_IPAS_COMMA: 8 IPAS - SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX - SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX - SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX - SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant"; - - BO_ 512 GAS_COMMAND: 6 EON - SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR - SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR - SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR - - BO_ 513 GAS_SENSOR: 6 INTERCEPTOR - SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON - SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON - SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON - - VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; - -BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX - SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX - -CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss"; - -BO_ 767 SDSU: 8 XXX - SG_ FD_BUTTON : 7|1@0+ (1,0) [0|1] "" XXX - -CM_ "BO_ SDSU: The sDSU is a modified DSU for use in TSS1 Toyotas. Learn more: https://github.com/wocsor/panda/tree/smart_dsu"; - -CM_ SG_ 767 FD_BUTTON "The follow distance button signal as forwarded by the sdsu"; - -CM_ "lexus_rx_350_2016_pt.dbc starts here"; - - - -BO_ 550 BRAKE_MODULE: 8 XXX - SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|511] "" XXX - SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|511] "" XXX - SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|1] "" XXX - -BO_ 608 STEER_TORQUE_SENSOR: 8 XXX - SG_ STEER_TORQUE_EPS : 47|16@0- (0.73,0) [-20000|20000] "" XXX - SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX - SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - SG_ STEER_ANGLE : 31|16@0- (0.0573,0) [-500|500] "" XXX - -BO_ 610 EPS_STATUS: 5 EPS - SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX - SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX - SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX - -BO_ 956 GEAR_PACKET: 8 XXX - SG_ SPORT_ON : 2|1@0+ (1,0) [0|1] "" XXX - SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX - SG_ ECON_ON : 40|1@0+ (1,0) [0|1] "" XXX - -BO_ 705 GAS_PEDAL: 8 XXX - SG_ GAS_PEDAL : 55|8@0+ (1,0) [0|255] "" XXX - - -CM_ SG_ 550 BRAKE_PRESSURE "seems prop to pedal force"; -CM_ SG_ 550 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; -CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; -VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled" ; -VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby" ; -VAL_ 956 SPORT_ON 0 "off" 1 "on" ; -VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P" ; -VAL_ 956 ECON_ON 0 "off" 1 "on" ; diff --git a/opendbc/lexus_rx_hybrid_2017_pt_generated.dbc b/opendbc/lexus_rx_hybrid_2017_pt_generated.dbc deleted file mode 100644 index fd9f217f2..000000000 --- a/opendbc/lexus_rx_hybrid_2017_pt_generated.dbc +++ /dev/null @@ -1,454 +0,0 @@ -CM_ "AUTOGENERATED FILE, DO NOT EDIT"; - - -CM_ "Imported file _toyota_2017.dbc starts here"; -VERSION "" - - -NS_ : - NS_DESC_ - CM_ - BA_DEF_ - BA_ - VAL_ - CAT_DEF_ - CAT_ - FILTER - BA_DEF_DEF_ - EV_DATA_ - ENVVAR_DATA_ - SGTYPE_ - SGTYPE_VAL_ - BA_DEF_SGTYPE_ - BA_SGTYPE_ - SIG_TYPE_REF_ - VAL_TABLE_ - SIG_GROUP_ - SIG_VALTYPE_ - SIGTYPE_VALTYPE_ - BO_TX_BU_ - BA_DEF_REL_ - BA_REL_ - BA_DEF_DEF_REL_ - BU_SG_REL_ - BU_EV_REL_ - BU_BO_REL_ - SG_MUL_VAL_ - -BS_: - -BU_: XXX DSU HCU EPS IPAS CGW - -BO_ 36 KINEMATICS: 8 XXX - SG_ ACCEL_Y : 33|10@0+ (0.03589,-18.375) [0|65535] "m/s^2" XXX - SG_ YAW_RATE : 1|10@0+ (0.244,-125) [0|65535] "deg/sec" XXX - SG_ STEERING_TORQUE : 17|10@0+ (1,-512) [0|65535] "" XXX - -BO_ 37 STEER_ANGLE_SENSOR: 8 XXX - SG_ STEER_ANGLE : 3|12@0- (1.5,0) [-500|500] "deg" XXX - SG_ STEER_FRACTION : 39|4@0- (0.1,0) [-0.7|0.7] "deg" XXX - SG_ STEER_RATE : 35|12@0- (1,0) [-2000|2000] "deg/s" XXX - -BO_ 166 BRAKE: 8 XXX - SG_ BRAKE_AMOUNT : 7|8@0+ (1,0) [0|255] "" XXX - SG_ BRAKE_PEDAL : 23|8@0+ (1,0) [0|255] "" XXX - -BO_ 170 WHEEL_SPEEDS: 8 XXX - SG_ WHEEL_SPEED_FR : 7|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_FL : 23|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_RR : 39|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_RL : 55|16@0+ (0.01,-67.67) [0|250] "kph" XXX - -BO_ 180 SPEED: 8 XXX - SG_ ENCODER : 39|8@0+ (1,0) [0|255] "" XXX - SG_ SPEED : 47|16@0+ (0.01,0) [0|250] "kph" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 353 DSU_SPEED: 7 XXX - SG_ FORWARD_SPEED : 15|16@0- (0.00390625,-30) [0|255] "kph" XXX - -BO_ 452 ENGINE_RPM: 8 CGW - SG_ RPM : 7|16@0- (0.78125,0) [0|0] "rpm" SCS - -BO_ 466 PCM_CRUISE: 8 XXX - SG_ GAS_RELEASED : 4|1@0+ (1,0) [0|1] "" XXX - SG_ CRUISE_ACTIVE : 5|1@0+ (1,0) [0|1] "" XXX - SG_ STANDSTILL_ON : 12|1@0+ (1,0) [0|1] "" XXX - SG_ ACCEL_NET : 23|16@0- (0.001,0) [-20|20] "m/s2" XXX - SG_ CRUISE_STATE : 55|4@0+ (1,0) [0|15] "" XXX - SG_ CANCEL_REQ : 49|1@1+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 467 PCM_CRUISE_2: 8 XXX - SG_ MAIN_ON : 15|1@0+ (1,0) [0|1] "" XXX - SG_ LOW_SPEED_LOCKOUT : 14|2@0+ (1,0) [0|3] "kph" XXX - SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "kph" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 552 ACCELEROMETER: 8 XXX - SG_ ACCEL_Z : 22|15@0- (1,0) [0|32767] "" XXX - SG_ ACCEL_X : 6|15@0- (0.001,0) [-20|20] "m/s2" XXX - -BO_ 560 BRAKE_MODULE2: 7 XXX - SG_ BRAKE_PRESSED : 26|1@0+ (1,0) [0|1] "" XXX - -BO_ 614 STEERING_IPAS: 8 IPAS - SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX - SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX - SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX - SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 643 PRE_COLLISION: 7 DSU - SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 15|8@0+ (1,0) [0|255] "" XXX - SG_ FORCE : 23|16@0- (2,0) [0|255] "N" XXX - SG_ SET_ME_X002 : 33|8@0+ (1,0) [0|3] "" XXX - SG_ BRAKE_STATUS : 39|3@0+ (1,0) [0|255] "" XXX - SG_ STATE : 36|3@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X003 : 40|1@0+ (1,0) [0|1] "" XXX - SG_ PRECOLLISION_ACTIVE : 41|1@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 55|8@0+ (1,0) [0|255] "" XXX - -BO_ 740 STEERING_LKA: 5 XXX - SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX - SG_ STEER_REQUEST : 0|1@0+ (1,0) [0|1] "" XXX - SG_ COUNTER : 6|6@0+ (1,0) [0|63] "" XXX - SG_ SET_ME_1 : 7|1@0+ (1,0) [0|1] "" XXX - SG_ STEER_TORQUE_CMD : 15|16@0- (1,0) [0|65535] "" XXX - SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX - -BO_ 742 LEAD_INFO: 8 DSU - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" HCU - SG_ LEAD_REL_SPEED : 23|12@0- (0.025,0) [-100|100] "m/s" HCU - SG_ LEAD_LONG_DIST : 7|13@0+ (0.05,0) [0|300] "m" HCU - -BO_ 835 ACC_CONTROL: 8 DSU - SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU - SG_ ACC_MALFUNCTION : 18|1@0+ (1,0) [0|0] "" XXX - SG_ ACC_CUT_IN : 25|1@0+ (1,0) [0|1] "" XXX - SG_ ALLOW_LONG_PRESS : 17|2@0+ (1,0) [0|2] "" XXX - SG_ ACC_TYPE : 23|2@0+ (1,0) [0|3] "" HCU - SG_ DISTANCE : 20|1@0+ (1,0) [0|1] "" XXX - SG_ MINI_CAR : 21|1@0+ (1,0) [0|1] "" XXX - SG_ PERMIT_BRAKING : 30|1@0+ (1,0) [0|1] "" HCU - SG_ RELEASE_STANDSTILL : 31|1@0+ (1,0) [0|1] "" HCU - SG_ CANCEL_REQ : 24|1@0+ (1,0) [0|1] "" HCU - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - SG_ ACCEL_CMD_ALT : 47|8@0- (0.05,0) [0|0] "m/s^2" XXX - SG_ RADAR_DIRTY : 19|1@0+ (1,0) [0|1] "" XXX - -BO_ 836 PRE_COLLISION_2: 8 DSU - SG_ CHECKSUM : 63|8@0+ (1,0) [0|0] "" XXX - -BO_ 869 DSU_CRUISE : 7 DSU - SG_ RES_BTN : 3|1@0+ (1,0) [0|0] "" XXX - SG_ SET_BTN : 2|1@0+ (1,0) [0|0] "" XXX - SG_ CANCEL_BTN : 1|1@0+ (1,0) [0|0] "" XXX - SG_ MAIN_ON : 0|1@0+ (1,0) [0|0] "" XXX - SG_ SET_SPEED : 15|8@0+ (1,0) [0|0] "km/h" XXX - SG_ CRUISE_REQUEST : 31|8@0+ (100,-12800) [0|0] "N" XXX - SG_ LEAD_DISTANCE : 39|8@0+ (1,0) [0|0] "m" XXX - -BO_ 921 PCM_CRUISE_SM: 8 XXX - SG_ MAIN_ON : 4|1@0+ (1,0) [0|1] "" XXX - SG_ CRUISE_CONTROL_STATE : 11|4@0+ (1,0) [0|15] "" XXX - SG_ DISTANCE_LINES : 14|2@0+ (1,0) [0|3] "" XXX - SG_ UI_SET_SPEED : 31|8@0+ (1,0) [0|255] "" XXX - -BO_ 951 ESP_CONTROL: 8 ESP - SG_ TC_DISABLED : 13|1@0+ (1,0) [0|1] "" XXX - SG_ VSC_DISABLED : 12|2@0+ (1,0) [0|1] "" XXX - SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" XXX - SG_ BRAKE_HOLD_ENABLED : 33|1@1+ (1,0) [0|1] "" XXX - SG_ BRAKE_HOLD_ACTIVE : 36|1@0+ (1,0) [0|1] "" XXX - -BO_ 1020 SOLAR_SENSOR: 8 XXX - SG_ LUX_SENSOR : 55|13@0+ (1,0) [0|0] "" XXX - -BO_ 1041 ACC_HUD: 8 DSU - SG_ PCS_INDICATOR : 7|2@0+ (1,0) [0|3] "" XXX - SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X20 : 15|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X10 : 39|8@0+ (1,0) [0|1] "" XXX - SG_ PCS_OFF : 40|1@0+ (1,0) [0|0] "" XXX - SG_ PCS_SENSITIVITY : 55|8@0+ (1,0) [0|1] "" XXX - -BO_ 1042 LKAS_HUD: 8 XXX - SG_ BARRIERS : 1|2@0+ (1,0) [0|3] "" XXX - SG_ RIGHT_LINE : 3|2@0+ (1,0) [0|3] "" XXX - SG_ LEFT_LINE : 5|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X01 : 7|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X01_2 : 11|2@0+ (1,0) [0|3] "" XXX - SG_ LDA_ALERT : 9|2@0+ (1,0) [0|3] "" XXX - SG_ TWO_BEEPS : 12|1@0+ (1,0) [0|1] "" XXX - SG_ ADJUSTING_CAMERA : 13|1@0+ (1,0) [0|1] "" XXX - SG_ LDA_MALFUNCTION : 15|1@0+ (1,0) [0|1] "" XXX - SG_ REPEATED_BEEPS : 32|1@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X0C : 23|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X2C : 47|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X38 : 55|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X02 : 63|8@0+ (1,0) [0|1] "" XXX - -BO_ 1043 TIME : 8 CGW - SG_ YEAR : 7|8@0+ (1,0) [0|0] "year" XXX - SG_ MONTH : 15|8@0+ (1,0) [0|0] "month" XXX - SG_ DAY : 23|8@0+ (1,0) [0|0] "day" XXX - SG_ HOUR : 31|8@0+ (1,0) [0|0] "hour" XXX - SG_ MINUTE : 39|8@0+ (1,0) [0|0] "minute" XXX - SG_ GMT_DIFF : 55|1@0+ (1,0) [0|0] "" XXX - SG_ GMTDIFF_HOURS : 54|4@0+ (1,0) [0|0] "hours" XXX - SG_ GMTDIFF_MINUTES : 50|6@0+ (1,0) [0|0] "minutes" XXX - SG_ SUMMER : 60|1@0+ (1,0) [0|0] "" XXX - -BO_ 1408 VIN_PART_1: 8 CGW - SG_ VIN_1 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_2 : 15|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_3 : 23|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_4 : 31|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_5 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_6 : 47|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_7 : 55|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_8 : 63|8@0+ (1,0) [0|0] "" XXX - -BO_ 1409 VIN_PART_2: 8 CGW - SG_ VIN_9 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_10 : 15|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_11 : 23|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_12 : 31|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_13 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_14 : 47|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_15 : 55|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_16 : 63|8@0+ (1,0) [0|0] "" XXX - -BO_ 1410 VIN_PART_3: 8 CGW - SG_ VIN_17 : 7|8@0+ (1,0) [0|0] "" XXX - -BO_ 1553 UI_SETTING: 8 XXX - SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX - SG_ ODOMETER : 43|20@0+ (1,0) [0|1048575] "" XXX - -BO_ 1556 STEERING_LEVERS: 8 XXX - SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX - SG_ HAZARD_LIGHT : 27|1@0+ (1,0) [0|1] "" XXX - -BO_ 1568 SEATS_DOORS: 8 XXX - SG_ METER_DIMMED : 38|1@0+ (1,0) [0|1] "" XXX - SG_ PARKING_BRAKE : 60|1@0+ (1,0) [0|1] "" XXX - SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_RR : 43|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_FR : 44|1@0+ (1,0) [0|1] "" XXX - -BO_ 1570 LIGHT_STALK: 8 SCM - SG_ AUTO_HIGH_BEAM : 37|1@0+ (1,0) [0|1] "" XXX - SG_ FRONT_FOG : 27|1@0+ (1,0) [0|1] "" XXX - SG_ PARKING_LIGHT : 28|1@0+ (1,0) [0|1] "" XXX - SG_ LOW_BEAM : 29|1@0+ (1,0) [0|1] "" XXX - SG_ HIGH_BEAM : 30|1@0+ (1,0) [0|1] "" XXX - SG_ DAYTIME_RUNNING_LIGHT : 31|1@0+ (1,0) [0|1] "" XXX - -BO_ 1161 RSA1: 8 FCM - SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY1 : 12|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT1 : 9|2@0+ (1,0) [0|0] "" XXX - SG_ SPDVAL1 : 23|8@0+ (1,0) [0|0] "kph" XXX - SG_ SPLSGN1 : 31|4@0+ (1,0) [0|0] "" XXX - SG_ SPLSGN2 : 27|4@0+ (1,0) [0|0] "" XXX - SG_ TSGN2 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY2 : 44|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT2 : 41|2@0+ (1,0) [0|0] "" XXX - SG_ SPDVAL2 : 55|8@0+ (1,0) [0|0] "" XXX - SG_ BZRRQ_P : 63|2@0+ (1,0) [0|0] "" XXX - SG_ BZRRQ_A : 61|2@0+ (1,0) [0|0] "" XXX - SG_ SYNCID1 : 59|4@0+ (1,0) [0|0] "" XXX - -BO_ 1162 RSA2: 8 FCM - SG_ TSGN3 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY3 : 12|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT3 : 9|2@0+ (1,0) [0|0] "" XXX - SG_ SPLSGN3 : 31|4@0+ (1,0) [0|0] "" XXX - SG_ SPLSGN4 : 27|4@0+ (1,0) [0|0] "" XXX - SG_ TSGN4 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY4 : 44|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT4 : 41|2@0+ (1,0) [0|0] "" XXX - SG_ DPSGNREQ : 54|1@0+ (1,0) [0|0] "" XXX - SG_ SGNNUMP : 53|3@0+ (1,0) [0|0] "" XXX - SG_ SGNNUMA : 50|3@0+ (1,0) [0|0] "" XXX - SG_ SPDUNT : 63|2@0+ (1,0) [0|0] "" XXX - SG_ TSRWMSG : 61|2@0+ (1,0) [0|0] "" XXX - SG_ SYNCID2 : 59|4@0+ (1,0) [0|0] "" XXX - -BO_ 1163 RSA3: 8 FCM - SG_ TSREQPD : 7|1@0+ (1,0) [0|0] "" XXX - SG_ TSRMSW : 6|1@0+ (1,0) [0|0] "" XXX - SG_ OTSGNNTM : 5|2@0+ (1,0) [0|0] "" XXX - SG_ NTLVLSPD : 3|2@0+ (1,0) [0|0] "" XXX - SG_ OVSPNTM : 1|2@0+ (1,0) [0|0] "" XXX - SG_ OVSPVALL : 11|4@0+ (1,-5) [0|0] "" XXX - SG_ OVSPVALM : 19|4@0+ (1,-5) [0|0] "" XXX - SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX - SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" XXX - -BO_ 1571 CENTRAL_GATEWAY_UNIT: 8 CGW - SG_ DOOR_LOCK_FEEDBACK_LIGHT : 15|1@0+ (1,0) [0|0] "" XXX - SG_ KEYFOB_LOCKING_FEEDBACK_LIGHT : 61|1@0+ (1,0) [0|0] "" XXX - SG_ KEYFOB_UNLOCKING_FEEDBACK_LIGHT : 62|1@0+ (1,0) [0|0] "" XXX - -CM_ SG_ 36 ACCEL_Y "unit is tbd"; -CM_ SG_ 36 YAW_RATE "verify"; -CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; -CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; -CM_ SG_ 37 STEER_RATE "factor is tbd"; -CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; -CM_ SG_ 466 CRUISE_STATE "Active state is 8, if standstill is requested will switch to state 11(3 sec timer), after timer is elapsed will switch into state 7(standstill). If plus button was pressed - status 9, minus button pressed - status 10"; -CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isn't perfect"; -CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; -CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; -CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; -CM_ SG_ 608 STEER_OVERRIDE "set when driver torque exceeds a certain value"; -CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; -CM_ SG_ 643 COUNTER "only used on cars that use this msg for cruise control"; -CM_ SG_ 643 BRAKE_STATUS "only used on cars that use this msg for cruise control"; -CM_ SG_ 643 PRECOLLISION_ACTIVE "set 0.5s before any braking"; -CM_ SG_ 835 ACC_TYPE "if 2, car is likely to have a permanent low speed lockout. 1 is ok"; -CM_ SG_ 835 RADAR_DIRTY "Display Clean Radar Sensor message on HUD"; -CM_ SG_ 835 ACC_MALFUNCTION "display ACC fault on dash if set to 1"; -CM_ SG_ 835 ACC_CUT_IN "Display blinking yellow lead if set to 1"; -CM_ SG_ 835 DISTANCE "Display Distance Bars on HUD Permanently"; -CM_ SG_ 835 ALLOW_LONG_PRESS "Enable Toyota's factory set speed increment behaviour, available on both metrics cars and imperial unit cars"; -CM_ SG_ 835 PERMIT_BRAKING "Original ACC has this going high when a car in front is detected. In openpilot and before the PERMIT_BRAKING name, this was 'SET_ME_1' and is hardcoded to be high. Unsure if only informational or has an effect though existing usage in openpilot is to always set it to 1. Originally 'PMTBRKG' in the leaked toyota_2017_ref_pt.dbc file and name expansion speculated to be PerMiT BRaKinG."; -CM_ SG_ 835 ACCEL_CMD_ALT "Copy of main ACCEL_CMD, but across 8 bits instead of 16 bits like ACCEL_CMD. Unsure if only informational or has an effect. Likely informational as existing openpilot sets this to 0 and no loss of functionality observed. Originally 'AT_RAW' in leaked toyota_2017_ref_pt.dbc file."; -CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; -CM_ SG_ 951 BRAKE_LIGHTS_ACC "brake lights when ACC commands decel"; -CM_ SG_ 1041 PCS_INDICATOR "Pre-Collision System Indicator"; -CM_ SG_ 1041 PCS_SENSITIVITY "Pre-Collision System Sensitivity"; -CM_ SG_ 1042 SET_ME_1 "unclear what this is, but it's always 1 in drive traces"; -CM_ SG_ 1042 REPEATED_BEEPS "recommended for fcw and other important alerts"; -CM_ SG_ 1161 SPDVAL1 "Numbers 0-199 is displayed, 200-254 displays circle without number and 255 is for no limit."; -CM_ SG_ 1161 SYNCID1 "counter from 1 to f at 1 Hz"; -CM_ SG_ 1161 SPDVAL2 "conditional speed value 70"; -CM_ SG_ 1162 SGNNUMP "1 if SPDVAL1 is set, otherwise 0"; -CM_ SG_ 1162 SYNCID2 "counter from 1 to f at 1 Hz"; -CM_ SG_ 1163 TSREQPD "always 1"; -CM_ SG_ 1163 TSRMSW "always 1"; -CM_ SG_ 1163 OTSGNNTM "always 3"; -CM_ SG_ 1163 NTLVLSPD "always 3"; -CM_ SG_ 1163 OVSPNTM "always 3"; -CM_ SG_ 1163 OVSPVALL "-5 at start then 2 after 2 seconds"; -CM_ SG_ 1163 OVSPVALM "-5 at start then 5 after 2 seconds"; -CM_ SG_ 1163 OVSPVALH "-5 at start then 10 after 2 seconds"; -CM_ SG_ 1163 TSRSPU "always 1"; -CM_ SG_ 1553 ODOMETER "Unit is dependent upon units signal"; - -VAL_ 466 CRUISE_STATE 11 "timer_3sec" 10 "adaptive click down" 9 "adaptive click up" 8 "adaptive engaged" 7 "standstill" 6 "non-adaptive click up" 5 "non-adaptive click down" 4 "non-adaptive hold down" 3 "non-adaptive hold up" 2 "non-adaptive being engaged" 1 "non-adaptive engaged" 0 "off"; -VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok"; -VAL_ 614 STATE 3 "enabled" 1 "disabled"; -VAL_ 614 DIRECTION_CMD 3 "right" 2 "center" 1 "left"; -VAL_ 643 STATE 0 "normal" 1 "adaptive_cruise_control" 3 "emergency_braking"; -VAL_ 835 ACC_TYPE 2 "permanent low speed lockout" 1 "ok"; -VAL_ 835 ACC_MALFUNCTION 1 "faulted" 0 "ok"; -VAL_ 835 ACC_CUT_IN 1 "CUT-IN Detected" 0 "clear"; -VAL_ 835 ALLOW_LONG_PRESS 2 "set speed increase by 5 speed units regardless" 1 "set speed increase by 1 speed unit on short press, 5 speed units on long press"; -VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted"; -VAL_ 1041 PCS_INDICATOR 2 "PCS Faulted" 1 "PCS Turned Off By User" 0 "PCS Enabled"; -VAL_ 1041 PCS_SENSITIVITY 64 "high sensitivity" 128 "mid sensitivity" 192 "low sensitivity" 0 "off"; -VAL_ 1042 LDA_ALERT 3 "hold with continuous beep" 2 "LDA unavailable" 1 "hold" 0 "none"; -VAL_ 1042 BARRIERS 3 "both" 2 "right" 1 "left" 0 "none"; -VAL_ 1042 RIGHT_LINE 3 "orange" 2 "faded" 1 "solid" 0 "none"; -VAL_ 1042 LEFT_LINE 3 "orange" 2 "faded" 1 "solid" 0 "none"; -VAL_ 1553 UNITS 1 "km" 2 "miles"; -VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left"; -VAL_ 1161 TSGN1 1 "speed sign" 0 "none"; -VAL_ 1161 TSGN2 1 "speed sign" 0 "none"; -VAL_ 1161 SPLSGN2 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none"; -VAL_ 1162 TSGN3 0 "none" 1 "speed sign" 2 "0 unlimited" 7 "unlimited" 16 "highway" 17 "no highway" 18 "motorway" 19 "no motorway" 20 "in city" 21 "outside city" 22 "pedestrian area" 23 "no pedestrian area" 65 "no overtaking left" 66 "no overtaking right" 67 "overtaking allowed again" 81 "no right turn" 97 "stop" 105 "yield" 113 "stop" 114 "yield us" 129 "no entry" 138 "no entry tss2" 145 "do not enter"; -VAL_ 1162 SPLSGN3 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none"; - - - - -CM_ "Imported file _comma.dbc starts here"; -BO_ 359 STEERING_IPAS_COMMA: 8 IPAS - SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX - SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX - SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX - SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant"; - - BO_ 512 GAS_COMMAND: 6 EON - SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR - SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR - SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR - - BO_ 513 GAS_SENSOR: 6 INTERCEPTOR - SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON - SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON - SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON - - VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; - -BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX - SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX - -CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss"; - -BO_ 767 SDSU: 8 XXX - SG_ FD_BUTTON : 7|1@0+ (1,0) [0|1] "" XXX - -CM_ "BO_ SDSU: The sDSU is a modified DSU for use in TSS1 Toyotas. Learn more: https://github.com/wocsor/panda/tree/smart_dsu"; - -CM_ SG_ 767 FD_BUTTON "The follow distance button signal as forwarded by the sdsu"; - -CM_ "lexus_rx_hybrid_2017_pt.dbc starts here"; - - - -BO_ 550 BRAKE_MODULE: 8 XXX - SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|511] "" XXX - SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|511] "" XXX - SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|1] "" XXX - -BO_ 581 GAS_PEDAL: 5 XXX - SG_ GAS_PEDAL : 23|8@0+ (0.005,0) [0|1] "" XXX - -BO_ 608 STEER_TORQUE_SENSOR: 8 XXX - SG_ STEER_TORQUE_EPS : 47|16@0- (0.73,0) [-20000|20000] "" XXX - SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX - SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - SG_ STEER_ANGLE : 31|16@0- (0.0573,0) [-500|500] "" XXX - -BO_ 610 EPS_STATUS: 5 EPS - SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX - SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX - SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX - -BO_ 956 GEAR_PACKET: 8 XXX - SG_ SPORT_ON : 2|1@0+ (1,0) [0|1] "" XXX - SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX - SG_ ECON_ON : 40|1@0+ (1,0) [0|1] "" XXX - -CM_ SG_ 550 BRAKE_PRESSURE "seems prop to pedal force"; -CM_ SG_ 550 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; -CM_ SG_ 581 GAS_PEDAL "it seems slightly filtered"; -CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; -VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled"; -VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby"; -VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; -VAL_ 956 SPORT_ON 0 "off" 1 "on"; -VAL_ 956 ECON_ON 0 "off" 1 "on"; diff --git a/opendbc/mazda_2017.dbc b/opendbc/mazda_2017.dbc index fdd6d2824..fbd11162a 100644 --- a/opendbc/mazda_2017.dbc +++ b/opendbc/mazda_2017.dbc @@ -324,7 +324,7 @@ BO_ 1034 MSG_07: 8 XXX SG_ NEW_SIGNAL_8 : 39|8@0+ (1,0) [0|255] "" XXX SG_ NEW_SIGNAL_9 : 31|8@0+ (1,0) [0|255] "" XXX -BO_ 870 NEW_MSG_16: 8 XXX +BO_ 870 RADAR_366_STATIC: 8 XXX SG_ NEW_SIGNAL_1 : 7|8@0+ (1,0) [0|255] "" XXX SG_ NEW_SIGNAL_2 : 15|8@0+ (1,0) [0|255] "" XXX SG_ NEW_SIGNAL_3 : 23|8@0+ (1,0) [0|255] "" XXX @@ -333,14 +333,16 @@ BO_ 870 NEW_MSG_16: 8 XXX SG_ NEW_SIGNAL_6 : 47|8@0+ (1,0) [0|255] "" XXX SG_ NEW_SIGNAL_7 : 55|8@0+ (1,0) [0|255] "" XXX -BO_ 867 NEW_MSG_17: 8 XXX - SG_ NEW_SIGNAL_1 : 31|8@0+ (1,0) [0|255] "" XXX - SG_ NEW_SIGNAL_2 : 23|8@0+ (1,0) [0|255] "" XXX - SG_ NEW_SIGNAL_3 : 15|8@0+ (1,0) [0|255] "" XXX - SG_ NEW_SIGNAL_4 : 7|8@0+ (1,0) [0|255] "" XXX - SG_ NEW_SIGNAL_5 : 39|8@0+ (1,0) [0|255] "" XXX - SG_ NEW_SIGNAL_6 : 47|8@0+ (1,0) [0|255] "" XXX - SG_ CTR : 63|8@0+ (1,0) [0|255] "" XXX +BO_ 867 RADAR_363: 8 XXX + SG_ CTR : 59|4@0+ (1,0) [0|255] "" XXX + SG_ STATIC_4 : 43|16@0+ (1,0) [0|255] "" XXX + SG_ FLIPPY_1 : 31|3@0+ (1,0) [0|7] "" XXX + SG_ FLIPPY_2 : 47|1@0+ (1,0) [0|15] "" XXX + SG_ FLIPPY_4 : 44|1@0+ (1,0) [0|3] "" XXX + SG_ FLIPPY_3 : 46|1@0+ (1,0) [0|3] "" XXX + SG_ CURVE_1 : 7|12@0+ (1,0) [0|255] "" XXX + SG_ CURVE_2 : 11|12@0+ (1,0) [0|255] "" XXX + SG_ CURVE_3 : 28|13@0+ (1,0) [0|255] "" XXX BO_ 130 STEER: 8 XXX SG_ NEW_SIGNAL_5 : 55|8@0+ (1,0) [0|255] "" XXX @@ -361,19 +363,13 @@ BO_ 304 GEAR_RELATED: 8 XXX SG_ NEW_SIGNAL_1 : 55|8@0+ (1,0) [0|255] "" XXX SG_ NEW_SIGNAL_2 : 47|8@0+ (1,0) [0|255] "" XXX -BO_ 865 NEW_MSG_5: 8 XXX - SG_ SPEED_INVERSE : 55|8@0+ (1,0) [0|255] "" XXX - SG_ NEW_SIGNAL_1 : 47|1@0+ (1,0) [0|255] "" XXX - SG_ NEW_SIGNAL_3 : 40|1@0+ (1,0) [0|1] "" XXX - SG_ IS_MOVING : 43|3@0+ (1,0) [0|127] "" XXX - SG_ NEW_SIGNAL_2 : 46|1@0+ (1,0) [0|7] "" XXX - SG_ NEW_SIGNAL_4 : 44|1@0+ (1,0) [0|1] "" XXX - SG_ NEW_SIGNAL_7 : 23|8@0+ (1,0) [0|255] "" XXX - SG_ NEW_SIGNAL_8 : 31|8@0+ (1,0) [0|255] "" XXX - SG_ NEW_SIGNAL_10 : 39|8@0+ (1,0) [0|255] "" XXX - SG_ NEW_SIGNAL_6 : 15|3@0+ (1,0) [0|255] "" XXX - SG_ NEW_SIGNAL_5 : 7|8@0+ (1,0) [0|255] "" XXX +BO_ 865 RADAR_DISTANCE: 8 XXX SG_ CTR : 56|4@1+ (1,0) [0|15] "" XXX + SG_ STATIC : 36|3@0+ (1,0) [0|31] "" XXX + SG_ DISTANCE_RELATED : 33|4@0+ (1,0) [0|3] "" XXX + SG_ SPEED_INVERSE : 43|12@0- (-0.225,0) [0|255] "kph" XXX + SG_ DISTANCE_LEAD : 7|24@0+ (1,0) [0|31] "" XXX + SG_ RELATIVE_VEL_LEAD : 31|11@0- (1,0) [0|255] "" XXX BO_ 836 NEW_MSG_19: 8 XXX SG_ CTR : 48|4@1+ (1,0) [0|15] "" XXX @@ -387,15 +383,16 @@ BO_ 832 SEATBELT: 8 XXX SG_ NEW_SIGNAL_4 : 8|4@1+ (1,0) [0|3] "" XXX SG_ DRIVER_SEATBELT : 27|1@0+ (1,0) [0|1] "" XXX -BO_ 866 NEW_MSG_21: 8 XXX - SG_ NEW_SIGNAL_2 : 7|8@0+ (1,0) [0|131071] "" XXX - SG_ NEW_SIGNAL_1 : 15|8@0+ (1,0) [0|15] "" XXX - SG_ NEW_SIGNAL_3 : 55|8@0+ (1,0) [0|255] "" XXX - SG_ NEW_SIGNAL_4 : 47|8@0+ (1,0) [0|255] "" XXX - SG_ NEW_SIGNAL_5 : 39|8@0+ (1,0) [0|255] "" XXX - SG_ NEW_SIGNAL_6 : 27|4@0+ (1,0) [0|255] "" XXX - SG_ NEW_SIGNAL_7 : 23|8@0+ (1,0) [0|255] "" XXX +BO_ 866 RADAR_TURN: 8 XXX SG_ CTR : 59|4@0+ (1,0) [0|15] "" XXX + SG_ STEER_ANGLE : 43|12@0+ (-1,2048) [0|7] "" XXX + SG_ STATIC_2 : 63|4@0+ (1,0) [0|15] "" XXX + SG_ CURVE_1 : 7|12@0+ (1,0) [0|131071] "" XXX + SG_ CURVE_2 : 11|12@0- (1,0) [0|127] "" XXX + SG_ FLIPPY_1 : 44|1@0+ (1,0) [0|15] "" XXX + SG_ NEW_SIGNAL_4 : 34|3@1+ (1,0) [0|3] "" XXX + SG_ CURVE_3 : 31|11@0- (1,0) [0|63] "" XXX + SG_ NEW_SIGNAL_1 : 33|4@0+ (1,0) [0|3] "" XXX BO_ 158 MSG_05: 8 XXX SG_ NEW_SIGNAL_1 : 23|8@0+ (1,0) [0|15] "" XXX @@ -514,16 +511,25 @@ BO_ 542 NEW_MSG_33: 8 XXX SG_ CTR : 48|4@1+ (1,0) [0|15] "" XXX SG_ CTR2 : 56|4@1+ (1,0) [0|15] "" XXX -BO_ 868 NEW_MSG_34: 8 XXX +BO_ 868 RADAR_364: 8 XXX SG_ CTR : 59|4@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_1 : 7|12@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_2 : 11|12@0- (1,0) [0|15] "" XXX + SG_ NEW_SIGNAL_3 : 27|12@0- (1,0) [0|255] "" XXX + SG_ FLIPPERS_1 : 31|4@0+ (1,0) [0|15] "" XXX + SG_ NEW_SIGNAL_4 : 44|1@1+ (1,0) [0|3] "" XXX + SG_ FLIPPY_1 : 46|1@0+ (1,0) [0|3] "" XXX + SG_ STATIC_1 : 47|1@0+ (1,0) [0|15] "" XXX + SG_ STATIC_2 : 43|16@0+ (1,0) [0|7] "" XXX -BO_ 869 NEW_MSG_35: 8 XXX - SG_ NEW_SIGNAL_1 : 7|4@0+ (1,0) [0|255] "" XXX - SG_ NEW_SIGNAL_3 : 23|16@0+ (1,0) [0|255] "" XXX - SG_ NEW_SIGNAL_2 : 39|16@0+ (1,0) [0|255] "" XXX - SG_ NEW_SIGNAL_4 : 55|2@0+ (1,0) [0|255] "" XXX - SG_ NEW_SIGNAL_5 : 50|4@1+ (1,0) [0|15] "" XXX +BO_ 869 RADAR_365: 8 XXX SG_ CTR : 59|4@0+ (1,0) [0|255] "" XXX + SG_ NEW_SIGNAL_4 : 39|6@0+ (1,0) [0|63] "" XXX + SG_ NEW_SIGNAL_1 : 7|14@0+ (1,0) [0|65535] "" XXX + SG_ RELATED_1 : 9|18@0+ (1,0) [0|3] "" XXX + SG_ RELATED_2 : 33|18@0+ (1,0) [0|15] "" XXX + SG_ STATIC : 61|2@0+ (1,0) [0|3] "" XXX + SG_ NEW_SIGNAL_2 : 63|2@0+ (1,0) [0|15] "" XXX BO_ 1114 NEW_MSG_4: 8 XXX @@ -551,30 +557,33 @@ BO_ 535 CURVE_CTRS: 8 XXX BO_ 540 CRZ_CTRL: 8 XXX SG_ NEW_SIGNAL_6 : 10|1@0+ (1,0) [0|1] "" XXX SG_ NEW_SIGNAL_9 : 31|1@0+ (1,0) [0|255] "" XXX - SG_ NEW_SIGNAL_10 : 30|1@0+ (1,0) [0|1] "" XXX - SG_ ACC_GAS_MAYBE : 23|1@0+ (1,0) [0|31] "" XXX SG_ ACC_GAS_MAYBE2 : 29|1@0+ (1,0) [0|1] "" XXX SG_ HANDS_OFF_STEERING : 48|1@0+ (1,0) [0|1] "" XXX SG_ HANDS_ON_STEER_WARN : 59|4@0+ (1,0) [0|255] "" XXX - SG_ NEW_SIGNAL_1 : 52|1@0+ (1,0) [0|1] "" XXX - SG_ NEW_SIGNAL_2 : 45|3@0+ (1,0) [0|255] "" XXX - SG_ NEW_SIGNAL_8 : 0|1@0+ (1,0) [0|1] "" XXX - SG_ NEW_SIGNAL_3 : 1|1@0+ (1,0) [0|1] "" XXX SG_ CRZ_ACTIVE : 3|1@0+ (1,0) [0|1] "" XXX - SG_ NEW_SIGNAL_4 : 8|1@0+ (1,0) [0|255] "" XXX - SG_ NEW_SIGNAL_5 : 9|1@0+ (1,0) [0|1] "" XXX SG_ CRZ_AVAILABLE : 17|1@0+ (1,0) [0|255] "" XXX SG_ DISTANCE_SETTING : 20|3@0+ (1,0) [0|7] "" XXX + SG_ MSG_1_INV : 1|1@0+ (1,0) [0|1] "" XXX + SG_ MSG_1_COPY : 9|1@0+ (1,0) [0|1] "" XXX + SG_ ACC_GAS_MAYBE : 23|1@0+ (1,0) [0|31] "" XXX + SG_ ACC_ACTIVE_2 : 52|1@0+ (1,0) [0|1] "" XXX + SG_ NEW_SIGNAL_10 : 30|1@0+ (1,0) [0|1] "" XXX + SG_ MSG_1 : 0|1@0+ (1,0) [0|3] "" XXX + SG_ 5_SEC_DISABLE_TIMER : 45|3@0+ (1,0) [0|7] "" XXX + SG_ NEW_SIGNAL_3 : 13|1@0+ (1,0) [0|3] "" XXX + SG_ MSG_1_INV_COPY : 8|1@0+ (1,0) [0|7] "" XXX BO_ 539 CRZ_INFO: 8 XXX - SG_ NEW_SIGNAL_5 : 34|1@0+ (1,0) [0|1] "" XXX - SG_ NEW_SIGNAL_7 : 47|1@0+ (1,0) [0|255] "" XXX SG_ CTR1 : 55|8@0+ (1,0) [0|255] "" XXX - SG_ NEW_SIGNAL_3 : 37|1@0+ (1,0) [0|255] "" XXX SG_ ACC_ACTIVE : 33|1@0+ (1,0) [0|1] "" XXX - SG_ ACCEL_CMD : 31|8@0- (1,0) [0|1] "" XXX SG_ CHKSUM : 63|8@0+ (1,0) [0|255] "" XXX - SG_ NEW_SIGNAL_1 : 7|16@0+ (1,0) [0|65535] "" XXX + SG_ NEW_SIGNAL_7 : 47|1@0+ (1,0) [0|255] "" XXX + SG_ ACC_SET_ALLOWED : 34|1@0+ (1,0) [0|1] "" XXX + SG_ CRZ_ENDED : 36|1@0+ (1,0) [0|255] "" XXX + SG_ ACCEL_CMD : 17|13@0+ (1,-4096) [0|1] "" XXX + SG_ STATIC_1 : 15|11@0+ (1,0) [0|16383] "" XXX + SG_ STATIC_2 : 18|3@1+ (1,0) [0|3] "" XXX + SG_ ERROR_STATUS : 7|8@0+ (1,0) [0|255] "" XXX BO_ 121 EPB: 8 XXX SG_ NEW_SIGNAL_1 : 4|4@0+ (1,0) [0|255] "" XXX @@ -736,6 +745,8 @@ BO_ 1171 MOB3: 8 XXX BO_ 1248 MOB4: 8 XXX +BO_ 1177 RADAR_499_STATIC: 8 XXX + diff --git a/opendbc/subaru_forester_2017_generated.dbc b/opendbc/subaru_forester_2017_generated.dbc index 6e5b3ff27..78e97d2f0 100644 --- a/opendbc/subaru_forester_2017_generated.dbc +++ b/opendbc/subaru_forester_2017_generated.dbc @@ -134,10 +134,10 @@ BO_ 352 ES_Brake: 8 XXX SG_ Counter : 48|3@1+ (1,0) [0|7] "" XXX SG_ Checksum : 56|8@1+ (1,0) [0|255] "" XXX -BO_ 353 ES_CruiseThrottle: 8 XXX - SG_ Throttle_Cruise : 0|12@1+ (1,0) [0|4095] "" XXX +BO_ 353 ES_Distance: 8 XXX + SG_ Cruise_Throttle : 0|12@1+ (1,0) [0|4095] "" XXX SG_ Signal1 : 12|4@1+ (1,0) [0|15] "" XXX - SG_ Cruise_Activated : 16|1@1+ (1,0) [0|1] "" XXX + SG_ Car_Follow : 16|1@1+ (1,0) [0|1] "" XXX SG_ Signal2 : 17|3@1+ (1,0) [0|7] "" XXX SG_ Brake_On : 20|1@1+ (1,0) [0|1] "" XXX SG_ Distance_Swap : 21|1@1+ (1,0) [0|1] "" XXX @@ -249,13 +249,15 @@ VAL_ 328 Gear 0 "N" 1 "D" 2 "D" 3 "D" 4 "D" 5 "D" 6 "D" 14 "R" 15 "P"; CM_ "subaru_forester_2017.dbc starts here"; - BO_ 355 ES_DashStatus: 8 XXX SG_ Not_Ready_Startup : 4|2@1+ (1,0) [0|3] "" XXX SG_ Cruise_On : 16|1@1+ (1,0) [0|1] "" XXX + SG_ Cruise_Activated : 17|1@0+ (1,0) [0|1] "" XXX SG_ Cruise_Set_Speed : 24|8@1+ (1,0) [0|255] "" XXX SG_ Counter : 40|3@1+ (1,0) [0|7] "" XXX - SG_ Cruise_Activated : 54|1@1+ (1,0) [0|1] "" XXX + SG_ Brake : 43|1@1+ (1,0) [0|1] "" XXX + SG_ Car_Follow : 54|1@1+ (1,0) [0|1] "" XXX + SG_ Far_Distance : 56|4@1+ (1,0) [0|1] "" XXX BO_ 881 Steering_Torque: 8 XXX SG_ Steering_Motor_Flat : 0|10@1+ (32,0) [0|1000] "" XXX diff --git a/opendbc/subaru_global_2017_generated.dbc b/opendbc/subaru_global_2017_generated.dbc index 7964225b9..4c6327563 100644 --- a/opendbc/subaru_global_2017_generated.dbc +++ b/opendbc/subaru_global_2017_generated.dbc @@ -119,6 +119,11 @@ BO_ 313 Brake_Pedal: 8 XXX SG_ Brake_Pedal : 36|12@1+ (1,0) [0|4095] "" XXX SG_ Signal4 : 48|16@1+ (1,0) [0|65535] "" XXX +BO_ 372 Engine_Stop_Start: 8 XXX + SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX + SG_ Counter : 8|4@1+ (1,0) [0|15] "" XXX + SG_ STOP_START_STATE : 39|2@0+ (1,0) [0|3] "" XXX + BO_ 290 ES_LKAS: 8 XXX SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX SG_ Counter : 8|4@1+ (1,0) [0|15] "" XXX @@ -161,6 +166,7 @@ BO_ 912 Dashlights: 8 XXX SG_ SEATBELT_FL : 48|1@1+ (1,0) [0|1] "" XXX SG_ LEFT_BLINKER : 50|1@1+ (1,0) [0|1] "" XXX SG_ RIGHT_BLINKER : 51|1@1+ (1,0) [0|1] "" XXX + SG_ STOP_START : 54|1@0+ (1,0) [0|1] "" XXX BO_ 940 BodyInfo: 8 XXX SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX @@ -257,7 +263,6 @@ CM_ SG_ 912 ICY_ROAD "1 = DASHLIGHT ON, 2 = WARNING, 3 = OFF"; CM_ "subaru_global_2017.dbc starts here"; - BO_ 72 Transmission: 8 XXX SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX SG_ Counter : 8|4@1+ (1,0) [0|15] "" XXX diff --git a/opendbc/subaru_outback_2015_generated.dbc b/opendbc/subaru_outback_2015_generated.dbc index bea56d532..a2fef697f 100644 --- a/opendbc/subaru_outback_2015_generated.dbc +++ b/opendbc/subaru_outback_2015_generated.dbc @@ -134,10 +134,10 @@ BO_ 352 ES_Brake: 8 XXX SG_ Counter : 48|3@1+ (1,0) [0|7] "" XXX SG_ Checksum : 56|8@1+ (1,0) [0|255] "" XXX -BO_ 353 ES_CruiseThrottle: 8 XXX - SG_ Throttle_Cruise : 0|12@1+ (1,0) [0|4095] "" XXX +BO_ 353 ES_Distance: 8 XXX + SG_ Cruise_Throttle : 0|12@1+ (1,0) [0|4095] "" XXX SG_ Signal1 : 12|4@1+ (1,0) [0|15] "" XXX - SG_ Cruise_Activated : 16|1@1+ (1,0) [0|1] "" XXX + SG_ Car_Follow : 16|1@1+ (1,0) [0|1] "" XXX SG_ Signal2 : 17|3@1+ (1,0) [0|7] "" XXX SG_ Brake_On : 20|1@1+ (1,0) [0|1] "" XXX SG_ Distance_Swap : 21|1@1+ (1,0) [0|1] "" XXX @@ -249,7 +249,6 @@ VAL_ 328 Gear 0 "N" 1 "D" 2 "D" 3 "D" 4 "D" 5 "D" 6 "D" 14 "R" 15 "P"; CM_ "subaru_outback_2015.dbc starts here"; - BO_ 358 ES_DashStatus: 8 XXX SG_ Not_Ready_Startup : 0|3@1+ (1,0) [0|7] "" XXX SG_ Seatbelt_Disengage : 12|2@1+ (1,0) [0|3] "" XXX diff --git a/opendbc/subaru_outback_2019_generated.dbc b/opendbc/subaru_outback_2019_generated.dbc index ba6a9fc31..af6d7f416 100644 --- a/opendbc/subaru_outback_2019_generated.dbc +++ b/opendbc/subaru_outback_2019_generated.dbc @@ -134,10 +134,10 @@ BO_ 352 ES_Brake: 8 XXX SG_ Counter : 48|3@1+ (1,0) [0|7] "" XXX SG_ Checksum : 56|8@1+ (1,0) [0|255] "" XXX -BO_ 353 ES_CruiseThrottle: 8 XXX - SG_ Throttle_Cruise : 0|12@1+ (1,0) [0|4095] "" XXX +BO_ 353 ES_Distance: 8 XXX + SG_ Cruise_Throttle : 0|12@1+ (1,0) [0|4095] "" XXX SG_ Signal1 : 12|4@1+ (1,0) [0|15] "" XXX - SG_ Cruise_Activated : 16|1@1+ (1,0) [0|1] "" XXX + SG_ Car_Follow : 16|1@1+ (1,0) [0|1] "" XXX SG_ Signal2 : 17|3@1+ (1,0) [0|7] "" XXX SG_ Brake_On : 20|1@1+ (1,0) [0|1] "" XXX SG_ Distance_Swap : 21|1@1+ (1,0) [0|1] "" XXX @@ -249,7 +249,6 @@ VAL_ 328 Gear 0 "N" 1 "D" 2 "D" 3 "D" 4 "D" 5 "D" 6 "D" 14 "R" 15 "P"; CM_ "subaru_outback_2019.dbc starts here"; - BO_ 358 ES_DashStatus: 8 XXX SG_ Not_Ready_Startup : 0|3@1+ (1,0) [0|7] "" XXX SG_ Seatbelt_Disengage : 12|2@1+ (1,0) [0|3] "" XXX diff --git a/opendbc/toyota_avalon_2017_pt_generated.dbc b/opendbc/toyota_avalon_2017_pt_generated.dbc deleted file mode 100644 index 901616d58..000000000 --- a/opendbc/toyota_avalon_2017_pt_generated.dbc +++ /dev/null @@ -1,450 +0,0 @@ -CM_ "AUTOGENERATED FILE, DO NOT EDIT"; - - -CM_ "Imported file _toyota_2017.dbc starts here"; -VERSION "" - - -NS_ : - NS_DESC_ - CM_ - BA_DEF_ - BA_ - VAL_ - CAT_DEF_ - CAT_ - FILTER - BA_DEF_DEF_ - EV_DATA_ - ENVVAR_DATA_ - SGTYPE_ - SGTYPE_VAL_ - BA_DEF_SGTYPE_ - BA_SGTYPE_ - SIG_TYPE_REF_ - VAL_TABLE_ - SIG_GROUP_ - SIG_VALTYPE_ - SIGTYPE_VALTYPE_ - BO_TX_BU_ - BA_DEF_REL_ - BA_REL_ - BA_DEF_DEF_REL_ - BU_SG_REL_ - BU_EV_REL_ - BU_BO_REL_ - SG_MUL_VAL_ - -BS_: - -BU_: XXX DSU HCU EPS IPAS CGW - -BO_ 36 KINEMATICS: 8 XXX - SG_ ACCEL_Y : 33|10@0+ (0.03589,-18.375) [0|65535] "m/s^2" XXX - SG_ YAW_RATE : 1|10@0+ (0.244,-125) [0|65535] "deg/sec" XXX - SG_ STEERING_TORQUE : 17|10@0+ (1,-512) [0|65535] "" XXX - -BO_ 37 STEER_ANGLE_SENSOR: 8 XXX - SG_ STEER_ANGLE : 3|12@0- (1.5,0) [-500|500] "deg" XXX - SG_ STEER_FRACTION : 39|4@0- (0.1,0) [-0.7|0.7] "deg" XXX - SG_ STEER_RATE : 35|12@0- (1,0) [-2000|2000] "deg/s" XXX - -BO_ 166 BRAKE: 8 XXX - SG_ BRAKE_AMOUNT : 7|8@0+ (1,0) [0|255] "" XXX - SG_ BRAKE_PEDAL : 23|8@0+ (1,0) [0|255] "" XXX - -BO_ 170 WHEEL_SPEEDS: 8 XXX - SG_ WHEEL_SPEED_FR : 7|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_FL : 23|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_RR : 39|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_RL : 55|16@0+ (0.01,-67.67) [0|250] "kph" XXX - -BO_ 180 SPEED: 8 XXX - SG_ ENCODER : 39|8@0+ (1,0) [0|255] "" XXX - SG_ SPEED : 47|16@0+ (0.01,0) [0|250] "kph" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 353 DSU_SPEED: 7 XXX - SG_ FORWARD_SPEED : 15|16@0- (0.00390625,-30) [0|255] "kph" XXX - -BO_ 452 ENGINE_RPM: 8 CGW - SG_ RPM : 7|16@0- (0.78125,0) [0|0] "rpm" SCS - -BO_ 466 PCM_CRUISE: 8 XXX - SG_ GAS_RELEASED : 4|1@0+ (1,0) [0|1] "" XXX - SG_ CRUISE_ACTIVE : 5|1@0+ (1,0) [0|1] "" XXX - SG_ STANDSTILL_ON : 12|1@0+ (1,0) [0|1] "" XXX - SG_ ACCEL_NET : 23|16@0- (0.001,0) [-20|20] "m/s2" XXX - SG_ CRUISE_STATE : 55|4@0+ (1,0) [0|15] "" XXX - SG_ CANCEL_REQ : 49|1@1+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 467 PCM_CRUISE_2: 8 XXX - SG_ MAIN_ON : 15|1@0+ (1,0) [0|1] "" XXX - SG_ LOW_SPEED_LOCKOUT : 14|2@0+ (1,0) [0|3] "kph" XXX - SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "kph" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 552 ACCELEROMETER: 8 XXX - SG_ ACCEL_Z : 22|15@0- (1,0) [0|32767] "" XXX - SG_ ACCEL_X : 6|15@0- (0.001,0) [-20|20] "m/s2" XXX - -BO_ 560 BRAKE_MODULE2: 7 XXX - SG_ BRAKE_PRESSED : 26|1@0+ (1,0) [0|1] "" XXX - -BO_ 614 STEERING_IPAS: 8 IPAS - SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX - SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX - SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX - SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 643 PRE_COLLISION: 7 DSU - SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 15|8@0+ (1,0) [0|255] "" XXX - SG_ FORCE : 23|16@0- (2,0) [0|255] "N" XXX - SG_ SET_ME_X002 : 33|8@0+ (1,0) [0|3] "" XXX - SG_ BRAKE_STATUS : 39|3@0+ (1,0) [0|255] "" XXX - SG_ STATE : 36|3@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X003 : 40|1@0+ (1,0) [0|1] "" XXX - SG_ PRECOLLISION_ACTIVE : 41|1@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 55|8@0+ (1,0) [0|255] "" XXX - -BO_ 740 STEERING_LKA: 5 XXX - SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX - SG_ STEER_REQUEST : 0|1@0+ (1,0) [0|1] "" XXX - SG_ COUNTER : 6|6@0+ (1,0) [0|63] "" XXX - SG_ SET_ME_1 : 7|1@0+ (1,0) [0|1] "" XXX - SG_ STEER_TORQUE_CMD : 15|16@0- (1,0) [0|65535] "" XXX - SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX - -BO_ 742 LEAD_INFO: 8 DSU - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" HCU - SG_ LEAD_REL_SPEED : 23|12@0- (0.025,0) [-100|100] "m/s" HCU - SG_ LEAD_LONG_DIST : 7|13@0+ (0.05,0) [0|300] "m" HCU - -BO_ 835 ACC_CONTROL: 8 DSU - SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU - SG_ ACC_MALFUNCTION : 18|1@0+ (1,0) [0|0] "" XXX - SG_ ACC_CUT_IN : 25|1@0+ (1,0) [0|1] "" XXX - SG_ ALLOW_LONG_PRESS : 17|2@0+ (1,0) [0|2] "" XXX - SG_ ACC_TYPE : 23|2@0+ (1,0) [0|3] "" HCU - SG_ DISTANCE : 20|1@0+ (1,0) [0|1] "" XXX - SG_ MINI_CAR : 21|1@0+ (1,0) [0|1] "" XXX - SG_ PERMIT_BRAKING : 30|1@0+ (1,0) [0|1] "" HCU - SG_ RELEASE_STANDSTILL : 31|1@0+ (1,0) [0|1] "" HCU - SG_ CANCEL_REQ : 24|1@0+ (1,0) [0|1] "" HCU - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - SG_ ACCEL_CMD_ALT : 47|8@0- (0.05,0) [0|0] "m/s^2" XXX - SG_ RADAR_DIRTY : 19|1@0+ (1,0) [0|1] "" XXX - -BO_ 836 PRE_COLLISION_2: 8 DSU - SG_ CHECKSUM : 63|8@0+ (1,0) [0|0] "" XXX - -BO_ 869 DSU_CRUISE : 7 DSU - SG_ RES_BTN : 3|1@0+ (1,0) [0|0] "" XXX - SG_ SET_BTN : 2|1@0+ (1,0) [0|0] "" XXX - SG_ CANCEL_BTN : 1|1@0+ (1,0) [0|0] "" XXX - SG_ MAIN_ON : 0|1@0+ (1,0) [0|0] "" XXX - SG_ SET_SPEED : 15|8@0+ (1,0) [0|0] "km/h" XXX - SG_ CRUISE_REQUEST : 31|8@0+ (100,-12800) [0|0] "N" XXX - SG_ LEAD_DISTANCE : 39|8@0+ (1,0) [0|0] "m" XXX - -BO_ 921 PCM_CRUISE_SM: 8 XXX - SG_ MAIN_ON : 4|1@0+ (1,0) [0|1] "" XXX - SG_ CRUISE_CONTROL_STATE : 11|4@0+ (1,0) [0|15] "" XXX - SG_ DISTANCE_LINES : 14|2@0+ (1,0) [0|3] "" XXX - SG_ UI_SET_SPEED : 31|8@0+ (1,0) [0|255] "" XXX - -BO_ 951 ESP_CONTROL: 8 ESP - SG_ TC_DISABLED : 13|1@0+ (1,0) [0|1] "" XXX - SG_ VSC_DISABLED : 12|2@0+ (1,0) [0|1] "" XXX - SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" XXX - SG_ BRAKE_HOLD_ENABLED : 33|1@1+ (1,0) [0|1] "" XXX - SG_ BRAKE_HOLD_ACTIVE : 36|1@0+ (1,0) [0|1] "" XXX - -BO_ 1020 SOLAR_SENSOR: 8 XXX - SG_ LUX_SENSOR : 55|13@0+ (1,0) [0|0] "" XXX - -BO_ 1041 ACC_HUD: 8 DSU - SG_ PCS_INDICATOR : 7|2@0+ (1,0) [0|3] "" XXX - SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X20 : 15|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X10 : 39|8@0+ (1,0) [0|1] "" XXX - SG_ PCS_OFF : 40|1@0+ (1,0) [0|0] "" XXX - SG_ PCS_SENSITIVITY : 55|8@0+ (1,0) [0|1] "" XXX - -BO_ 1042 LKAS_HUD: 8 XXX - SG_ BARRIERS : 1|2@0+ (1,0) [0|3] "" XXX - SG_ RIGHT_LINE : 3|2@0+ (1,0) [0|3] "" XXX - SG_ LEFT_LINE : 5|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X01 : 7|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X01_2 : 11|2@0+ (1,0) [0|3] "" XXX - SG_ LDA_ALERT : 9|2@0+ (1,0) [0|3] "" XXX - SG_ TWO_BEEPS : 12|1@0+ (1,0) [0|1] "" XXX - SG_ ADJUSTING_CAMERA : 13|1@0+ (1,0) [0|1] "" XXX - SG_ LDA_MALFUNCTION : 15|1@0+ (1,0) [0|1] "" XXX - SG_ REPEATED_BEEPS : 32|1@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X0C : 23|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X2C : 47|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X38 : 55|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X02 : 63|8@0+ (1,0) [0|1] "" XXX - -BO_ 1043 TIME : 8 CGW - SG_ YEAR : 7|8@0+ (1,0) [0|0] "year" XXX - SG_ MONTH : 15|8@0+ (1,0) [0|0] "month" XXX - SG_ DAY : 23|8@0+ (1,0) [0|0] "day" XXX - SG_ HOUR : 31|8@0+ (1,0) [0|0] "hour" XXX - SG_ MINUTE : 39|8@0+ (1,0) [0|0] "minute" XXX - SG_ GMT_DIFF : 55|1@0+ (1,0) [0|0] "" XXX - SG_ GMTDIFF_HOURS : 54|4@0+ (1,0) [0|0] "hours" XXX - SG_ GMTDIFF_MINUTES : 50|6@0+ (1,0) [0|0] "minutes" XXX - SG_ SUMMER : 60|1@0+ (1,0) [0|0] "" XXX - -BO_ 1408 VIN_PART_1: 8 CGW - SG_ VIN_1 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_2 : 15|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_3 : 23|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_4 : 31|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_5 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_6 : 47|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_7 : 55|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_8 : 63|8@0+ (1,0) [0|0] "" XXX - -BO_ 1409 VIN_PART_2: 8 CGW - SG_ VIN_9 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_10 : 15|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_11 : 23|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_12 : 31|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_13 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_14 : 47|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_15 : 55|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_16 : 63|8@0+ (1,0) [0|0] "" XXX - -BO_ 1410 VIN_PART_3: 8 CGW - SG_ VIN_17 : 7|8@0+ (1,0) [0|0] "" XXX - -BO_ 1553 UI_SETTING: 8 XXX - SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX - SG_ ODOMETER : 43|20@0+ (1,0) [0|1048575] "" XXX - -BO_ 1556 STEERING_LEVERS: 8 XXX - SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX - SG_ HAZARD_LIGHT : 27|1@0+ (1,0) [0|1] "" XXX - -BO_ 1568 SEATS_DOORS: 8 XXX - SG_ METER_DIMMED : 38|1@0+ (1,0) [0|1] "" XXX - SG_ PARKING_BRAKE : 60|1@0+ (1,0) [0|1] "" XXX - SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_RR : 43|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_FR : 44|1@0+ (1,0) [0|1] "" XXX - -BO_ 1570 LIGHT_STALK: 8 SCM - SG_ AUTO_HIGH_BEAM : 37|1@0+ (1,0) [0|1] "" XXX - SG_ FRONT_FOG : 27|1@0+ (1,0) [0|1] "" XXX - SG_ PARKING_LIGHT : 28|1@0+ (1,0) [0|1] "" XXX - SG_ LOW_BEAM : 29|1@0+ (1,0) [0|1] "" XXX - SG_ HIGH_BEAM : 30|1@0+ (1,0) [0|1] "" XXX - SG_ DAYTIME_RUNNING_LIGHT : 31|1@0+ (1,0) [0|1] "" XXX - -BO_ 1161 RSA1: 8 FCM - SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY1 : 12|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT1 : 9|2@0+ (1,0) [0|0] "" XXX - SG_ SPDVAL1 : 23|8@0+ (1,0) [0|0] "kph" XXX - SG_ SPLSGN1 : 31|4@0+ (1,0) [0|0] "" XXX - SG_ SPLSGN2 : 27|4@0+ (1,0) [0|0] "" XXX - SG_ TSGN2 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY2 : 44|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT2 : 41|2@0+ (1,0) [0|0] "" XXX - SG_ SPDVAL2 : 55|8@0+ (1,0) [0|0] "" XXX - SG_ BZRRQ_P : 63|2@0+ (1,0) [0|0] "" XXX - SG_ BZRRQ_A : 61|2@0+ (1,0) [0|0] "" XXX - SG_ SYNCID1 : 59|4@0+ (1,0) [0|0] "" XXX - -BO_ 1162 RSA2: 8 FCM - SG_ TSGN3 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY3 : 12|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT3 : 9|2@0+ (1,0) [0|0] "" XXX - SG_ SPLSGN3 : 31|4@0+ (1,0) [0|0] "" XXX - SG_ SPLSGN4 : 27|4@0+ (1,0) [0|0] "" XXX - SG_ TSGN4 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY4 : 44|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT4 : 41|2@0+ (1,0) [0|0] "" XXX - SG_ DPSGNREQ : 54|1@0+ (1,0) [0|0] "" XXX - SG_ SGNNUMP : 53|3@0+ (1,0) [0|0] "" XXX - SG_ SGNNUMA : 50|3@0+ (1,0) [0|0] "" XXX - SG_ SPDUNT : 63|2@0+ (1,0) [0|0] "" XXX - SG_ TSRWMSG : 61|2@0+ (1,0) [0|0] "" XXX - SG_ SYNCID2 : 59|4@0+ (1,0) [0|0] "" XXX - -BO_ 1163 RSA3: 8 FCM - SG_ TSREQPD : 7|1@0+ (1,0) [0|0] "" XXX - SG_ TSRMSW : 6|1@0+ (1,0) [0|0] "" XXX - SG_ OTSGNNTM : 5|2@0+ (1,0) [0|0] "" XXX - SG_ NTLVLSPD : 3|2@0+ (1,0) [0|0] "" XXX - SG_ OVSPNTM : 1|2@0+ (1,0) [0|0] "" XXX - SG_ OVSPVALL : 11|4@0+ (1,-5) [0|0] "" XXX - SG_ OVSPVALM : 19|4@0+ (1,-5) [0|0] "" XXX - SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX - SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" XXX - -BO_ 1571 CENTRAL_GATEWAY_UNIT: 8 CGW - SG_ DOOR_LOCK_FEEDBACK_LIGHT : 15|1@0+ (1,0) [0|0] "" XXX - SG_ KEYFOB_LOCKING_FEEDBACK_LIGHT : 61|1@0+ (1,0) [0|0] "" XXX - SG_ KEYFOB_UNLOCKING_FEEDBACK_LIGHT : 62|1@0+ (1,0) [0|0] "" XXX - -CM_ SG_ 36 ACCEL_Y "unit is tbd"; -CM_ SG_ 36 YAW_RATE "verify"; -CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; -CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; -CM_ SG_ 37 STEER_RATE "factor is tbd"; -CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; -CM_ SG_ 466 CRUISE_STATE "Active state is 8, if standstill is requested will switch to state 11(3 sec timer), after timer is elapsed will switch into state 7(standstill). If plus button was pressed - status 9, minus button pressed - status 10"; -CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isn't perfect"; -CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; -CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; -CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; -CM_ SG_ 608 STEER_OVERRIDE "set when driver torque exceeds a certain value"; -CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; -CM_ SG_ 643 COUNTER "only used on cars that use this msg for cruise control"; -CM_ SG_ 643 BRAKE_STATUS "only used on cars that use this msg for cruise control"; -CM_ SG_ 643 PRECOLLISION_ACTIVE "set 0.5s before any braking"; -CM_ SG_ 835 ACC_TYPE "if 2, car is likely to have a permanent low speed lockout. 1 is ok"; -CM_ SG_ 835 RADAR_DIRTY "Display Clean Radar Sensor message on HUD"; -CM_ SG_ 835 ACC_MALFUNCTION "display ACC fault on dash if set to 1"; -CM_ SG_ 835 ACC_CUT_IN "Display blinking yellow lead if set to 1"; -CM_ SG_ 835 DISTANCE "Display Distance Bars on HUD Permanently"; -CM_ SG_ 835 ALLOW_LONG_PRESS "Enable Toyota's factory set speed increment behaviour, available on both metrics cars and imperial unit cars"; -CM_ SG_ 835 PERMIT_BRAKING "Original ACC has this going high when a car in front is detected. In openpilot and before the PERMIT_BRAKING name, this was 'SET_ME_1' and is hardcoded to be high. Unsure if only informational or has an effect though existing usage in openpilot is to always set it to 1. Originally 'PMTBRKG' in the leaked toyota_2017_ref_pt.dbc file and name expansion speculated to be PerMiT BRaKinG."; -CM_ SG_ 835 ACCEL_CMD_ALT "Copy of main ACCEL_CMD, but across 8 bits instead of 16 bits like ACCEL_CMD. Unsure if only informational or has an effect. Likely informational as existing openpilot sets this to 0 and no loss of functionality observed. Originally 'AT_RAW' in leaked toyota_2017_ref_pt.dbc file."; -CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; -CM_ SG_ 951 BRAKE_LIGHTS_ACC "brake lights when ACC commands decel"; -CM_ SG_ 1041 PCS_INDICATOR "Pre-Collision System Indicator"; -CM_ SG_ 1041 PCS_SENSITIVITY "Pre-Collision System Sensitivity"; -CM_ SG_ 1042 SET_ME_1 "unclear what this is, but it's always 1 in drive traces"; -CM_ SG_ 1042 REPEATED_BEEPS "recommended for fcw and other important alerts"; -CM_ SG_ 1161 SPDVAL1 "Numbers 0-199 is displayed, 200-254 displays circle without number and 255 is for no limit."; -CM_ SG_ 1161 SYNCID1 "counter from 1 to f at 1 Hz"; -CM_ SG_ 1161 SPDVAL2 "conditional speed value 70"; -CM_ SG_ 1162 SGNNUMP "1 if SPDVAL1 is set, otherwise 0"; -CM_ SG_ 1162 SYNCID2 "counter from 1 to f at 1 Hz"; -CM_ SG_ 1163 TSREQPD "always 1"; -CM_ SG_ 1163 TSRMSW "always 1"; -CM_ SG_ 1163 OTSGNNTM "always 3"; -CM_ SG_ 1163 NTLVLSPD "always 3"; -CM_ SG_ 1163 OVSPNTM "always 3"; -CM_ SG_ 1163 OVSPVALL "-5 at start then 2 after 2 seconds"; -CM_ SG_ 1163 OVSPVALM "-5 at start then 5 after 2 seconds"; -CM_ SG_ 1163 OVSPVALH "-5 at start then 10 after 2 seconds"; -CM_ SG_ 1163 TSRSPU "always 1"; -CM_ SG_ 1553 ODOMETER "Unit is dependent upon units signal"; - -VAL_ 466 CRUISE_STATE 11 "timer_3sec" 10 "adaptive click down" 9 "adaptive click up" 8 "adaptive engaged" 7 "standstill" 6 "non-adaptive click up" 5 "non-adaptive click down" 4 "non-adaptive hold down" 3 "non-adaptive hold up" 2 "non-adaptive being engaged" 1 "non-adaptive engaged" 0 "off"; -VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok"; -VAL_ 614 STATE 3 "enabled" 1 "disabled"; -VAL_ 614 DIRECTION_CMD 3 "right" 2 "center" 1 "left"; -VAL_ 643 STATE 0 "normal" 1 "adaptive_cruise_control" 3 "emergency_braking"; -VAL_ 835 ACC_TYPE 2 "permanent low speed lockout" 1 "ok"; -VAL_ 835 ACC_MALFUNCTION 1 "faulted" 0 "ok"; -VAL_ 835 ACC_CUT_IN 1 "CUT-IN Detected" 0 "clear"; -VAL_ 835 ALLOW_LONG_PRESS 2 "set speed increase by 5 speed units regardless" 1 "set speed increase by 1 speed unit on short press, 5 speed units on long press"; -VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted"; -VAL_ 1041 PCS_INDICATOR 2 "PCS Faulted" 1 "PCS Turned Off By User" 0 "PCS Enabled"; -VAL_ 1041 PCS_SENSITIVITY 64 "high sensitivity" 128 "mid sensitivity" 192 "low sensitivity" 0 "off"; -VAL_ 1042 LDA_ALERT 3 "hold with continuous beep" 2 "LDA unavailable" 1 "hold" 0 "none"; -VAL_ 1042 BARRIERS 3 "both" 2 "right" 1 "left" 0 "none"; -VAL_ 1042 RIGHT_LINE 3 "orange" 2 "faded" 1 "solid" 0 "none"; -VAL_ 1042 LEFT_LINE 3 "orange" 2 "faded" 1 "solid" 0 "none"; -VAL_ 1553 UNITS 1 "km" 2 "miles"; -VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left"; -VAL_ 1161 TSGN1 1 "speed sign" 0 "none"; -VAL_ 1161 TSGN2 1 "speed sign" 0 "none"; -VAL_ 1161 SPLSGN2 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none"; -VAL_ 1162 TSGN3 0 "none" 1 "speed sign" 2 "0 unlimited" 7 "unlimited" 16 "highway" 17 "no highway" 18 "motorway" 19 "no motorway" 20 "in city" 21 "outside city" 22 "pedestrian area" 23 "no pedestrian area" 65 "no overtaking left" 66 "no overtaking right" 67 "overtaking allowed again" 81 "no right turn" 97 "stop" 105 "yield" 113 "stop" 114 "yield us" 129 "no entry" 138 "no entry tss2" 145 "do not enter"; -VAL_ 1162 SPLSGN3 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none"; - - - - -CM_ "Imported file _comma.dbc starts here"; -BO_ 359 STEERING_IPAS_COMMA: 8 IPAS - SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX - SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX - SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX - SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant"; - - BO_ 512 GAS_COMMAND: 6 EON - SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR - SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR - SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR - - BO_ 513 GAS_SENSOR: 6 INTERCEPTOR - SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON - SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON - SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON - - VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; - -BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX - SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX - -CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss"; - -BO_ 767 SDSU: 8 XXX - SG_ FD_BUTTON : 7|1@0+ (1,0) [0|1] "" XXX - -CM_ "BO_ SDSU: The sDSU is a modified DSU for use in TSS1 Toyotas. Learn more: https://github.com/wocsor/panda/tree/smart_dsu"; - -CM_ SG_ 767 FD_BUTTON "The follow distance button signal as forwarded by the sdsu"; - -CM_ "toyota_avalon_2017_pt.dbc starts here"; - - - -BO_ 550 BRAKE_MODULE: 8 XXX - SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|255] "" XXX - SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|65535] "" XXX - SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|3] "" XXX - -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 - -BO_ 608 STEER_TORQUE_SENSOR: 8 XXX - SG_ STEER_TORQUE_EPS : 47|16@0- (0.73,0) [-20000|20000] "" XXX - SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX - SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - SG_ STEER_ANGLE : 31|16@0- (0.0573,0) [-500|500] "" XXX - -BO_ 610 EPS_STATUS: 5 EPS - SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX - SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX - SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX - -BO_ 956 GEAR_PACKET: 8 XXX - SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX - -CM_ SG_ 548 BRAKE_PRESSURE "seems prop to pedal force"; -CM_ SG_ 548 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; -CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; -VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; -VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled"; -VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby"; diff --git a/opendbc/toyota_camry_hybrid_2018_pt_generated.dbc b/opendbc/toyota_camry_hybrid_2018_pt_generated.dbc deleted file mode 100644 index 55ebbb6a4..000000000 --- a/opendbc/toyota_camry_hybrid_2018_pt_generated.dbc +++ /dev/null @@ -1,453 +0,0 @@ -CM_ "AUTOGENERATED FILE, DO NOT EDIT"; - - -CM_ "Imported file _toyota_2017.dbc starts here"; -VERSION "" - - -NS_ : - NS_DESC_ - CM_ - BA_DEF_ - BA_ - VAL_ - CAT_DEF_ - CAT_ - FILTER - BA_DEF_DEF_ - EV_DATA_ - ENVVAR_DATA_ - SGTYPE_ - SGTYPE_VAL_ - BA_DEF_SGTYPE_ - BA_SGTYPE_ - SIG_TYPE_REF_ - VAL_TABLE_ - SIG_GROUP_ - SIG_VALTYPE_ - SIGTYPE_VALTYPE_ - BO_TX_BU_ - BA_DEF_REL_ - BA_REL_ - BA_DEF_DEF_REL_ - BU_SG_REL_ - BU_EV_REL_ - BU_BO_REL_ - SG_MUL_VAL_ - -BS_: - -BU_: XXX DSU HCU EPS IPAS CGW - -BO_ 36 KINEMATICS: 8 XXX - SG_ ACCEL_Y : 33|10@0+ (0.03589,-18.375) [0|65535] "m/s^2" XXX - SG_ YAW_RATE : 1|10@0+ (0.244,-125) [0|65535] "deg/sec" XXX - SG_ STEERING_TORQUE : 17|10@0+ (1,-512) [0|65535] "" XXX - -BO_ 37 STEER_ANGLE_SENSOR: 8 XXX - SG_ STEER_ANGLE : 3|12@0- (1.5,0) [-500|500] "deg" XXX - SG_ STEER_FRACTION : 39|4@0- (0.1,0) [-0.7|0.7] "deg" XXX - SG_ STEER_RATE : 35|12@0- (1,0) [-2000|2000] "deg/s" XXX - -BO_ 166 BRAKE: 8 XXX - SG_ BRAKE_AMOUNT : 7|8@0+ (1,0) [0|255] "" XXX - SG_ BRAKE_PEDAL : 23|8@0+ (1,0) [0|255] "" XXX - -BO_ 170 WHEEL_SPEEDS: 8 XXX - SG_ WHEEL_SPEED_FR : 7|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_FL : 23|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_RR : 39|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_RL : 55|16@0+ (0.01,-67.67) [0|250] "kph" XXX - -BO_ 180 SPEED: 8 XXX - SG_ ENCODER : 39|8@0+ (1,0) [0|255] "" XXX - SG_ SPEED : 47|16@0+ (0.01,0) [0|250] "kph" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 353 DSU_SPEED: 7 XXX - SG_ FORWARD_SPEED : 15|16@0- (0.00390625,-30) [0|255] "kph" XXX - -BO_ 452 ENGINE_RPM: 8 CGW - SG_ RPM : 7|16@0- (0.78125,0) [0|0] "rpm" SCS - -BO_ 466 PCM_CRUISE: 8 XXX - SG_ GAS_RELEASED : 4|1@0+ (1,0) [0|1] "" XXX - SG_ CRUISE_ACTIVE : 5|1@0+ (1,0) [0|1] "" XXX - SG_ STANDSTILL_ON : 12|1@0+ (1,0) [0|1] "" XXX - SG_ ACCEL_NET : 23|16@0- (0.001,0) [-20|20] "m/s2" XXX - SG_ CRUISE_STATE : 55|4@0+ (1,0) [0|15] "" XXX - SG_ CANCEL_REQ : 49|1@1+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 467 PCM_CRUISE_2: 8 XXX - SG_ MAIN_ON : 15|1@0+ (1,0) [0|1] "" XXX - SG_ LOW_SPEED_LOCKOUT : 14|2@0+ (1,0) [0|3] "kph" XXX - SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "kph" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 552 ACCELEROMETER: 8 XXX - SG_ ACCEL_Z : 22|15@0- (1,0) [0|32767] "" XXX - SG_ ACCEL_X : 6|15@0- (0.001,0) [-20|20] "m/s2" XXX - -BO_ 560 BRAKE_MODULE2: 7 XXX - SG_ BRAKE_PRESSED : 26|1@0+ (1,0) [0|1] "" XXX - -BO_ 614 STEERING_IPAS: 8 IPAS - SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX - SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX - SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX - SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 643 PRE_COLLISION: 7 DSU - SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 15|8@0+ (1,0) [0|255] "" XXX - SG_ FORCE : 23|16@0- (2,0) [0|255] "N" XXX - SG_ SET_ME_X002 : 33|8@0+ (1,0) [0|3] "" XXX - SG_ BRAKE_STATUS : 39|3@0+ (1,0) [0|255] "" XXX - SG_ STATE : 36|3@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X003 : 40|1@0+ (1,0) [0|1] "" XXX - SG_ PRECOLLISION_ACTIVE : 41|1@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 55|8@0+ (1,0) [0|255] "" XXX - -BO_ 740 STEERING_LKA: 5 XXX - SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX - SG_ STEER_REQUEST : 0|1@0+ (1,0) [0|1] "" XXX - SG_ COUNTER : 6|6@0+ (1,0) [0|63] "" XXX - SG_ SET_ME_1 : 7|1@0+ (1,0) [0|1] "" XXX - SG_ STEER_TORQUE_CMD : 15|16@0- (1,0) [0|65535] "" XXX - SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX - -BO_ 742 LEAD_INFO: 8 DSU - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" HCU - SG_ LEAD_REL_SPEED : 23|12@0- (0.025,0) [-100|100] "m/s" HCU - SG_ LEAD_LONG_DIST : 7|13@0+ (0.05,0) [0|300] "m" HCU - -BO_ 835 ACC_CONTROL: 8 DSU - SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU - SG_ ACC_MALFUNCTION : 18|1@0+ (1,0) [0|0] "" XXX - SG_ ACC_CUT_IN : 25|1@0+ (1,0) [0|1] "" XXX - SG_ ALLOW_LONG_PRESS : 17|2@0+ (1,0) [0|2] "" XXX - SG_ ACC_TYPE : 23|2@0+ (1,0) [0|3] "" HCU - SG_ DISTANCE : 20|1@0+ (1,0) [0|1] "" XXX - SG_ MINI_CAR : 21|1@0+ (1,0) [0|1] "" XXX - SG_ PERMIT_BRAKING : 30|1@0+ (1,0) [0|1] "" HCU - SG_ RELEASE_STANDSTILL : 31|1@0+ (1,0) [0|1] "" HCU - SG_ CANCEL_REQ : 24|1@0+ (1,0) [0|1] "" HCU - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - SG_ ACCEL_CMD_ALT : 47|8@0- (0.05,0) [0|0] "m/s^2" XXX - SG_ RADAR_DIRTY : 19|1@0+ (1,0) [0|1] "" XXX - -BO_ 836 PRE_COLLISION_2: 8 DSU - SG_ CHECKSUM : 63|8@0+ (1,0) [0|0] "" XXX - -BO_ 869 DSU_CRUISE : 7 DSU - SG_ RES_BTN : 3|1@0+ (1,0) [0|0] "" XXX - SG_ SET_BTN : 2|1@0+ (1,0) [0|0] "" XXX - SG_ CANCEL_BTN : 1|1@0+ (1,0) [0|0] "" XXX - SG_ MAIN_ON : 0|1@0+ (1,0) [0|0] "" XXX - SG_ SET_SPEED : 15|8@0+ (1,0) [0|0] "km/h" XXX - SG_ CRUISE_REQUEST : 31|8@0+ (100,-12800) [0|0] "N" XXX - SG_ LEAD_DISTANCE : 39|8@0+ (1,0) [0|0] "m" XXX - -BO_ 921 PCM_CRUISE_SM: 8 XXX - SG_ MAIN_ON : 4|1@0+ (1,0) [0|1] "" XXX - SG_ CRUISE_CONTROL_STATE : 11|4@0+ (1,0) [0|15] "" XXX - SG_ DISTANCE_LINES : 14|2@0+ (1,0) [0|3] "" XXX - SG_ UI_SET_SPEED : 31|8@0+ (1,0) [0|255] "" XXX - -BO_ 951 ESP_CONTROL: 8 ESP - SG_ TC_DISABLED : 13|1@0+ (1,0) [0|1] "" XXX - SG_ VSC_DISABLED : 12|2@0+ (1,0) [0|1] "" XXX - SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" XXX - SG_ BRAKE_HOLD_ENABLED : 33|1@1+ (1,0) [0|1] "" XXX - SG_ BRAKE_HOLD_ACTIVE : 36|1@0+ (1,0) [0|1] "" XXX - -BO_ 1020 SOLAR_SENSOR: 8 XXX - SG_ LUX_SENSOR : 55|13@0+ (1,0) [0|0] "" XXX - -BO_ 1041 ACC_HUD: 8 DSU - SG_ PCS_INDICATOR : 7|2@0+ (1,0) [0|3] "" XXX - SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X20 : 15|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X10 : 39|8@0+ (1,0) [0|1] "" XXX - SG_ PCS_OFF : 40|1@0+ (1,0) [0|0] "" XXX - SG_ PCS_SENSITIVITY : 55|8@0+ (1,0) [0|1] "" XXX - -BO_ 1042 LKAS_HUD: 8 XXX - SG_ BARRIERS : 1|2@0+ (1,0) [0|3] "" XXX - SG_ RIGHT_LINE : 3|2@0+ (1,0) [0|3] "" XXX - SG_ LEFT_LINE : 5|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X01 : 7|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X01_2 : 11|2@0+ (1,0) [0|3] "" XXX - SG_ LDA_ALERT : 9|2@0+ (1,0) [0|3] "" XXX - SG_ TWO_BEEPS : 12|1@0+ (1,0) [0|1] "" XXX - SG_ ADJUSTING_CAMERA : 13|1@0+ (1,0) [0|1] "" XXX - SG_ LDA_MALFUNCTION : 15|1@0+ (1,0) [0|1] "" XXX - SG_ REPEATED_BEEPS : 32|1@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X0C : 23|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X2C : 47|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X38 : 55|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X02 : 63|8@0+ (1,0) [0|1] "" XXX - -BO_ 1043 TIME : 8 CGW - SG_ YEAR : 7|8@0+ (1,0) [0|0] "year" XXX - SG_ MONTH : 15|8@0+ (1,0) [0|0] "month" XXX - SG_ DAY : 23|8@0+ (1,0) [0|0] "day" XXX - SG_ HOUR : 31|8@0+ (1,0) [0|0] "hour" XXX - SG_ MINUTE : 39|8@0+ (1,0) [0|0] "minute" XXX - SG_ GMT_DIFF : 55|1@0+ (1,0) [0|0] "" XXX - SG_ GMTDIFF_HOURS : 54|4@0+ (1,0) [0|0] "hours" XXX - SG_ GMTDIFF_MINUTES : 50|6@0+ (1,0) [0|0] "minutes" XXX - SG_ SUMMER : 60|1@0+ (1,0) [0|0] "" XXX - -BO_ 1408 VIN_PART_1: 8 CGW - SG_ VIN_1 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_2 : 15|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_3 : 23|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_4 : 31|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_5 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_6 : 47|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_7 : 55|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_8 : 63|8@0+ (1,0) [0|0] "" XXX - -BO_ 1409 VIN_PART_2: 8 CGW - SG_ VIN_9 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_10 : 15|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_11 : 23|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_12 : 31|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_13 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_14 : 47|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_15 : 55|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_16 : 63|8@0+ (1,0) [0|0] "" XXX - -BO_ 1410 VIN_PART_3: 8 CGW - SG_ VIN_17 : 7|8@0+ (1,0) [0|0] "" XXX - -BO_ 1553 UI_SETTING: 8 XXX - SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX - SG_ ODOMETER : 43|20@0+ (1,0) [0|1048575] "" XXX - -BO_ 1556 STEERING_LEVERS: 8 XXX - SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX - SG_ HAZARD_LIGHT : 27|1@0+ (1,0) [0|1] "" XXX - -BO_ 1568 SEATS_DOORS: 8 XXX - SG_ METER_DIMMED : 38|1@0+ (1,0) [0|1] "" XXX - SG_ PARKING_BRAKE : 60|1@0+ (1,0) [0|1] "" XXX - SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_RR : 43|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_FR : 44|1@0+ (1,0) [0|1] "" XXX - -BO_ 1570 LIGHT_STALK: 8 SCM - SG_ AUTO_HIGH_BEAM : 37|1@0+ (1,0) [0|1] "" XXX - SG_ FRONT_FOG : 27|1@0+ (1,0) [0|1] "" XXX - SG_ PARKING_LIGHT : 28|1@0+ (1,0) [0|1] "" XXX - SG_ LOW_BEAM : 29|1@0+ (1,0) [0|1] "" XXX - SG_ HIGH_BEAM : 30|1@0+ (1,0) [0|1] "" XXX - SG_ DAYTIME_RUNNING_LIGHT : 31|1@0+ (1,0) [0|1] "" XXX - -BO_ 1161 RSA1: 8 FCM - SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY1 : 12|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT1 : 9|2@0+ (1,0) [0|0] "" XXX - SG_ SPDVAL1 : 23|8@0+ (1,0) [0|0] "kph" XXX - SG_ SPLSGN1 : 31|4@0+ (1,0) [0|0] "" XXX - SG_ SPLSGN2 : 27|4@0+ (1,0) [0|0] "" XXX - SG_ TSGN2 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY2 : 44|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT2 : 41|2@0+ (1,0) [0|0] "" XXX - SG_ SPDVAL2 : 55|8@0+ (1,0) [0|0] "" XXX - SG_ BZRRQ_P : 63|2@0+ (1,0) [0|0] "" XXX - SG_ BZRRQ_A : 61|2@0+ (1,0) [0|0] "" XXX - SG_ SYNCID1 : 59|4@0+ (1,0) [0|0] "" XXX - -BO_ 1162 RSA2: 8 FCM - SG_ TSGN3 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY3 : 12|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT3 : 9|2@0+ (1,0) [0|0] "" XXX - SG_ SPLSGN3 : 31|4@0+ (1,0) [0|0] "" XXX - SG_ SPLSGN4 : 27|4@0+ (1,0) [0|0] "" XXX - SG_ TSGN4 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY4 : 44|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT4 : 41|2@0+ (1,0) [0|0] "" XXX - SG_ DPSGNREQ : 54|1@0+ (1,0) [0|0] "" XXX - SG_ SGNNUMP : 53|3@0+ (1,0) [0|0] "" XXX - SG_ SGNNUMA : 50|3@0+ (1,0) [0|0] "" XXX - SG_ SPDUNT : 63|2@0+ (1,0) [0|0] "" XXX - SG_ TSRWMSG : 61|2@0+ (1,0) [0|0] "" XXX - SG_ SYNCID2 : 59|4@0+ (1,0) [0|0] "" XXX - -BO_ 1163 RSA3: 8 FCM - SG_ TSREQPD : 7|1@0+ (1,0) [0|0] "" XXX - SG_ TSRMSW : 6|1@0+ (1,0) [0|0] "" XXX - SG_ OTSGNNTM : 5|2@0+ (1,0) [0|0] "" XXX - SG_ NTLVLSPD : 3|2@0+ (1,0) [0|0] "" XXX - SG_ OVSPNTM : 1|2@0+ (1,0) [0|0] "" XXX - SG_ OVSPVALL : 11|4@0+ (1,-5) [0|0] "" XXX - SG_ OVSPVALM : 19|4@0+ (1,-5) [0|0] "" XXX - SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX - SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" XXX - -BO_ 1571 CENTRAL_GATEWAY_UNIT: 8 CGW - SG_ DOOR_LOCK_FEEDBACK_LIGHT : 15|1@0+ (1,0) [0|0] "" XXX - SG_ KEYFOB_LOCKING_FEEDBACK_LIGHT : 61|1@0+ (1,0) [0|0] "" XXX - SG_ KEYFOB_UNLOCKING_FEEDBACK_LIGHT : 62|1@0+ (1,0) [0|0] "" XXX - -CM_ SG_ 36 ACCEL_Y "unit is tbd"; -CM_ SG_ 36 YAW_RATE "verify"; -CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; -CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; -CM_ SG_ 37 STEER_RATE "factor is tbd"; -CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; -CM_ SG_ 466 CRUISE_STATE "Active state is 8, if standstill is requested will switch to state 11(3 sec timer), after timer is elapsed will switch into state 7(standstill). If plus button was pressed - status 9, minus button pressed - status 10"; -CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isn't perfect"; -CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; -CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; -CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; -CM_ SG_ 608 STEER_OVERRIDE "set when driver torque exceeds a certain value"; -CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; -CM_ SG_ 643 COUNTER "only used on cars that use this msg for cruise control"; -CM_ SG_ 643 BRAKE_STATUS "only used on cars that use this msg for cruise control"; -CM_ SG_ 643 PRECOLLISION_ACTIVE "set 0.5s before any braking"; -CM_ SG_ 835 ACC_TYPE "if 2, car is likely to have a permanent low speed lockout. 1 is ok"; -CM_ SG_ 835 RADAR_DIRTY "Display Clean Radar Sensor message on HUD"; -CM_ SG_ 835 ACC_MALFUNCTION "display ACC fault on dash if set to 1"; -CM_ SG_ 835 ACC_CUT_IN "Display blinking yellow lead if set to 1"; -CM_ SG_ 835 DISTANCE "Display Distance Bars on HUD Permanently"; -CM_ SG_ 835 ALLOW_LONG_PRESS "Enable Toyota's factory set speed increment behaviour, available on both metrics cars and imperial unit cars"; -CM_ SG_ 835 PERMIT_BRAKING "Original ACC has this going high when a car in front is detected. In openpilot and before the PERMIT_BRAKING name, this was 'SET_ME_1' and is hardcoded to be high. Unsure if only informational or has an effect though existing usage in openpilot is to always set it to 1. Originally 'PMTBRKG' in the leaked toyota_2017_ref_pt.dbc file and name expansion speculated to be PerMiT BRaKinG."; -CM_ SG_ 835 ACCEL_CMD_ALT "Copy of main ACCEL_CMD, but across 8 bits instead of 16 bits like ACCEL_CMD. Unsure if only informational or has an effect. Likely informational as existing openpilot sets this to 0 and no loss of functionality observed. Originally 'AT_RAW' in leaked toyota_2017_ref_pt.dbc file."; -CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; -CM_ SG_ 951 BRAKE_LIGHTS_ACC "brake lights when ACC commands decel"; -CM_ SG_ 1041 PCS_INDICATOR "Pre-Collision System Indicator"; -CM_ SG_ 1041 PCS_SENSITIVITY "Pre-Collision System Sensitivity"; -CM_ SG_ 1042 SET_ME_1 "unclear what this is, but it's always 1 in drive traces"; -CM_ SG_ 1042 REPEATED_BEEPS "recommended for fcw and other important alerts"; -CM_ SG_ 1161 SPDVAL1 "Numbers 0-199 is displayed, 200-254 displays circle without number and 255 is for no limit."; -CM_ SG_ 1161 SYNCID1 "counter from 1 to f at 1 Hz"; -CM_ SG_ 1161 SPDVAL2 "conditional speed value 70"; -CM_ SG_ 1162 SGNNUMP "1 if SPDVAL1 is set, otherwise 0"; -CM_ SG_ 1162 SYNCID2 "counter from 1 to f at 1 Hz"; -CM_ SG_ 1163 TSREQPD "always 1"; -CM_ SG_ 1163 TSRMSW "always 1"; -CM_ SG_ 1163 OTSGNNTM "always 3"; -CM_ SG_ 1163 NTLVLSPD "always 3"; -CM_ SG_ 1163 OVSPNTM "always 3"; -CM_ SG_ 1163 OVSPVALL "-5 at start then 2 after 2 seconds"; -CM_ SG_ 1163 OVSPVALM "-5 at start then 5 after 2 seconds"; -CM_ SG_ 1163 OVSPVALH "-5 at start then 10 after 2 seconds"; -CM_ SG_ 1163 TSRSPU "always 1"; -CM_ SG_ 1553 ODOMETER "Unit is dependent upon units signal"; - -VAL_ 466 CRUISE_STATE 11 "timer_3sec" 10 "adaptive click down" 9 "adaptive click up" 8 "adaptive engaged" 7 "standstill" 6 "non-adaptive click up" 5 "non-adaptive click down" 4 "non-adaptive hold down" 3 "non-adaptive hold up" 2 "non-adaptive being engaged" 1 "non-adaptive engaged" 0 "off"; -VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok"; -VAL_ 614 STATE 3 "enabled" 1 "disabled"; -VAL_ 614 DIRECTION_CMD 3 "right" 2 "center" 1 "left"; -VAL_ 643 STATE 0 "normal" 1 "adaptive_cruise_control" 3 "emergency_braking"; -VAL_ 835 ACC_TYPE 2 "permanent low speed lockout" 1 "ok"; -VAL_ 835 ACC_MALFUNCTION 1 "faulted" 0 "ok"; -VAL_ 835 ACC_CUT_IN 1 "CUT-IN Detected" 0 "clear"; -VAL_ 835 ALLOW_LONG_PRESS 2 "set speed increase by 5 speed units regardless" 1 "set speed increase by 1 speed unit on short press, 5 speed units on long press"; -VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted"; -VAL_ 1041 PCS_INDICATOR 2 "PCS Faulted" 1 "PCS Turned Off By User" 0 "PCS Enabled"; -VAL_ 1041 PCS_SENSITIVITY 64 "high sensitivity" 128 "mid sensitivity" 192 "low sensitivity" 0 "off"; -VAL_ 1042 LDA_ALERT 3 "hold with continuous beep" 2 "LDA unavailable" 1 "hold" 0 "none"; -VAL_ 1042 BARRIERS 3 "both" 2 "right" 1 "left" 0 "none"; -VAL_ 1042 RIGHT_LINE 3 "orange" 2 "faded" 1 "solid" 0 "none"; -VAL_ 1042 LEFT_LINE 3 "orange" 2 "faded" 1 "solid" 0 "none"; -VAL_ 1553 UNITS 1 "km" 2 "miles"; -VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left"; -VAL_ 1161 TSGN1 1 "speed sign" 0 "none"; -VAL_ 1161 TSGN2 1 "speed sign" 0 "none"; -VAL_ 1161 SPLSGN2 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none"; -VAL_ 1162 TSGN3 0 "none" 1 "speed sign" 2 "0 unlimited" 7 "unlimited" 16 "highway" 17 "no highway" 18 "motorway" 19 "no motorway" 20 "in city" 21 "outside city" 22 "pedestrian area" 23 "no pedestrian area" 65 "no overtaking left" 66 "no overtaking right" 67 "overtaking allowed again" 81 "no right turn" 97 "stop" 105 "yield" 113 "stop" 114 "yield us" 129 "no entry" 138 "no entry tss2" 145 "do not enter"; -VAL_ 1162 SPLSGN3 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none"; - - - - -CM_ "Imported file _comma.dbc starts here"; -BO_ 359 STEERING_IPAS_COMMA: 8 IPAS - SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX - SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX - SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX - SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant"; - - BO_ 512 GAS_COMMAND: 6 EON - SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR - SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR - SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR - - BO_ 513 GAS_SENSOR: 6 INTERCEPTOR - SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON - SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON - SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON - - VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; - -BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX - SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX - -CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss"; - -BO_ 767 SDSU: 8 XXX - SG_ FD_BUTTON : 7|1@0+ (1,0) [0|1] "" XXX - -CM_ "BO_ SDSU: The sDSU is a modified DSU for use in TSS1 Toyotas. Learn more: https://github.com/wocsor/panda/tree/smart_dsu"; - -CM_ SG_ 767 FD_BUTTON "The follow distance button signal as forwarded by the sdsu"; - -CM_ "toyota_camry_hybrid_2018_pt.dbc starts here"; - - - -BO_ 295 GEAR_PACKET: 8 XXX - SG_ CAR_MOVEMENT : 39|8@0- (1,0) [0|255] "" XXX - SG_ COUNTER : 55|8@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - SG_ GEAR : 47|4@0+ (1,0) [0|15] "" XXX - -BO_ 550 BRAKE_MODULE: 8 XXX - SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|511] "" XXX - SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|511] "" XXX - SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|1] "" XXX - -BO_ 581 GAS_PEDAL: 8 XXX - SG_ GAS_PEDAL : 23|8@0+ (0.005,0) [0|1] "" XXX - -BO_ 608 STEER_TORQUE_SENSOR: 8 XXX - SG_ STEER_TORQUE_EPS : 47|16@0- (0.73,0) [-20000|20000] "" XXX - SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX - SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - SG_ STEER_ANGLE : 31|16@0- (0.0573,0) [-500|500] "" XXX - -BO_ 610 EPS_STATUS: 8 EPS - SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX - SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX - SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -CM_ SG_ 550 BRAKE_PRESSURE "seems prop to pedal force"; -CM_ SG_ 550 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; -CM_ SG_ 581 GAS_PEDAL "it seems slightly filtered"; -CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; -VAL_ 295 GEAR 0 "P" 1 "R" 2 "N" 3 "D" 4 "B"; -VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled"; -VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby"; diff --git a/opendbc/toyota_corolla_2017_pt_generated.dbc b/opendbc/toyota_corolla_2017_pt_generated.dbc deleted file mode 100644 index 5fa0e8399..000000000 --- a/opendbc/toyota_corolla_2017_pt_generated.dbc +++ /dev/null @@ -1,450 +0,0 @@ -CM_ "AUTOGENERATED FILE, DO NOT EDIT"; - - -CM_ "Imported file _toyota_2017.dbc starts here"; -VERSION "" - - -NS_ : - NS_DESC_ - CM_ - BA_DEF_ - BA_ - VAL_ - CAT_DEF_ - CAT_ - FILTER - BA_DEF_DEF_ - EV_DATA_ - ENVVAR_DATA_ - SGTYPE_ - SGTYPE_VAL_ - BA_DEF_SGTYPE_ - BA_SGTYPE_ - SIG_TYPE_REF_ - VAL_TABLE_ - SIG_GROUP_ - SIG_VALTYPE_ - SIGTYPE_VALTYPE_ - BO_TX_BU_ - BA_DEF_REL_ - BA_REL_ - BA_DEF_DEF_REL_ - BU_SG_REL_ - BU_EV_REL_ - BU_BO_REL_ - SG_MUL_VAL_ - -BS_: - -BU_: XXX DSU HCU EPS IPAS CGW - -BO_ 36 KINEMATICS: 8 XXX - SG_ ACCEL_Y : 33|10@0+ (0.03589,-18.375) [0|65535] "m/s^2" XXX - SG_ YAW_RATE : 1|10@0+ (0.244,-125) [0|65535] "deg/sec" XXX - SG_ STEERING_TORQUE : 17|10@0+ (1,-512) [0|65535] "" XXX - -BO_ 37 STEER_ANGLE_SENSOR: 8 XXX - SG_ STEER_ANGLE : 3|12@0- (1.5,0) [-500|500] "deg" XXX - SG_ STEER_FRACTION : 39|4@0- (0.1,0) [-0.7|0.7] "deg" XXX - SG_ STEER_RATE : 35|12@0- (1,0) [-2000|2000] "deg/s" XXX - -BO_ 166 BRAKE: 8 XXX - SG_ BRAKE_AMOUNT : 7|8@0+ (1,0) [0|255] "" XXX - SG_ BRAKE_PEDAL : 23|8@0+ (1,0) [0|255] "" XXX - -BO_ 170 WHEEL_SPEEDS: 8 XXX - SG_ WHEEL_SPEED_FR : 7|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_FL : 23|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_RR : 39|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_RL : 55|16@0+ (0.01,-67.67) [0|250] "kph" XXX - -BO_ 180 SPEED: 8 XXX - SG_ ENCODER : 39|8@0+ (1,0) [0|255] "" XXX - SG_ SPEED : 47|16@0+ (0.01,0) [0|250] "kph" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 353 DSU_SPEED: 7 XXX - SG_ FORWARD_SPEED : 15|16@0- (0.00390625,-30) [0|255] "kph" XXX - -BO_ 452 ENGINE_RPM: 8 CGW - SG_ RPM : 7|16@0- (0.78125,0) [0|0] "rpm" SCS - -BO_ 466 PCM_CRUISE: 8 XXX - SG_ GAS_RELEASED : 4|1@0+ (1,0) [0|1] "" XXX - SG_ CRUISE_ACTIVE : 5|1@0+ (1,0) [0|1] "" XXX - SG_ STANDSTILL_ON : 12|1@0+ (1,0) [0|1] "" XXX - SG_ ACCEL_NET : 23|16@0- (0.001,0) [-20|20] "m/s2" XXX - SG_ CRUISE_STATE : 55|4@0+ (1,0) [0|15] "" XXX - SG_ CANCEL_REQ : 49|1@1+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 467 PCM_CRUISE_2: 8 XXX - SG_ MAIN_ON : 15|1@0+ (1,0) [0|1] "" XXX - SG_ LOW_SPEED_LOCKOUT : 14|2@0+ (1,0) [0|3] "kph" XXX - SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "kph" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 552 ACCELEROMETER: 8 XXX - SG_ ACCEL_Z : 22|15@0- (1,0) [0|32767] "" XXX - SG_ ACCEL_X : 6|15@0- (0.001,0) [-20|20] "m/s2" XXX - -BO_ 560 BRAKE_MODULE2: 7 XXX - SG_ BRAKE_PRESSED : 26|1@0+ (1,0) [0|1] "" XXX - -BO_ 614 STEERING_IPAS: 8 IPAS - SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX - SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX - SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX - SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 643 PRE_COLLISION: 7 DSU - SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 15|8@0+ (1,0) [0|255] "" XXX - SG_ FORCE : 23|16@0- (2,0) [0|255] "N" XXX - SG_ SET_ME_X002 : 33|8@0+ (1,0) [0|3] "" XXX - SG_ BRAKE_STATUS : 39|3@0+ (1,0) [0|255] "" XXX - SG_ STATE : 36|3@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X003 : 40|1@0+ (1,0) [0|1] "" XXX - SG_ PRECOLLISION_ACTIVE : 41|1@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 55|8@0+ (1,0) [0|255] "" XXX - -BO_ 740 STEERING_LKA: 5 XXX - SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX - SG_ STEER_REQUEST : 0|1@0+ (1,0) [0|1] "" XXX - SG_ COUNTER : 6|6@0+ (1,0) [0|63] "" XXX - SG_ SET_ME_1 : 7|1@0+ (1,0) [0|1] "" XXX - SG_ STEER_TORQUE_CMD : 15|16@0- (1,0) [0|65535] "" XXX - SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX - -BO_ 742 LEAD_INFO: 8 DSU - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" HCU - SG_ LEAD_REL_SPEED : 23|12@0- (0.025,0) [-100|100] "m/s" HCU - SG_ LEAD_LONG_DIST : 7|13@0+ (0.05,0) [0|300] "m" HCU - -BO_ 835 ACC_CONTROL: 8 DSU - SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU - SG_ ACC_MALFUNCTION : 18|1@0+ (1,0) [0|0] "" XXX - SG_ ACC_CUT_IN : 25|1@0+ (1,0) [0|1] "" XXX - SG_ ALLOW_LONG_PRESS : 17|2@0+ (1,0) [0|2] "" XXX - SG_ ACC_TYPE : 23|2@0+ (1,0) [0|3] "" HCU - SG_ DISTANCE : 20|1@0+ (1,0) [0|1] "" XXX - SG_ MINI_CAR : 21|1@0+ (1,0) [0|1] "" XXX - SG_ PERMIT_BRAKING : 30|1@0+ (1,0) [0|1] "" HCU - SG_ RELEASE_STANDSTILL : 31|1@0+ (1,0) [0|1] "" HCU - SG_ CANCEL_REQ : 24|1@0+ (1,0) [0|1] "" HCU - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - SG_ ACCEL_CMD_ALT : 47|8@0- (0.05,0) [0|0] "m/s^2" XXX - SG_ RADAR_DIRTY : 19|1@0+ (1,0) [0|1] "" XXX - -BO_ 836 PRE_COLLISION_2: 8 DSU - SG_ CHECKSUM : 63|8@0+ (1,0) [0|0] "" XXX - -BO_ 869 DSU_CRUISE : 7 DSU - SG_ RES_BTN : 3|1@0+ (1,0) [0|0] "" XXX - SG_ SET_BTN : 2|1@0+ (1,0) [0|0] "" XXX - SG_ CANCEL_BTN : 1|1@0+ (1,0) [0|0] "" XXX - SG_ MAIN_ON : 0|1@0+ (1,0) [0|0] "" XXX - SG_ SET_SPEED : 15|8@0+ (1,0) [0|0] "km/h" XXX - SG_ CRUISE_REQUEST : 31|8@0+ (100,-12800) [0|0] "N" XXX - SG_ LEAD_DISTANCE : 39|8@0+ (1,0) [0|0] "m" XXX - -BO_ 921 PCM_CRUISE_SM: 8 XXX - SG_ MAIN_ON : 4|1@0+ (1,0) [0|1] "" XXX - SG_ CRUISE_CONTROL_STATE : 11|4@0+ (1,0) [0|15] "" XXX - SG_ DISTANCE_LINES : 14|2@0+ (1,0) [0|3] "" XXX - SG_ UI_SET_SPEED : 31|8@0+ (1,0) [0|255] "" XXX - -BO_ 951 ESP_CONTROL: 8 ESP - SG_ TC_DISABLED : 13|1@0+ (1,0) [0|1] "" XXX - SG_ VSC_DISABLED : 12|2@0+ (1,0) [0|1] "" XXX - SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" XXX - SG_ BRAKE_HOLD_ENABLED : 33|1@1+ (1,0) [0|1] "" XXX - SG_ BRAKE_HOLD_ACTIVE : 36|1@0+ (1,0) [0|1] "" XXX - -BO_ 1020 SOLAR_SENSOR: 8 XXX - SG_ LUX_SENSOR : 55|13@0+ (1,0) [0|0] "" XXX - -BO_ 1041 ACC_HUD: 8 DSU - SG_ PCS_INDICATOR : 7|2@0+ (1,0) [0|3] "" XXX - SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X20 : 15|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X10 : 39|8@0+ (1,0) [0|1] "" XXX - SG_ PCS_OFF : 40|1@0+ (1,0) [0|0] "" XXX - SG_ PCS_SENSITIVITY : 55|8@0+ (1,0) [0|1] "" XXX - -BO_ 1042 LKAS_HUD: 8 XXX - SG_ BARRIERS : 1|2@0+ (1,0) [0|3] "" XXX - SG_ RIGHT_LINE : 3|2@0+ (1,0) [0|3] "" XXX - SG_ LEFT_LINE : 5|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X01 : 7|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X01_2 : 11|2@0+ (1,0) [0|3] "" XXX - SG_ LDA_ALERT : 9|2@0+ (1,0) [0|3] "" XXX - SG_ TWO_BEEPS : 12|1@0+ (1,0) [0|1] "" XXX - SG_ ADJUSTING_CAMERA : 13|1@0+ (1,0) [0|1] "" XXX - SG_ LDA_MALFUNCTION : 15|1@0+ (1,0) [0|1] "" XXX - SG_ REPEATED_BEEPS : 32|1@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X0C : 23|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X2C : 47|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X38 : 55|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X02 : 63|8@0+ (1,0) [0|1] "" XXX - -BO_ 1043 TIME : 8 CGW - SG_ YEAR : 7|8@0+ (1,0) [0|0] "year" XXX - SG_ MONTH : 15|8@0+ (1,0) [0|0] "month" XXX - SG_ DAY : 23|8@0+ (1,0) [0|0] "day" XXX - SG_ HOUR : 31|8@0+ (1,0) [0|0] "hour" XXX - SG_ MINUTE : 39|8@0+ (1,0) [0|0] "minute" XXX - SG_ GMT_DIFF : 55|1@0+ (1,0) [0|0] "" XXX - SG_ GMTDIFF_HOURS : 54|4@0+ (1,0) [0|0] "hours" XXX - SG_ GMTDIFF_MINUTES : 50|6@0+ (1,0) [0|0] "minutes" XXX - SG_ SUMMER : 60|1@0+ (1,0) [0|0] "" XXX - -BO_ 1408 VIN_PART_1: 8 CGW - SG_ VIN_1 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_2 : 15|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_3 : 23|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_4 : 31|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_5 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_6 : 47|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_7 : 55|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_8 : 63|8@0+ (1,0) [0|0] "" XXX - -BO_ 1409 VIN_PART_2: 8 CGW - SG_ VIN_9 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_10 : 15|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_11 : 23|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_12 : 31|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_13 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_14 : 47|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_15 : 55|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_16 : 63|8@0+ (1,0) [0|0] "" XXX - -BO_ 1410 VIN_PART_3: 8 CGW - SG_ VIN_17 : 7|8@0+ (1,0) [0|0] "" XXX - -BO_ 1553 UI_SETTING: 8 XXX - SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX - SG_ ODOMETER : 43|20@0+ (1,0) [0|1048575] "" XXX - -BO_ 1556 STEERING_LEVERS: 8 XXX - SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX - SG_ HAZARD_LIGHT : 27|1@0+ (1,0) [0|1] "" XXX - -BO_ 1568 SEATS_DOORS: 8 XXX - SG_ METER_DIMMED : 38|1@0+ (1,0) [0|1] "" XXX - SG_ PARKING_BRAKE : 60|1@0+ (1,0) [0|1] "" XXX - SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_RR : 43|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_FR : 44|1@0+ (1,0) [0|1] "" XXX - -BO_ 1570 LIGHT_STALK: 8 SCM - SG_ AUTO_HIGH_BEAM : 37|1@0+ (1,0) [0|1] "" XXX - SG_ FRONT_FOG : 27|1@0+ (1,0) [0|1] "" XXX - SG_ PARKING_LIGHT : 28|1@0+ (1,0) [0|1] "" XXX - SG_ LOW_BEAM : 29|1@0+ (1,0) [0|1] "" XXX - SG_ HIGH_BEAM : 30|1@0+ (1,0) [0|1] "" XXX - SG_ DAYTIME_RUNNING_LIGHT : 31|1@0+ (1,0) [0|1] "" XXX - -BO_ 1161 RSA1: 8 FCM - SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY1 : 12|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT1 : 9|2@0+ (1,0) [0|0] "" XXX - SG_ SPDVAL1 : 23|8@0+ (1,0) [0|0] "kph" XXX - SG_ SPLSGN1 : 31|4@0+ (1,0) [0|0] "" XXX - SG_ SPLSGN2 : 27|4@0+ (1,0) [0|0] "" XXX - SG_ TSGN2 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY2 : 44|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT2 : 41|2@0+ (1,0) [0|0] "" XXX - SG_ SPDVAL2 : 55|8@0+ (1,0) [0|0] "" XXX - SG_ BZRRQ_P : 63|2@0+ (1,0) [0|0] "" XXX - SG_ BZRRQ_A : 61|2@0+ (1,0) [0|0] "" XXX - SG_ SYNCID1 : 59|4@0+ (1,0) [0|0] "" XXX - -BO_ 1162 RSA2: 8 FCM - SG_ TSGN3 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY3 : 12|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT3 : 9|2@0+ (1,0) [0|0] "" XXX - SG_ SPLSGN3 : 31|4@0+ (1,0) [0|0] "" XXX - SG_ SPLSGN4 : 27|4@0+ (1,0) [0|0] "" XXX - SG_ TSGN4 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY4 : 44|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT4 : 41|2@0+ (1,0) [0|0] "" XXX - SG_ DPSGNREQ : 54|1@0+ (1,0) [0|0] "" XXX - SG_ SGNNUMP : 53|3@0+ (1,0) [0|0] "" XXX - SG_ SGNNUMA : 50|3@0+ (1,0) [0|0] "" XXX - SG_ SPDUNT : 63|2@0+ (1,0) [0|0] "" XXX - SG_ TSRWMSG : 61|2@0+ (1,0) [0|0] "" XXX - SG_ SYNCID2 : 59|4@0+ (1,0) [0|0] "" XXX - -BO_ 1163 RSA3: 8 FCM - SG_ TSREQPD : 7|1@0+ (1,0) [0|0] "" XXX - SG_ TSRMSW : 6|1@0+ (1,0) [0|0] "" XXX - SG_ OTSGNNTM : 5|2@0+ (1,0) [0|0] "" XXX - SG_ NTLVLSPD : 3|2@0+ (1,0) [0|0] "" XXX - SG_ OVSPNTM : 1|2@0+ (1,0) [0|0] "" XXX - SG_ OVSPVALL : 11|4@0+ (1,-5) [0|0] "" XXX - SG_ OVSPVALM : 19|4@0+ (1,-5) [0|0] "" XXX - SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX - SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" XXX - -BO_ 1571 CENTRAL_GATEWAY_UNIT: 8 CGW - SG_ DOOR_LOCK_FEEDBACK_LIGHT : 15|1@0+ (1,0) [0|0] "" XXX - SG_ KEYFOB_LOCKING_FEEDBACK_LIGHT : 61|1@0+ (1,0) [0|0] "" XXX - SG_ KEYFOB_UNLOCKING_FEEDBACK_LIGHT : 62|1@0+ (1,0) [0|0] "" XXX - -CM_ SG_ 36 ACCEL_Y "unit is tbd"; -CM_ SG_ 36 YAW_RATE "verify"; -CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; -CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; -CM_ SG_ 37 STEER_RATE "factor is tbd"; -CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; -CM_ SG_ 466 CRUISE_STATE "Active state is 8, if standstill is requested will switch to state 11(3 sec timer), after timer is elapsed will switch into state 7(standstill). If plus button was pressed - status 9, minus button pressed - status 10"; -CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isn't perfect"; -CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; -CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; -CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; -CM_ SG_ 608 STEER_OVERRIDE "set when driver torque exceeds a certain value"; -CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; -CM_ SG_ 643 COUNTER "only used on cars that use this msg for cruise control"; -CM_ SG_ 643 BRAKE_STATUS "only used on cars that use this msg for cruise control"; -CM_ SG_ 643 PRECOLLISION_ACTIVE "set 0.5s before any braking"; -CM_ SG_ 835 ACC_TYPE "if 2, car is likely to have a permanent low speed lockout. 1 is ok"; -CM_ SG_ 835 RADAR_DIRTY "Display Clean Radar Sensor message on HUD"; -CM_ SG_ 835 ACC_MALFUNCTION "display ACC fault on dash if set to 1"; -CM_ SG_ 835 ACC_CUT_IN "Display blinking yellow lead if set to 1"; -CM_ SG_ 835 DISTANCE "Display Distance Bars on HUD Permanently"; -CM_ SG_ 835 ALLOW_LONG_PRESS "Enable Toyota's factory set speed increment behaviour, available on both metrics cars and imperial unit cars"; -CM_ SG_ 835 PERMIT_BRAKING "Original ACC has this going high when a car in front is detected. In openpilot and before the PERMIT_BRAKING name, this was 'SET_ME_1' and is hardcoded to be high. Unsure if only informational or has an effect though existing usage in openpilot is to always set it to 1. Originally 'PMTBRKG' in the leaked toyota_2017_ref_pt.dbc file and name expansion speculated to be PerMiT BRaKinG."; -CM_ SG_ 835 ACCEL_CMD_ALT "Copy of main ACCEL_CMD, but across 8 bits instead of 16 bits like ACCEL_CMD. Unsure if only informational or has an effect. Likely informational as existing openpilot sets this to 0 and no loss of functionality observed. Originally 'AT_RAW' in leaked toyota_2017_ref_pt.dbc file."; -CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; -CM_ SG_ 951 BRAKE_LIGHTS_ACC "brake lights when ACC commands decel"; -CM_ SG_ 1041 PCS_INDICATOR "Pre-Collision System Indicator"; -CM_ SG_ 1041 PCS_SENSITIVITY "Pre-Collision System Sensitivity"; -CM_ SG_ 1042 SET_ME_1 "unclear what this is, but it's always 1 in drive traces"; -CM_ SG_ 1042 REPEATED_BEEPS "recommended for fcw and other important alerts"; -CM_ SG_ 1161 SPDVAL1 "Numbers 0-199 is displayed, 200-254 displays circle without number and 255 is for no limit."; -CM_ SG_ 1161 SYNCID1 "counter from 1 to f at 1 Hz"; -CM_ SG_ 1161 SPDVAL2 "conditional speed value 70"; -CM_ SG_ 1162 SGNNUMP "1 if SPDVAL1 is set, otherwise 0"; -CM_ SG_ 1162 SYNCID2 "counter from 1 to f at 1 Hz"; -CM_ SG_ 1163 TSREQPD "always 1"; -CM_ SG_ 1163 TSRMSW "always 1"; -CM_ SG_ 1163 OTSGNNTM "always 3"; -CM_ SG_ 1163 NTLVLSPD "always 3"; -CM_ SG_ 1163 OVSPNTM "always 3"; -CM_ SG_ 1163 OVSPVALL "-5 at start then 2 after 2 seconds"; -CM_ SG_ 1163 OVSPVALM "-5 at start then 5 after 2 seconds"; -CM_ SG_ 1163 OVSPVALH "-5 at start then 10 after 2 seconds"; -CM_ SG_ 1163 TSRSPU "always 1"; -CM_ SG_ 1553 ODOMETER "Unit is dependent upon units signal"; - -VAL_ 466 CRUISE_STATE 11 "timer_3sec" 10 "adaptive click down" 9 "adaptive click up" 8 "adaptive engaged" 7 "standstill" 6 "non-adaptive click up" 5 "non-adaptive click down" 4 "non-adaptive hold down" 3 "non-adaptive hold up" 2 "non-adaptive being engaged" 1 "non-adaptive engaged" 0 "off"; -VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok"; -VAL_ 614 STATE 3 "enabled" 1 "disabled"; -VAL_ 614 DIRECTION_CMD 3 "right" 2 "center" 1 "left"; -VAL_ 643 STATE 0 "normal" 1 "adaptive_cruise_control" 3 "emergency_braking"; -VAL_ 835 ACC_TYPE 2 "permanent low speed lockout" 1 "ok"; -VAL_ 835 ACC_MALFUNCTION 1 "faulted" 0 "ok"; -VAL_ 835 ACC_CUT_IN 1 "CUT-IN Detected" 0 "clear"; -VAL_ 835 ALLOW_LONG_PRESS 2 "set speed increase by 5 speed units regardless" 1 "set speed increase by 1 speed unit on short press, 5 speed units on long press"; -VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted"; -VAL_ 1041 PCS_INDICATOR 2 "PCS Faulted" 1 "PCS Turned Off By User" 0 "PCS Enabled"; -VAL_ 1041 PCS_SENSITIVITY 64 "high sensitivity" 128 "mid sensitivity" 192 "low sensitivity" 0 "off"; -VAL_ 1042 LDA_ALERT 3 "hold with continuous beep" 2 "LDA unavailable" 1 "hold" 0 "none"; -VAL_ 1042 BARRIERS 3 "both" 2 "right" 1 "left" 0 "none"; -VAL_ 1042 RIGHT_LINE 3 "orange" 2 "faded" 1 "solid" 0 "none"; -VAL_ 1042 LEFT_LINE 3 "orange" 2 "faded" 1 "solid" 0 "none"; -VAL_ 1553 UNITS 1 "km" 2 "miles"; -VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left"; -VAL_ 1161 TSGN1 1 "speed sign" 0 "none"; -VAL_ 1161 TSGN2 1 "speed sign" 0 "none"; -VAL_ 1161 SPLSGN2 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none"; -VAL_ 1162 TSGN3 0 "none" 1 "speed sign" 2 "0 unlimited" 7 "unlimited" 16 "highway" 17 "no highway" 18 "motorway" 19 "no motorway" 20 "in city" 21 "outside city" 22 "pedestrian area" 23 "no pedestrian area" 65 "no overtaking left" 66 "no overtaking right" 67 "overtaking allowed again" 81 "no right turn" 97 "stop" 105 "yield" 113 "stop" 114 "yield us" 129 "no entry" 138 "no entry tss2" 145 "do not enter"; -VAL_ 1162 SPLSGN3 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none"; - - - - -CM_ "Imported file _comma.dbc starts here"; -BO_ 359 STEERING_IPAS_COMMA: 8 IPAS - SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX - SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX - SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX - SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant"; - - BO_ 512 GAS_COMMAND: 6 EON - SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR - SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR - SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR - - BO_ 513 GAS_SENSOR: 6 INTERCEPTOR - SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON - SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON - SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON - - VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; - -BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX - SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX - -CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss"; - -BO_ 767 SDSU: 8 XXX - SG_ FD_BUTTON : 7|1@0+ (1,0) [0|1] "" XXX - -CM_ "BO_ SDSU: The sDSU is a modified DSU for use in TSS1 Toyotas. Learn more: https://github.com/wocsor/panda/tree/smart_dsu"; - -CM_ SG_ 767 FD_BUTTON "The follow distance button signal as forwarded by the sdsu"; - -CM_ "toyota_corolla_2017_pt.dbc starts here"; - - - -BO_ 548 BRAKE_MODULE: 8 XXX - SG_ BRAKE_PRESSURE : 43|12@0+ (1,0) [0|4047] "" XXX - SG_ BRAKE_PRESSED : 5|1@0+ (1,0) [0|1] "" XXX - -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 - -BO_ 608 STEER_TORQUE_SENSOR: 8 XXX - SG_ STEER_TORQUE_EPS : 47|16@0- (0.88,0) [-20000|20000] "" XXX - SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX - SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - SG_ STEER_ANGLE : 31|16@0- (0.0573,0) [-500|500] "" XXX - -BO_ 610 EPS_STATUS: 5 EPS - SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX - SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX - SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX - -BO_ 956 GEAR_PACKET: 8 XXX - SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX - SG_ SPORT_ON : 3|1@0+ (1,0) [0|1] "" XXX - -CM_ SG_ 548 BRAKE_PRESSURE "seems prop to pedal force"; -CM_ SG_ 548 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; -CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; -VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; -VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled"; -VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby"; diff --git a/opendbc/toyota_highlander_2017_pt_generated.dbc b/opendbc/toyota_highlander_2017_pt_generated.dbc deleted file mode 100644 index 6745ef9a0..000000000 --- a/opendbc/toyota_highlander_2017_pt_generated.dbc +++ /dev/null @@ -1,450 +0,0 @@ -CM_ "AUTOGENERATED FILE, DO NOT EDIT"; - - -CM_ "Imported file _toyota_2017.dbc starts here"; -VERSION "" - - -NS_ : - NS_DESC_ - CM_ - BA_DEF_ - BA_ - VAL_ - CAT_DEF_ - CAT_ - FILTER - BA_DEF_DEF_ - EV_DATA_ - ENVVAR_DATA_ - SGTYPE_ - SGTYPE_VAL_ - BA_DEF_SGTYPE_ - BA_SGTYPE_ - SIG_TYPE_REF_ - VAL_TABLE_ - SIG_GROUP_ - SIG_VALTYPE_ - SIGTYPE_VALTYPE_ - BO_TX_BU_ - BA_DEF_REL_ - BA_REL_ - BA_DEF_DEF_REL_ - BU_SG_REL_ - BU_EV_REL_ - BU_BO_REL_ - SG_MUL_VAL_ - -BS_: - -BU_: XXX DSU HCU EPS IPAS CGW - -BO_ 36 KINEMATICS: 8 XXX - SG_ ACCEL_Y : 33|10@0+ (0.03589,-18.375) [0|65535] "m/s^2" XXX - SG_ YAW_RATE : 1|10@0+ (0.244,-125) [0|65535] "deg/sec" XXX - SG_ STEERING_TORQUE : 17|10@0+ (1,-512) [0|65535] "" XXX - -BO_ 37 STEER_ANGLE_SENSOR: 8 XXX - SG_ STEER_ANGLE : 3|12@0- (1.5,0) [-500|500] "deg" XXX - SG_ STEER_FRACTION : 39|4@0- (0.1,0) [-0.7|0.7] "deg" XXX - SG_ STEER_RATE : 35|12@0- (1,0) [-2000|2000] "deg/s" XXX - -BO_ 166 BRAKE: 8 XXX - SG_ BRAKE_AMOUNT : 7|8@0+ (1,0) [0|255] "" XXX - SG_ BRAKE_PEDAL : 23|8@0+ (1,0) [0|255] "" XXX - -BO_ 170 WHEEL_SPEEDS: 8 XXX - SG_ WHEEL_SPEED_FR : 7|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_FL : 23|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_RR : 39|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_RL : 55|16@0+ (0.01,-67.67) [0|250] "kph" XXX - -BO_ 180 SPEED: 8 XXX - SG_ ENCODER : 39|8@0+ (1,0) [0|255] "" XXX - SG_ SPEED : 47|16@0+ (0.01,0) [0|250] "kph" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 353 DSU_SPEED: 7 XXX - SG_ FORWARD_SPEED : 15|16@0- (0.00390625,-30) [0|255] "kph" XXX - -BO_ 452 ENGINE_RPM: 8 CGW - SG_ RPM : 7|16@0- (0.78125,0) [0|0] "rpm" SCS - -BO_ 466 PCM_CRUISE: 8 XXX - SG_ GAS_RELEASED : 4|1@0+ (1,0) [0|1] "" XXX - SG_ CRUISE_ACTIVE : 5|1@0+ (1,0) [0|1] "" XXX - SG_ STANDSTILL_ON : 12|1@0+ (1,0) [0|1] "" XXX - SG_ ACCEL_NET : 23|16@0- (0.001,0) [-20|20] "m/s2" XXX - SG_ CRUISE_STATE : 55|4@0+ (1,0) [0|15] "" XXX - SG_ CANCEL_REQ : 49|1@1+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 467 PCM_CRUISE_2: 8 XXX - SG_ MAIN_ON : 15|1@0+ (1,0) [0|1] "" XXX - SG_ LOW_SPEED_LOCKOUT : 14|2@0+ (1,0) [0|3] "kph" XXX - SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "kph" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 552 ACCELEROMETER: 8 XXX - SG_ ACCEL_Z : 22|15@0- (1,0) [0|32767] "" XXX - SG_ ACCEL_X : 6|15@0- (0.001,0) [-20|20] "m/s2" XXX - -BO_ 560 BRAKE_MODULE2: 7 XXX - SG_ BRAKE_PRESSED : 26|1@0+ (1,0) [0|1] "" XXX - -BO_ 614 STEERING_IPAS: 8 IPAS - SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX - SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX - SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX - SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 643 PRE_COLLISION: 7 DSU - SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 15|8@0+ (1,0) [0|255] "" XXX - SG_ FORCE : 23|16@0- (2,0) [0|255] "N" XXX - SG_ SET_ME_X002 : 33|8@0+ (1,0) [0|3] "" XXX - SG_ BRAKE_STATUS : 39|3@0+ (1,0) [0|255] "" XXX - SG_ STATE : 36|3@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X003 : 40|1@0+ (1,0) [0|1] "" XXX - SG_ PRECOLLISION_ACTIVE : 41|1@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 55|8@0+ (1,0) [0|255] "" XXX - -BO_ 740 STEERING_LKA: 5 XXX - SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX - SG_ STEER_REQUEST : 0|1@0+ (1,0) [0|1] "" XXX - SG_ COUNTER : 6|6@0+ (1,0) [0|63] "" XXX - SG_ SET_ME_1 : 7|1@0+ (1,0) [0|1] "" XXX - SG_ STEER_TORQUE_CMD : 15|16@0- (1,0) [0|65535] "" XXX - SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX - -BO_ 742 LEAD_INFO: 8 DSU - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" HCU - SG_ LEAD_REL_SPEED : 23|12@0- (0.025,0) [-100|100] "m/s" HCU - SG_ LEAD_LONG_DIST : 7|13@0+ (0.05,0) [0|300] "m" HCU - -BO_ 835 ACC_CONTROL: 8 DSU - SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU - SG_ ACC_MALFUNCTION : 18|1@0+ (1,0) [0|0] "" XXX - SG_ ACC_CUT_IN : 25|1@0+ (1,0) [0|1] "" XXX - SG_ ALLOW_LONG_PRESS : 17|2@0+ (1,0) [0|2] "" XXX - SG_ ACC_TYPE : 23|2@0+ (1,0) [0|3] "" HCU - SG_ DISTANCE : 20|1@0+ (1,0) [0|1] "" XXX - SG_ MINI_CAR : 21|1@0+ (1,0) [0|1] "" XXX - SG_ PERMIT_BRAKING : 30|1@0+ (1,0) [0|1] "" HCU - SG_ RELEASE_STANDSTILL : 31|1@0+ (1,0) [0|1] "" HCU - SG_ CANCEL_REQ : 24|1@0+ (1,0) [0|1] "" HCU - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - SG_ ACCEL_CMD_ALT : 47|8@0- (0.05,0) [0|0] "m/s^2" XXX - SG_ RADAR_DIRTY : 19|1@0+ (1,0) [0|1] "" XXX - -BO_ 836 PRE_COLLISION_2: 8 DSU - SG_ CHECKSUM : 63|8@0+ (1,0) [0|0] "" XXX - -BO_ 869 DSU_CRUISE : 7 DSU - SG_ RES_BTN : 3|1@0+ (1,0) [0|0] "" XXX - SG_ SET_BTN : 2|1@0+ (1,0) [0|0] "" XXX - SG_ CANCEL_BTN : 1|1@0+ (1,0) [0|0] "" XXX - SG_ MAIN_ON : 0|1@0+ (1,0) [0|0] "" XXX - SG_ SET_SPEED : 15|8@0+ (1,0) [0|0] "km/h" XXX - SG_ CRUISE_REQUEST : 31|8@0+ (100,-12800) [0|0] "N" XXX - SG_ LEAD_DISTANCE : 39|8@0+ (1,0) [0|0] "m" XXX - -BO_ 921 PCM_CRUISE_SM: 8 XXX - SG_ MAIN_ON : 4|1@0+ (1,0) [0|1] "" XXX - SG_ CRUISE_CONTROL_STATE : 11|4@0+ (1,0) [0|15] "" XXX - SG_ DISTANCE_LINES : 14|2@0+ (1,0) [0|3] "" XXX - SG_ UI_SET_SPEED : 31|8@0+ (1,0) [0|255] "" XXX - -BO_ 951 ESP_CONTROL: 8 ESP - SG_ TC_DISABLED : 13|1@0+ (1,0) [0|1] "" XXX - SG_ VSC_DISABLED : 12|2@0+ (1,0) [0|1] "" XXX - SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" XXX - SG_ BRAKE_HOLD_ENABLED : 33|1@1+ (1,0) [0|1] "" XXX - SG_ BRAKE_HOLD_ACTIVE : 36|1@0+ (1,0) [0|1] "" XXX - -BO_ 1020 SOLAR_SENSOR: 8 XXX - SG_ LUX_SENSOR : 55|13@0+ (1,0) [0|0] "" XXX - -BO_ 1041 ACC_HUD: 8 DSU - SG_ PCS_INDICATOR : 7|2@0+ (1,0) [0|3] "" XXX - SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X20 : 15|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X10 : 39|8@0+ (1,0) [0|1] "" XXX - SG_ PCS_OFF : 40|1@0+ (1,0) [0|0] "" XXX - SG_ PCS_SENSITIVITY : 55|8@0+ (1,0) [0|1] "" XXX - -BO_ 1042 LKAS_HUD: 8 XXX - SG_ BARRIERS : 1|2@0+ (1,0) [0|3] "" XXX - SG_ RIGHT_LINE : 3|2@0+ (1,0) [0|3] "" XXX - SG_ LEFT_LINE : 5|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X01 : 7|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X01_2 : 11|2@0+ (1,0) [0|3] "" XXX - SG_ LDA_ALERT : 9|2@0+ (1,0) [0|3] "" XXX - SG_ TWO_BEEPS : 12|1@0+ (1,0) [0|1] "" XXX - SG_ ADJUSTING_CAMERA : 13|1@0+ (1,0) [0|1] "" XXX - SG_ LDA_MALFUNCTION : 15|1@0+ (1,0) [0|1] "" XXX - SG_ REPEATED_BEEPS : 32|1@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X0C : 23|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X2C : 47|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X38 : 55|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X02 : 63|8@0+ (1,0) [0|1] "" XXX - -BO_ 1043 TIME : 8 CGW - SG_ YEAR : 7|8@0+ (1,0) [0|0] "year" XXX - SG_ MONTH : 15|8@0+ (1,0) [0|0] "month" XXX - SG_ DAY : 23|8@0+ (1,0) [0|0] "day" XXX - SG_ HOUR : 31|8@0+ (1,0) [0|0] "hour" XXX - SG_ MINUTE : 39|8@0+ (1,0) [0|0] "minute" XXX - SG_ GMT_DIFF : 55|1@0+ (1,0) [0|0] "" XXX - SG_ GMTDIFF_HOURS : 54|4@0+ (1,0) [0|0] "hours" XXX - SG_ GMTDIFF_MINUTES : 50|6@0+ (1,0) [0|0] "minutes" XXX - SG_ SUMMER : 60|1@0+ (1,0) [0|0] "" XXX - -BO_ 1408 VIN_PART_1: 8 CGW - SG_ VIN_1 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_2 : 15|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_3 : 23|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_4 : 31|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_5 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_6 : 47|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_7 : 55|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_8 : 63|8@0+ (1,0) [0|0] "" XXX - -BO_ 1409 VIN_PART_2: 8 CGW - SG_ VIN_9 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_10 : 15|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_11 : 23|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_12 : 31|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_13 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_14 : 47|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_15 : 55|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_16 : 63|8@0+ (1,0) [0|0] "" XXX - -BO_ 1410 VIN_PART_3: 8 CGW - SG_ VIN_17 : 7|8@0+ (1,0) [0|0] "" XXX - -BO_ 1553 UI_SETTING: 8 XXX - SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX - SG_ ODOMETER : 43|20@0+ (1,0) [0|1048575] "" XXX - -BO_ 1556 STEERING_LEVERS: 8 XXX - SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX - SG_ HAZARD_LIGHT : 27|1@0+ (1,0) [0|1] "" XXX - -BO_ 1568 SEATS_DOORS: 8 XXX - SG_ METER_DIMMED : 38|1@0+ (1,0) [0|1] "" XXX - SG_ PARKING_BRAKE : 60|1@0+ (1,0) [0|1] "" XXX - SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_RR : 43|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_FR : 44|1@0+ (1,0) [0|1] "" XXX - -BO_ 1570 LIGHT_STALK: 8 SCM - SG_ AUTO_HIGH_BEAM : 37|1@0+ (1,0) [0|1] "" XXX - SG_ FRONT_FOG : 27|1@0+ (1,0) [0|1] "" XXX - SG_ PARKING_LIGHT : 28|1@0+ (1,0) [0|1] "" XXX - SG_ LOW_BEAM : 29|1@0+ (1,0) [0|1] "" XXX - SG_ HIGH_BEAM : 30|1@0+ (1,0) [0|1] "" XXX - SG_ DAYTIME_RUNNING_LIGHT : 31|1@0+ (1,0) [0|1] "" XXX - -BO_ 1161 RSA1: 8 FCM - SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY1 : 12|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT1 : 9|2@0+ (1,0) [0|0] "" XXX - SG_ SPDVAL1 : 23|8@0+ (1,0) [0|0] "kph" XXX - SG_ SPLSGN1 : 31|4@0+ (1,0) [0|0] "" XXX - SG_ SPLSGN2 : 27|4@0+ (1,0) [0|0] "" XXX - SG_ TSGN2 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY2 : 44|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT2 : 41|2@0+ (1,0) [0|0] "" XXX - SG_ SPDVAL2 : 55|8@0+ (1,0) [0|0] "" XXX - SG_ BZRRQ_P : 63|2@0+ (1,0) [0|0] "" XXX - SG_ BZRRQ_A : 61|2@0+ (1,0) [0|0] "" XXX - SG_ SYNCID1 : 59|4@0+ (1,0) [0|0] "" XXX - -BO_ 1162 RSA2: 8 FCM - SG_ TSGN3 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY3 : 12|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT3 : 9|2@0+ (1,0) [0|0] "" XXX - SG_ SPLSGN3 : 31|4@0+ (1,0) [0|0] "" XXX - SG_ SPLSGN4 : 27|4@0+ (1,0) [0|0] "" XXX - SG_ TSGN4 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY4 : 44|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT4 : 41|2@0+ (1,0) [0|0] "" XXX - SG_ DPSGNREQ : 54|1@0+ (1,0) [0|0] "" XXX - SG_ SGNNUMP : 53|3@0+ (1,0) [0|0] "" XXX - SG_ SGNNUMA : 50|3@0+ (1,0) [0|0] "" XXX - SG_ SPDUNT : 63|2@0+ (1,0) [0|0] "" XXX - SG_ TSRWMSG : 61|2@0+ (1,0) [0|0] "" XXX - SG_ SYNCID2 : 59|4@0+ (1,0) [0|0] "" XXX - -BO_ 1163 RSA3: 8 FCM - SG_ TSREQPD : 7|1@0+ (1,0) [0|0] "" XXX - SG_ TSRMSW : 6|1@0+ (1,0) [0|0] "" XXX - SG_ OTSGNNTM : 5|2@0+ (1,0) [0|0] "" XXX - SG_ NTLVLSPD : 3|2@0+ (1,0) [0|0] "" XXX - SG_ OVSPNTM : 1|2@0+ (1,0) [0|0] "" XXX - SG_ OVSPVALL : 11|4@0+ (1,-5) [0|0] "" XXX - SG_ OVSPVALM : 19|4@0+ (1,-5) [0|0] "" XXX - SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX - SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" XXX - -BO_ 1571 CENTRAL_GATEWAY_UNIT: 8 CGW - SG_ DOOR_LOCK_FEEDBACK_LIGHT : 15|1@0+ (1,0) [0|0] "" XXX - SG_ KEYFOB_LOCKING_FEEDBACK_LIGHT : 61|1@0+ (1,0) [0|0] "" XXX - SG_ KEYFOB_UNLOCKING_FEEDBACK_LIGHT : 62|1@0+ (1,0) [0|0] "" XXX - -CM_ SG_ 36 ACCEL_Y "unit is tbd"; -CM_ SG_ 36 YAW_RATE "verify"; -CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; -CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; -CM_ SG_ 37 STEER_RATE "factor is tbd"; -CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; -CM_ SG_ 466 CRUISE_STATE "Active state is 8, if standstill is requested will switch to state 11(3 sec timer), after timer is elapsed will switch into state 7(standstill). If plus button was pressed - status 9, minus button pressed - status 10"; -CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isn't perfect"; -CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; -CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; -CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; -CM_ SG_ 608 STEER_OVERRIDE "set when driver torque exceeds a certain value"; -CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; -CM_ SG_ 643 COUNTER "only used on cars that use this msg for cruise control"; -CM_ SG_ 643 BRAKE_STATUS "only used on cars that use this msg for cruise control"; -CM_ SG_ 643 PRECOLLISION_ACTIVE "set 0.5s before any braking"; -CM_ SG_ 835 ACC_TYPE "if 2, car is likely to have a permanent low speed lockout. 1 is ok"; -CM_ SG_ 835 RADAR_DIRTY "Display Clean Radar Sensor message on HUD"; -CM_ SG_ 835 ACC_MALFUNCTION "display ACC fault on dash if set to 1"; -CM_ SG_ 835 ACC_CUT_IN "Display blinking yellow lead if set to 1"; -CM_ SG_ 835 DISTANCE "Display Distance Bars on HUD Permanently"; -CM_ SG_ 835 ALLOW_LONG_PRESS "Enable Toyota's factory set speed increment behaviour, available on both metrics cars and imperial unit cars"; -CM_ SG_ 835 PERMIT_BRAKING "Original ACC has this going high when a car in front is detected. In openpilot and before the PERMIT_BRAKING name, this was 'SET_ME_1' and is hardcoded to be high. Unsure if only informational or has an effect though existing usage in openpilot is to always set it to 1. Originally 'PMTBRKG' in the leaked toyota_2017_ref_pt.dbc file and name expansion speculated to be PerMiT BRaKinG."; -CM_ SG_ 835 ACCEL_CMD_ALT "Copy of main ACCEL_CMD, but across 8 bits instead of 16 bits like ACCEL_CMD. Unsure if only informational or has an effect. Likely informational as existing openpilot sets this to 0 and no loss of functionality observed. Originally 'AT_RAW' in leaked toyota_2017_ref_pt.dbc file."; -CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; -CM_ SG_ 951 BRAKE_LIGHTS_ACC "brake lights when ACC commands decel"; -CM_ SG_ 1041 PCS_INDICATOR "Pre-Collision System Indicator"; -CM_ SG_ 1041 PCS_SENSITIVITY "Pre-Collision System Sensitivity"; -CM_ SG_ 1042 SET_ME_1 "unclear what this is, but it's always 1 in drive traces"; -CM_ SG_ 1042 REPEATED_BEEPS "recommended for fcw and other important alerts"; -CM_ SG_ 1161 SPDVAL1 "Numbers 0-199 is displayed, 200-254 displays circle without number and 255 is for no limit."; -CM_ SG_ 1161 SYNCID1 "counter from 1 to f at 1 Hz"; -CM_ SG_ 1161 SPDVAL2 "conditional speed value 70"; -CM_ SG_ 1162 SGNNUMP "1 if SPDVAL1 is set, otherwise 0"; -CM_ SG_ 1162 SYNCID2 "counter from 1 to f at 1 Hz"; -CM_ SG_ 1163 TSREQPD "always 1"; -CM_ SG_ 1163 TSRMSW "always 1"; -CM_ SG_ 1163 OTSGNNTM "always 3"; -CM_ SG_ 1163 NTLVLSPD "always 3"; -CM_ SG_ 1163 OVSPNTM "always 3"; -CM_ SG_ 1163 OVSPVALL "-5 at start then 2 after 2 seconds"; -CM_ SG_ 1163 OVSPVALM "-5 at start then 5 after 2 seconds"; -CM_ SG_ 1163 OVSPVALH "-5 at start then 10 after 2 seconds"; -CM_ SG_ 1163 TSRSPU "always 1"; -CM_ SG_ 1553 ODOMETER "Unit is dependent upon units signal"; - -VAL_ 466 CRUISE_STATE 11 "timer_3sec" 10 "adaptive click down" 9 "adaptive click up" 8 "adaptive engaged" 7 "standstill" 6 "non-adaptive click up" 5 "non-adaptive click down" 4 "non-adaptive hold down" 3 "non-adaptive hold up" 2 "non-adaptive being engaged" 1 "non-adaptive engaged" 0 "off"; -VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok"; -VAL_ 614 STATE 3 "enabled" 1 "disabled"; -VAL_ 614 DIRECTION_CMD 3 "right" 2 "center" 1 "left"; -VAL_ 643 STATE 0 "normal" 1 "adaptive_cruise_control" 3 "emergency_braking"; -VAL_ 835 ACC_TYPE 2 "permanent low speed lockout" 1 "ok"; -VAL_ 835 ACC_MALFUNCTION 1 "faulted" 0 "ok"; -VAL_ 835 ACC_CUT_IN 1 "CUT-IN Detected" 0 "clear"; -VAL_ 835 ALLOW_LONG_PRESS 2 "set speed increase by 5 speed units regardless" 1 "set speed increase by 1 speed unit on short press, 5 speed units on long press"; -VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted"; -VAL_ 1041 PCS_INDICATOR 2 "PCS Faulted" 1 "PCS Turned Off By User" 0 "PCS Enabled"; -VAL_ 1041 PCS_SENSITIVITY 64 "high sensitivity" 128 "mid sensitivity" 192 "low sensitivity" 0 "off"; -VAL_ 1042 LDA_ALERT 3 "hold with continuous beep" 2 "LDA unavailable" 1 "hold" 0 "none"; -VAL_ 1042 BARRIERS 3 "both" 2 "right" 1 "left" 0 "none"; -VAL_ 1042 RIGHT_LINE 3 "orange" 2 "faded" 1 "solid" 0 "none"; -VAL_ 1042 LEFT_LINE 3 "orange" 2 "faded" 1 "solid" 0 "none"; -VAL_ 1553 UNITS 1 "km" 2 "miles"; -VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left"; -VAL_ 1161 TSGN1 1 "speed sign" 0 "none"; -VAL_ 1161 TSGN2 1 "speed sign" 0 "none"; -VAL_ 1161 SPLSGN2 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none"; -VAL_ 1162 TSGN3 0 "none" 1 "speed sign" 2 "0 unlimited" 7 "unlimited" 16 "highway" 17 "no highway" 18 "motorway" 19 "no motorway" 20 "in city" 21 "outside city" 22 "pedestrian area" 23 "no pedestrian area" 65 "no overtaking left" 66 "no overtaking right" 67 "overtaking allowed again" 81 "no right turn" 97 "stop" 105 "yield" 113 "stop" 114 "yield us" 129 "no entry" 138 "no entry tss2" 145 "do not enter"; -VAL_ 1162 SPLSGN3 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none"; - - - - -CM_ "Imported file _comma.dbc starts here"; -BO_ 359 STEERING_IPAS_COMMA: 8 IPAS - SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX - SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX - SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX - SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant"; - - BO_ 512 GAS_COMMAND: 6 EON - SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR - SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR - SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR - - BO_ 513 GAS_SENSOR: 6 INTERCEPTOR - SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON - SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON - SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON - - VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; - -BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX - SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX - -CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss"; - -BO_ 767 SDSU: 8 XXX - SG_ FD_BUTTON : 7|1@0+ (1,0) [0|1] "" XXX - -CM_ "BO_ SDSU: The sDSU is a modified DSU for use in TSS1 Toyotas. Learn more: https://github.com/wocsor/panda/tree/smart_dsu"; - -CM_ SG_ 767 FD_BUTTON "The follow distance button signal as forwarded by the sdsu"; - -CM_ "toyota_highlander_2017_pt.dbc starts here"; - - - -BO_ 550 BRAKE_MODULE: 8 XXX - SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|255] "" XXX - SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|65535] "" XXX - SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|3] "" XXX - -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 - -BO_ 608 STEER_TORQUE_SENSOR: 8 XXX - SG_ STEER_TORQUE_EPS : 47|16@0- (0.73,0) [-20000|20000] "" XXX - SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX - SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - SG_ STEER_ANGLE : 31|16@0- (0.0573,0) [-500|500] "" XXX - -BO_ 610 EPS_STATUS: 5 EPS - SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX - SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX - SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX - -BO_ 956 GEAR_PACKET: 8 XXX - SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX - -CM_ SG_ 548 BRAKE_PRESSURE "seems prop to pedal force"; -CM_ SG_ 548 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; -CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; -VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; -VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled"; -VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby"; diff --git a/opendbc/toyota_highlander_hybrid_2018_pt_generated.dbc b/opendbc/toyota_highlander_hybrid_2018_pt_generated.dbc deleted file mode 100644 index c8870edfd..000000000 --- a/opendbc/toyota_highlander_hybrid_2018_pt_generated.dbc +++ /dev/null @@ -1,450 +0,0 @@ -CM_ "AUTOGENERATED FILE, DO NOT EDIT"; - - -CM_ "Imported file _toyota_2017.dbc starts here"; -VERSION "" - - -NS_ : - NS_DESC_ - CM_ - BA_DEF_ - BA_ - VAL_ - CAT_DEF_ - CAT_ - FILTER - BA_DEF_DEF_ - EV_DATA_ - ENVVAR_DATA_ - SGTYPE_ - SGTYPE_VAL_ - BA_DEF_SGTYPE_ - BA_SGTYPE_ - SIG_TYPE_REF_ - VAL_TABLE_ - SIG_GROUP_ - SIG_VALTYPE_ - SIGTYPE_VALTYPE_ - BO_TX_BU_ - BA_DEF_REL_ - BA_REL_ - BA_DEF_DEF_REL_ - BU_SG_REL_ - BU_EV_REL_ - BU_BO_REL_ - SG_MUL_VAL_ - -BS_: - -BU_: XXX DSU HCU EPS IPAS CGW - -BO_ 36 KINEMATICS: 8 XXX - SG_ ACCEL_Y : 33|10@0+ (0.03589,-18.375) [0|65535] "m/s^2" XXX - SG_ YAW_RATE : 1|10@0+ (0.244,-125) [0|65535] "deg/sec" XXX - SG_ STEERING_TORQUE : 17|10@0+ (1,-512) [0|65535] "" XXX - -BO_ 37 STEER_ANGLE_SENSOR: 8 XXX - SG_ STEER_ANGLE : 3|12@0- (1.5,0) [-500|500] "deg" XXX - SG_ STEER_FRACTION : 39|4@0- (0.1,0) [-0.7|0.7] "deg" XXX - SG_ STEER_RATE : 35|12@0- (1,0) [-2000|2000] "deg/s" XXX - -BO_ 166 BRAKE: 8 XXX - SG_ BRAKE_AMOUNT : 7|8@0+ (1,0) [0|255] "" XXX - SG_ BRAKE_PEDAL : 23|8@0+ (1,0) [0|255] "" XXX - -BO_ 170 WHEEL_SPEEDS: 8 XXX - SG_ WHEEL_SPEED_FR : 7|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_FL : 23|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_RR : 39|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_RL : 55|16@0+ (0.01,-67.67) [0|250] "kph" XXX - -BO_ 180 SPEED: 8 XXX - SG_ ENCODER : 39|8@0+ (1,0) [0|255] "" XXX - SG_ SPEED : 47|16@0+ (0.01,0) [0|250] "kph" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 353 DSU_SPEED: 7 XXX - SG_ FORWARD_SPEED : 15|16@0- (0.00390625,-30) [0|255] "kph" XXX - -BO_ 452 ENGINE_RPM: 8 CGW - SG_ RPM : 7|16@0- (0.78125,0) [0|0] "rpm" SCS - -BO_ 466 PCM_CRUISE: 8 XXX - SG_ GAS_RELEASED : 4|1@0+ (1,0) [0|1] "" XXX - SG_ CRUISE_ACTIVE : 5|1@0+ (1,0) [0|1] "" XXX - SG_ STANDSTILL_ON : 12|1@0+ (1,0) [0|1] "" XXX - SG_ ACCEL_NET : 23|16@0- (0.001,0) [-20|20] "m/s2" XXX - SG_ CRUISE_STATE : 55|4@0+ (1,0) [0|15] "" XXX - SG_ CANCEL_REQ : 49|1@1+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 467 PCM_CRUISE_2: 8 XXX - SG_ MAIN_ON : 15|1@0+ (1,0) [0|1] "" XXX - SG_ LOW_SPEED_LOCKOUT : 14|2@0+ (1,0) [0|3] "kph" XXX - SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "kph" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 552 ACCELEROMETER: 8 XXX - SG_ ACCEL_Z : 22|15@0- (1,0) [0|32767] "" XXX - SG_ ACCEL_X : 6|15@0- (0.001,0) [-20|20] "m/s2" XXX - -BO_ 560 BRAKE_MODULE2: 7 XXX - SG_ BRAKE_PRESSED : 26|1@0+ (1,0) [0|1] "" XXX - -BO_ 614 STEERING_IPAS: 8 IPAS - SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX - SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX - SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX - SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 643 PRE_COLLISION: 7 DSU - SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 15|8@0+ (1,0) [0|255] "" XXX - SG_ FORCE : 23|16@0- (2,0) [0|255] "N" XXX - SG_ SET_ME_X002 : 33|8@0+ (1,0) [0|3] "" XXX - SG_ BRAKE_STATUS : 39|3@0+ (1,0) [0|255] "" XXX - SG_ STATE : 36|3@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X003 : 40|1@0+ (1,0) [0|1] "" XXX - SG_ PRECOLLISION_ACTIVE : 41|1@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 55|8@0+ (1,0) [0|255] "" XXX - -BO_ 740 STEERING_LKA: 5 XXX - SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX - SG_ STEER_REQUEST : 0|1@0+ (1,0) [0|1] "" XXX - SG_ COUNTER : 6|6@0+ (1,0) [0|63] "" XXX - SG_ SET_ME_1 : 7|1@0+ (1,0) [0|1] "" XXX - SG_ STEER_TORQUE_CMD : 15|16@0- (1,0) [0|65535] "" XXX - SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX - -BO_ 742 LEAD_INFO: 8 DSU - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" HCU - SG_ LEAD_REL_SPEED : 23|12@0- (0.025,0) [-100|100] "m/s" HCU - SG_ LEAD_LONG_DIST : 7|13@0+ (0.05,0) [0|300] "m" HCU - -BO_ 835 ACC_CONTROL: 8 DSU - SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU - SG_ ACC_MALFUNCTION : 18|1@0+ (1,0) [0|0] "" XXX - SG_ ACC_CUT_IN : 25|1@0+ (1,0) [0|1] "" XXX - SG_ ALLOW_LONG_PRESS : 17|2@0+ (1,0) [0|2] "" XXX - SG_ ACC_TYPE : 23|2@0+ (1,0) [0|3] "" HCU - SG_ DISTANCE : 20|1@0+ (1,0) [0|1] "" XXX - SG_ MINI_CAR : 21|1@0+ (1,0) [0|1] "" XXX - SG_ PERMIT_BRAKING : 30|1@0+ (1,0) [0|1] "" HCU - SG_ RELEASE_STANDSTILL : 31|1@0+ (1,0) [0|1] "" HCU - SG_ CANCEL_REQ : 24|1@0+ (1,0) [0|1] "" HCU - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - SG_ ACCEL_CMD_ALT : 47|8@0- (0.05,0) [0|0] "m/s^2" XXX - SG_ RADAR_DIRTY : 19|1@0+ (1,0) [0|1] "" XXX - -BO_ 836 PRE_COLLISION_2: 8 DSU - SG_ CHECKSUM : 63|8@0+ (1,0) [0|0] "" XXX - -BO_ 869 DSU_CRUISE : 7 DSU - SG_ RES_BTN : 3|1@0+ (1,0) [0|0] "" XXX - SG_ SET_BTN : 2|1@0+ (1,0) [0|0] "" XXX - SG_ CANCEL_BTN : 1|1@0+ (1,0) [0|0] "" XXX - SG_ MAIN_ON : 0|1@0+ (1,0) [0|0] "" XXX - SG_ SET_SPEED : 15|8@0+ (1,0) [0|0] "km/h" XXX - SG_ CRUISE_REQUEST : 31|8@0+ (100,-12800) [0|0] "N" XXX - SG_ LEAD_DISTANCE : 39|8@0+ (1,0) [0|0] "m" XXX - -BO_ 921 PCM_CRUISE_SM: 8 XXX - SG_ MAIN_ON : 4|1@0+ (1,0) [0|1] "" XXX - SG_ CRUISE_CONTROL_STATE : 11|4@0+ (1,0) [0|15] "" XXX - SG_ DISTANCE_LINES : 14|2@0+ (1,0) [0|3] "" XXX - SG_ UI_SET_SPEED : 31|8@0+ (1,0) [0|255] "" XXX - -BO_ 951 ESP_CONTROL: 8 ESP - SG_ TC_DISABLED : 13|1@0+ (1,0) [0|1] "" XXX - SG_ VSC_DISABLED : 12|2@0+ (1,0) [0|1] "" XXX - SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" XXX - SG_ BRAKE_HOLD_ENABLED : 33|1@1+ (1,0) [0|1] "" XXX - SG_ BRAKE_HOLD_ACTIVE : 36|1@0+ (1,0) [0|1] "" XXX - -BO_ 1020 SOLAR_SENSOR: 8 XXX - SG_ LUX_SENSOR : 55|13@0+ (1,0) [0|0] "" XXX - -BO_ 1041 ACC_HUD: 8 DSU - SG_ PCS_INDICATOR : 7|2@0+ (1,0) [0|3] "" XXX - SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X20 : 15|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X10 : 39|8@0+ (1,0) [0|1] "" XXX - SG_ PCS_OFF : 40|1@0+ (1,0) [0|0] "" XXX - SG_ PCS_SENSITIVITY : 55|8@0+ (1,0) [0|1] "" XXX - -BO_ 1042 LKAS_HUD: 8 XXX - SG_ BARRIERS : 1|2@0+ (1,0) [0|3] "" XXX - SG_ RIGHT_LINE : 3|2@0+ (1,0) [0|3] "" XXX - SG_ LEFT_LINE : 5|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X01 : 7|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X01_2 : 11|2@0+ (1,0) [0|3] "" XXX - SG_ LDA_ALERT : 9|2@0+ (1,0) [0|3] "" XXX - SG_ TWO_BEEPS : 12|1@0+ (1,0) [0|1] "" XXX - SG_ ADJUSTING_CAMERA : 13|1@0+ (1,0) [0|1] "" XXX - SG_ LDA_MALFUNCTION : 15|1@0+ (1,0) [0|1] "" XXX - SG_ REPEATED_BEEPS : 32|1@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X0C : 23|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X2C : 47|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X38 : 55|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X02 : 63|8@0+ (1,0) [0|1] "" XXX - -BO_ 1043 TIME : 8 CGW - SG_ YEAR : 7|8@0+ (1,0) [0|0] "year" XXX - SG_ MONTH : 15|8@0+ (1,0) [0|0] "month" XXX - SG_ DAY : 23|8@0+ (1,0) [0|0] "day" XXX - SG_ HOUR : 31|8@0+ (1,0) [0|0] "hour" XXX - SG_ MINUTE : 39|8@0+ (1,0) [0|0] "minute" XXX - SG_ GMT_DIFF : 55|1@0+ (1,0) [0|0] "" XXX - SG_ GMTDIFF_HOURS : 54|4@0+ (1,0) [0|0] "hours" XXX - SG_ GMTDIFF_MINUTES : 50|6@0+ (1,0) [0|0] "minutes" XXX - SG_ SUMMER : 60|1@0+ (1,0) [0|0] "" XXX - -BO_ 1408 VIN_PART_1: 8 CGW - SG_ VIN_1 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_2 : 15|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_3 : 23|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_4 : 31|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_5 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_6 : 47|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_7 : 55|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_8 : 63|8@0+ (1,0) [0|0] "" XXX - -BO_ 1409 VIN_PART_2: 8 CGW - SG_ VIN_9 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_10 : 15|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_11 : 23|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_12 : 31|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_13 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_14 : 47|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_15 : 55|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_16 : 63|8@0+ (1,0) [0|0] "" XXX - -BO_ 1410 VIN_PART_3: 8 CGW - SG_ VIN_17 : 7|8@0+ (1,0) [0|0] "" XXX - -BO_ 1553 UI_SETTING: 8 XXX - SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX - SG_ ODOMETER : 43|20@0+ (1,0) [0|1048575] "" XXX - -BO_ 1556 STEERING_LEVERS: 8 XXX - SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX - SG_ HAZARD_LIGHT : 27|1@0+ (1,0) [0|1] "" XXX - -BO_ 1568 SEATS_DOORS: 8 XXX - SG_ METER_DIMMED : 38|1@0+ (1,0) [0|1] "" XXX - SG_ PARKING_BRAKE : 60|1@0+ (1,0) [0|1] "" XXX - SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_RR : 43|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_FR : 44|1@0+ (1,0) [0|1] "" XXX - -BO_ 1570 LIGHT_STALK: 8 SCM - SG_ AUTO_HIGH_BEAM : 37|1@0+ (1,0) [0|1] "" XXX - SG_ FRONT_FOG : 27|1@0+ (1,0) [0|1] "" XXX - SG_ PARKING_LIGHT : 28|1@0+ (1,0) [0|1] "" XXX - SG_ LOW_BEAM : 29|1@0+ (1,0) [0|1] "" XXX - SG_ HIGH_BEAM : 30|1@0+ (1,0) [0|1] "" XXX - SG_ DAYTIME_RUNNING_LIGHT : 31|1@0+ (1,0) [0|1] "" XXX - -BO_ 1161 RSA1: 8 FCM - SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY1 : 12|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT1 : 9|2@0+ (1,0) [0|0] "" XXX - SG_ SPDVAL1 : 23|8@0+ (1,0) [0|0] "kph" XXX - SG_ SPLSGN1 : 31|4@0+ (1,0) [0|0] "" XXX - SG_ SPLSGN2 : 27|4@0+ (1,0) [0|0] "" XXX - SG_ TSGN2 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY2 : 44|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT2 : 41|2@0+ (1,0) [0|0] "" XXX - SG_ SPDVAL2 : 55|8@0+ (1,0) [0|0] "" XXX - SG_ BZRRQ_P : 63|2@0+ (1,0) [0|0] "" XXX - SG_ BZRRQ_A : 61|2@0+ (1,0) [0|0] "" XXX - SG_ SYNCID1 : 59|4@0+ (1,0) [0|0] "" XXX - -BO_ 1162 RSA2: 8 FCM - SG_ TSGN3 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY3 : 12|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT3 : 9|2@0+ (1,0) [0|0] "" XXX - SG_ SPLSGN3 : 31|4@0+ (1,0) [0|0] "" XXX - SG_ SPLSGN4 : 27|4@0+ (1,0) [0|0] "" XXX - SG_ TSGN4 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY4 : 44|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT4 : 41|2@0+ (1,0) [0|0] "" XXX - SG_ DPSGNREQ : 54|1@0+ (1,0) [0|0] "" XXX - SG_ SGNNUMP : 53|3@0+ (1,0) [0|0] "" XXX - SG_ SGNNUMA : 50|3@0+ (1,0) [0|0] "" XXX - SG_ SPDUNT : 63|2@0+ (1,0) [0|0] "" XXX - SG_ TSRWMSG : 61|2@0+ (1,0) [0|0] "" XXX - SG_ SYNCID2 : 59|4@0+ (1,0) [0|0] "" XXX - -BO_ 1163 RSA3: 8 FCM - SG_ TSREQPD : 7|1@0+ (1,0) [0|0] "" XXX - SG_ TSRMSW : 6|1@0+ (1,0) [0|0] "" XXX - SG_ OTSGNNTM : 5|2@0+ (1,0) [0|0] "" XXX - SG_ NTLVLSPD : 3|2@0+ (1,0) [0|0] "" XXX - SG_ OVSPNTM : 1|2@0+ (1,0) [0|0] "" XXX - SG_ OVSPVALL : 11|4@0+ (1,-5) [0|0] "" XXX - SG_ OVSPVALM : 19|4@0+ (1,-5) [0|0] "" XXX - SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX - SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" XXX - -BO_ 1571 CENTRAL_GATEWAY_UNIT: 8 CGW - SG_ DOOR_LOCK_FEEDBACK_LIGHT : 15|1@0+ (1,0) [0|0] "" XXX - SG_ KEYFOB_LOCKING_FEEDBACK_LIGHT : 61|1@0+ (1,0) [0|0] "" XXX - SG_ KEYFOB_UNLOCKING_FEEDBACK_LIGHT : 62|1@0+ (1,0) [0|0] "" XXX - -CM_ SG_ 36 ACCEL_Y "unit is tbd"; -CM_ SG_ 36 YAW_RATE "verify"; -CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; -CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; -CM_ SG_ 37 STEER_RATE "factor is tbd"; -CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; -CM_ SG_ 466 CRUISE_STATE "Active state is 8, if standstill is requested will switch to state 11(3 sec timer), after timer is elapsed will switch into state 7(standstill). If plus button was pressed - status 9, minus button pressed - status 10"; -CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isn't perfect"; -CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; -CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; -CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; -CM_ SG_ 608 STEER_OVERRIDE "set when driver torque exceeds a certain value"; -CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; -CM_ SG_ 643 COUNTER "only used on cars that use this msg for cruise control"; -CM_ SG_ 643 BRAKE_STATUS "only used on cars that use this msg for cruise control"; -CM_ SG_ 643 PRECOLLISION_ACTIVE "set 0.5s before any braking"; -CM_ SG_ 835 ACC_TYPE "if 2, car is likely to have a permanent low speed lockout. 1 is ok"; -CM_ SG_ 835 RADAR_DIRTY "Display Clean Radar Sensor message on HUD"; -CM_ SG_ 835 ACC_MALFUNCTION "display ACC fault on dash if set to 1"; -CM_ SG_ 835 ACC_CUT_IN "Display blinking yellow lead if set to 1"; -CM_ SG_ 835 DISTANCE "Display Distance Bars on HUD Permanently"; -CM_ SG_ 835 ALLOW_LONG_PRESS "Enable Toyota's factory set speed increment behaviour, available on both metrics cars and imperial unit cars"; -CM_ SG_ 835 PERMIT_BRAKING "Original ACC has this going high when a car in front is detected. In openpilot and before the PERMIT_BRAKING name, this was 'SET_ME_1' and is hardcoded to be high. Unsure if only informational or has an effect though existing usage in openpilot is to always set it to 1. Originally 'PMTBRKG' in the leaked toyota_2017_ref_pt.dbc file and name expansion speculated to be PerMiT BRaKinG."; -CM_ SG_ 835 ACCEL_CMD_ALT "Copy of main ACCEL_CMD, but across 8 bits instead of 16 bits like ACCEL_CMD. Unsure if only informational or has an effect. Likely informational as existing openpilot sets this to 0 and no loss of functionality observed. Originally 'AT_RAW' in leaked toyota_2017_ref_pt.dbc file."; -CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; -CM_ SG_ 951 BRAKE_LIGHTS_ACC "brake lights when ACC commands decel"; -CM_ SG_ 1041 PCS_INDICATOR "Pre-Collision System Indicator"; -CM_ SG_ 1041 PCS_SENSITIVITY "Pre-Collision System Sensitivity"; -CM_ SG_ 1042 SET_ME_1 "unclear what this is, but it's always 1 in drive traces"; -CM_ SG_ 1042 REPEATED_BEEPS "recommended for fcw and other important alerts"; -CM_ SG_ 1161 SPDVAL1 "Numbers 0-199 is displayed, 200-254 displays circle without number and 255 is for no limit."; -CM_ SG_ 1161 SYNCID1 "counter from 1 to f at 1 Hz"; -CM_ SG_ 1161 SPDVAL2 "conditional speed value 70"; -CM_ SG_ 1162 SGNNUMP "1 if SPDVAL1 is set, otherwise 0"; -CM_ SG_ 1162 SYNCID2 "counter from 1 to f at 1 Hz"; -CM_ SG_ 1163 TSREQPD "always 1"; -CM_ SG_ 1163 TSRMSW "always 1"; -CM_ SG_ 1163 OTSGNNTM "always 3"; -CM_ SG_ 1163 NTLVLSPD "always 3"; -CM_ SG_ 1163 OVSPNTM "always 3"; -CM_ SG_ 1163 OVSPVALL "-5 at start then 2 after 2 seconds"; -CM_ SG_ 1163 OVSPVALM "-5 at start then 5 after 2 seconds"; -CM_ SG_ 1163 OVSPVALH "-5 at start then 10 after 2 seconds"; -CM_ SG_ 1163 TSRSPU "always 1"; -CM_ SG_ 1553 ODOMETER "Unit is dependent upon units signal"; - -VAL_ 466 CRUISE_STATE 11 "timer_3sec" 10 "adaptive click down" 9 "adaptive click up" 8 "adaptive engaged" 7 "standstill" 6 "non-adaptive click up" 5 "non-adaptive click down" 4 "non-adaptive hold down" 3 "non-adaptive hold up" 2 "non-adaptive being engaged" 1 "non-adaptive engaged" 0 "off"; -VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok"; -VAL_ 614 STATE 3 "enabled" 1 "disabled"; -VAL_ 614 DIRECTION_CMD 3 "right" 2 "center" 1 "left"; -VAL_ 643 STATE 0 "normal" 1 "adaptive_cruise_control" 3 "emergency_braking"; -VAL_ 835 ACC_TYPE 2 "permanent low speed lockout" 1 "ok"; -VAL_ 835 ACC_MALFUNCTION 1 "faulted" 0 "ok"; -VAL_ 835 ACC_CUT_IN 1 "CUT-IN Detected" 0 "clear"; -VAL_ 835 ALLOW_LONG_PRESS 2 "set speed increase by 5 speed units regardless" 1 "set speed increase by 1 speed unit on short press, 5 speed units on long press"; -VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted"; -VAL_ 1041 PCS_INDICATOR 2 "PCS Faulted" 1 "PCS Turned Off By User" 0 "PCS Enabled"; -VAL_ 1041 PCS_SENSITIVITY 64 "high sensitivity" 128 "mid sensitivity" 192 "low sensitivity" 0 "off"; -VAL_ 1042 LDA_ALERT 3 "hold with continuous beep" 2 "LDA unavailable" 1 "hold" 0 "none"; -VAL_ 1042 BARRIERS 3 "both" 2 "right" 1 "left" 0 "none"; -VAL_ 1042 RIGHT_LINE 3 "orange" 2 "faded" 1 "solid" 0 "none"; -VAL_ 1042 LEFT_LINE 3 "orange" 2 "faded" 1 "solid" 0 "none"; -VAL_ 1553 UNITS 1 "km" 2 "miles"; -VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left"; -VAL_ 1161 TSGN1 1 "speed sign" 0 "none"; -VAL_ 1161 TSGN2 1 "speed sign" 0 "none"; -VAL_ 1161 SPLSGN2 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none"; -VAL_ 1162 TSGN3 0 "none" 1 "speed sign" 2 "0 unlimited" 7 "unlimited" 16 "highway" 17 "no highway" 18 "motorway" 19 "no motorway" 20 "in city" 21 "outside city" 22 "pedestrian area" 23 "no pedestrian area" 65 "no overtaking left" 66 "no overtaking right" 67 "overtaking allowed again" 81 "no right turn" 97 "stop" 105 "yield" 113 "stop" 114 "yield us" 129 "no entry" 138 "no entry tss2" 145 "do not enter"; -VAL_ 1162 SPLSGN3 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none"; - - - - -CM_ "Imported file _comma.dbc starts here"; -BO_ 359 STEERING_IPAS_COMMA: 8 IPAS - SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX - SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX - SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX - SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant"; - - BO_ 512 GAS_COMMAND: 6 EON - SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR - SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR - SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR - - BO_ 513 GAS_SENSOR: 6 INTERCEPTOR - SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON - SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON - SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON - - VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; - -BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX - SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX - -CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss"; - -BO_ 767 SDSU: 8 XXX - SG_ FD_BUTTON : 7|1@0+ (1,0) [0|1] "" XXX - -CM_ "BO_ SDSU: The sDSU is a modified DSU for use in TSS1 Toyotas. Learn more: https://github.com/wocsor/panda/tree/smart_dsu"; - -CM_ SG_ 767 FD_BUTTON "The follow distance button signal as forwarded by the sdsu"; - -CM_ "toyota_highlander_hybrid_2018_pt.dbc starts here"; - - - -BO_ 550 BRAKE_MODULE: 8 XXX - SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|511] "" XXX - SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|511] "" XXX - SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|1] "" XXX - -BO_ 581 GAS_PEDAL: 5 XXX - SG_ GAS_PEDAL : 23|8@0+ (0.005,0) [0|1] "" XXX - -BO_ 608 STEER_TORQUE_SENSOR: 8 XXX - SG_ STEER_TORQUE_EPS : 47|16@0- (0.73,0) [-20000|20000] "" XXX - SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX - SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - SG_ STEER_ANGLE : 31|16@0- (0.0573,0) [-500|500] "" XXX - -BO_ 610 EPS_STATUS: 5 EPS - SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX - SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX - SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX - -BO_ 956 GEAR_PACKET: 8 XXX - SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX - -CM_ SG_ 550 BRAKE_PRESSURE "seems prop to pedal force"; -CM_ SG_ 550 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; -CM_ SG_ 581 GAS_PEDAL "it seems slightly filtered"; -CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; -VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled"; -VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby"; -VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; diff --git a/opendbc/lexus_ct200h_2018_pt_generated.dbc b/opendbc/toyota_new_mc_pt_generated.dbc similarity index 69% rename from opendbc/lexus_ct200h_2018_pt_generated.dbc rename to opendbc/toyota_new_mc_pt_generated.dbc index 06fcd3dc1..dcbf1bb99 100644 --- a/opendbc/lexus_ct200h_2018_pt_generated.dbc +++ b/opendbc/toyota_new_mc_pt_generated.dbc @@ -1,6 +1,47 @@ CM_ "AUTOGENERATED FILE, DO NOT EDIT"; +CM_ "Imported file _comma.dbc starts here"; +BO_ 359 STEERING_IPAS_COMMA: 8 IPAS + SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX + SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX + SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant"; + +BO_ 512 GAS_COMMAND: 6 EON + SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR + SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR + SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR + SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR + SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR + +BO_ 513 GAS_SENSOR: 6 INTERCEPTOR + SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON + SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON + SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON + SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON + +VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; + +BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX + SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX + +CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss"; + +BO_ 767 SDSU: 8 XXX + SG_ FD_BUTTON : 7|1@0+ (1,0) [0|1] "" XXX + +CM_ "BO_ SDSU: The sDSU is a modified DSU for use in TSS1 Toyotas. Learn more: https://github.com/wocsor/panda/tree/smart_dsu"; +CM_ SG_ 767 FD_BUTTON "The follow distance button signal as forwarded by the sdsu"; + + CM_ "Imported file _toyota_2017.dbc starts here"; VERSION "" @@ -37,11 +78,11 @@ NS_ : BS_: -BU_: XXX DSU HCU EPS IPAS CGW +BU_: XXX DSU HCU EPS IPAS CGW BGM BO_ 36 KINEMATICS: 8 XXX SG_ ACCEL_Y : 33|10@0+ (0.03589,-18.375) [0|65535] "m/s^2" XXX - SG_ YAW_RATE : 1|10@0+ (0.244,-125) [0|65535] "deg/sec" XXX + SG_ YAW_RATE : 1|10@0+ (0.244,-125) [0|65535] "deg/s" XXX SG_ STEERING_TORQUE : 17|10@0+ (1,-512) [0|65535] "" XXX BO_ 37 STEER_ANGLE_SENSOR: 8 XXX @@ -54,18 +95,24 @@ BO_ 166 BRAKE: 8 XXX SG_ BRAKE_PEDAL : 23|8@0+ (1,0) [0|255] "" XXX BO_ 170 WHEEL_SPEEDS: 8 XXX - SG_ WHEEL_SPEED_FR : 7|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_FL : 23|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_RR : 39|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_RL : 55|16@0+ (0.01,-67.67) [0|250] "kph" XXX + SG_ WHEEL_SPEED_FR : 7|16@0+ (0.01,-67.67) [0|250] "km/h" XXX + SG_ WHEEL_SPEED_FL : 23|16@0+ (0.01,-67.67) [0|250] "km/h" XXX + SG_ WHEEL_SPEED_RR : 39|16@0+ (0.01,-67.67) [0|250] "km/h" XXX + SG_ WHEEL_SPEED_RL : 55|16@0+ (0.01,-67.67) [0|250] "km/h" XXX BO_ 180 SPEED: 8 XXX SG_ ENCODER : 39|8@0+ (1,0) [0|255] "" XXX - SG_ SPEED : 47|16@0+ (0.01,0) [0|250] "kph" XXX + SG_ SPEED : 47|16@0+ (0.01,0) [0|250] "km/h" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX +BO_ 295 GEAR_PACKET_HYBRID: 8 XXX + SG_ CAR_MOVEMENT : 39|8@0- (1,0) [0|255] "" XXX + SG_ COUNTER : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ GEAR : 47|4@0+ (1,0) [0|15] "" XXX + BO_ 353 DSU_SPEED: 7 XXX - SG_ FORWARD_SPEED : 15|16@0- (0.00390625,-30) [0|255] "kph" XXX + SG_ FORWARD_SPEED : 15|16@0- (0.00390625,-30) [0|255] "km/h" XXX BO_ 452 ENGINE_RPM: 8 CGW SG_ RPM : 7|16@0- (0.78125,0) [0|0] "rpm" SCS @@ -74,24 +121,34 @@ BO_ 466 PCM_CRUISE: 8 XXX SG_ GAS_RELEASED : 4|1@0+ (1,0) [0|1] "" XXX SG_ CRUISE_ACTIVE : 5|1@0+ (1,0) [0|1] "" XXX SG_ STANDSTILL_ON : 12|1@0+ (1,0) [0|1] "" XXX - SG_ ACCEL_NET : 23|16@0- (0.001,0) [-20|20] "m/s2" XXX + SG_ ACCEL_NET : 23|16@0- (0.001,0) [-20|20] "m/s^2" XXX SG_ CRUISE_STATE : 55|4@0+ (1,0) [0|15] "" XXX SG_ CANCEL_REQ : 49|1@1+ (1,0) [0|1] "" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX BO_ 467 PCM_CRUISE_2: 8 XXX SG_ MAIN_ON : 15|1@0+ (1,0) [0|1] "" XXX - SG_ LOW_SPEED_LOCKOUT : 14|2@0+ (1,0) [0|3] "kph" XXX - SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "kph" XXX + SG_ LOW_SPEED_LOCKOUT : 14|2@0+ (1,0) [0|3] "" XXX + SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "km/h" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX BO_ 552 ACCELEROMETER: 8 XXX - SG_ ACCEL_Z : 22|15@0- (1,0) [0|32767] "" XXX - SG_ ACCEL_X : 6|15@0- (0.001,0) [-20|20] "m/s2" XXX + SG_ ACCEL_Z : 22|15@0- (1,0) [0|32767] "m/s^2" XXX + SG_ ACCEL_X : 6|15@0- (0.001,0) [-20|20] "m/s^2" XXX -BO_ 560 BRAKE_MODULE2: 7 XXX +BO_ 560 BRAKE_2: 7 XXX SG_ BRAKE_PRESSED : 26|1@0+ (1,0) [0|1] "" XXX +BO_ 581 GAS_PEDAL_HYBRID: 8 XXX + SG_ GAS_PEDAL : 23|8@0+ (0.005,0) [0|1] "" XXX + +BO_ 608 STEER_TORQUE_SENSOR: 8 XXX + SG_ STEER_TORQUE_EPS : 47|16@0- (1,0) [-32768|32767] "" XXX + SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX + SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ STEER_ANGLE : 31|16@0- (0.0573,0) [-500|500] "" XXX + BO_ 614 STEERING_IPAS: 8 IPAS SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX @@ -113,6 +170,10 @@ BO_ 643 PRE_COLLISION: 7 DSU SG_ PRECOLLISION_ACTIVE : 41|1@0+ (1,0) [0|255] "" XXX SG_ CHECKSUM : 55|8@0+ (1,0) [0|255] "" XXX +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 + BO_ 740 STEERING_LKA: 5 XXX SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX SG_ STEER_REQUEST : 0|1@0+ (1,0) [0|1] "" XXX @@ -127,10 +188,11 @@ BO_ 742 LEAD_INFO: 8 DSU SG_ LEAD_LONG_DIST : 7|13@0+ (0.05,0) [0|300] "m" HCU BO_ 835 ACC_CONTROL: 8 DSU - SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU + SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s^2" HCU SG_ ACC_MALFUNCTION : 18|1@0+ (1,0) [0|0] "" XXX SG_ ACC_CUT_IN : 25|1@0+ (1,0) [0|1] "" XXX SG_ ALLOW_LONG_PRESS : 17|2@0+ (1,0) [0|2] "" XXX + SG_ ITS_CONNECT_LEAD : 39|8@0+ (1,0) [0|1] "" Vector__XXX SG_ ACC_TYPE : 23|2@0+ (1,0) [0|3] "" HCU SG_ DISTANCE : 20|1@0+ (1,0) [0|1] "" XXX SG_ MINI_CAR : 21|1@0+ (1,0) [0|1] "" XXX @@ -166,6 +228,23 @@ BO_ 951 ESP_CONTROL: 8 ESP SG_ BRAKE_HOLD_ENABLED : 33|1@1+ (1,0) [0|1] "" XXX SG_ BRAKE_HOLD_ACTIVE : 36|1@0+ (1,0) [0|1] "" XXX +BO_ 956 GEAR_PACKET: 8 XXX + SG_ SPORT_ON : 2|1@0+ (1,0) [0|1] "" XXX + SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX + SG_ SPORT_GEAR_ON : 33|1@0+ (1,0) [0|1] "" XXX + SG_ SPORT_GEAR : 38|3@0+ (1,0) [0|7] "" XXX + SG_ ECON_ON : 40|1@0+ (1,0) [0|1] "" XXX + SG_ B_GEAR_ENGAGED : 41|1@0+ (1,0) [0|1] "" XXX + SG_ DRIVE_ENGAGED : 47|1@0+ (1,0) [0|1] "" XXX + +BO_ 1005 REVERSE_CAMERA_STATE: 2 BGM + SG_ REVERSE_CAMERA_GUIDELINES : 9|2@0+ (1,0) [1|3] "" XXX + +BO_ 1009 PCM_CRUISE_ALT: 8 XXX + SG_ MAIN_ON : 13|1@0+ (1,0) [0|3] "" XXX + SG_ CRUISE_STATE : 10|1@0+ (1,0) [0|1] "" XXX + SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "mph" XXX + BO_ 1020 SOLAR_SENSOR: 8 XXX SG_ LUX_SENSOR : 55|13@0+ (1,0) [0|0] "" XXX @@ -177,20 +256,31 @@ BO_ 1041 ACC_HUD: 8 DSU SG_ PCS_OFF : 40|1@0+ (1,0) [0|0] "" XXX SG_ PCS_SENSITIVITY : 55|8@0+ (1,0) [0|1] "" XXX -BO_ 1042 LKAS_HUD: 8 XXX +BO_ 1042 LKAS_HUD: 8 DSU SG_ BARRIERS : 1|2@0+ (1,0) [0|3] "" XXX SG_ RIGHT_LINE : 3|2@0+ (1,0) [0|3] "" XXX SG_ LEFT_LINE : 5|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X01 : 7|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X01_2 : 11|2@0+ (1,0) [0|3] "" XXX + SG_ LKAS_STATUS : 7|2@0+ (1,0) [0|3] "" XXX SG_ LDA_ALERT : 9|2@0+ (1,0) [0|3] "" XXX + SG_ LDW_EXIST : 10|1@0+ (1,0) [0|1] "" XXX SG_ TWO_BEEPS : 12|1@0+ (1,0) [0|1] "" XXX SG_ ADJUSTING_CAMERA : 13|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_UNAVAILABLE_QUIET : 14|1@0+ (1,0) [0|1] "" XXX SG_ LDA_MALFUNCTION : 15|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_UNAVAILABLE : 16|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_SENSITIVITY : 18|2@0+ (1,0) [0|3] "" XXX + SG_ LDA_SA_TOGGLE : 20|2@0+ (1,0) [0|3] "" XXX + SG_ LDA_SPEED_TOO_LOW : 21|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_ON_MESSAGE : 31|2@0+ (1,0) [0|3] "" XXX SG_ REPEATED_BEEPS : 32|1@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X0C : 23|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X2C : 47|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X38 : 55|8@0+ (1,0) [0|1] "" XXX + SG_ LANE_SWAY_TOGGLE : 43|1@0+ (1,0) [0|1] "" XXX + SG_ LANE_SWAY_SENSITIVITY : 45|2@0+ (1,0) [0|3] "" XXX + SG_ TAKE_CONTROL : 46|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_FRONT_CAMERA_BLOCKED : 47|1@0+ (1,0) [0|1] "" XXX + SG_ LANE_SWAY_BUZZER : 50|2@0+ (1,0) [0|0] "" XXX + SG_ LANE_SWAY_FLD : 53|3@0+ (1,0) [0|7] "" XXX + SG_ LANE_SWAY_WARNING : 55|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X01 : 42|1@0+ (1,0) [0|1] "" XXX SG_ SET_ME_X02 : 63|8@0+ (1,0) [0|1] "" XXX BO_ 1043 TIME : 8 CGW @@ -204,59 +294,14 @@ BO_ 1043 TIME : 8 CGW SG_ GMTDIFF_MINUTES : 50|6@0+ (1,0) [0|0] "minutes" XXX SG_ SUMMER : 60|1@0+ (1,0) [0|0] "" XXX -BO_ 1408 VIN_PART_1: 8 CGW - SG_ VIN_1 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_2 : 15|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_3 : 23|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_4 : 31|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_5 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_6 : 47|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_7 : 55|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_8 : 63|8@0+ (1,0) [0|0] "" XXX - -BO_ 1409 VIN_PART_2: 8 CGW - SG_ VIN_9 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_10 : 15|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_11 : 23|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_12 : 31|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_13 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_14 : 47|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_15 : 55|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_16 : 63|8@0+ (1,0) [0|0] "" XXX - -BO_ 1410 VIN_PART_3: 8 CGW - SG_ VIN_17 : 7|8@0+ (1,0) [0|0] "" XXX - -BO_ 1553 UI_SETTING: 8 XXX - SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX - SG_ ODOMETER : 43|20@0+ (1,0) [0|1048575] "" XXX - -BO_ 1556 STEERING_LEVERS: 8 XXX - SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX - SG_ HAZARD_LIGHT : 27|1@0+ (1,0) [0|1] "" XXX - -BO_ 1568 SEATS_DOORS: 8 XXX - SG_ METER_DIMMED : 38|1@0+ (1,0) [0|1] "" XXX - SG_ PARKING_BRAKE : 60|1@0+ (1,0) [0|1] "" XXX - SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_RR : 43|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_FR : 44|1@0+ (1,0) [0|1] "" XXX - -BO_ 1570 LIGHT_STALK: 8 SCM - SG_ AUTO_HIGH_BEAM : 37|1@0+ (1,0) [0|1] "" XXX - SG_ FRONT_FOG : 27|1@0+ (1,0) [0|1] "" XXX - SG_ PARKING_LIGHT : 28|1@0+ (1,0) [0|1] "" XXX - SG_ LOW_BEAM : 29|1@0+ (1,0) [0|1] "" XXX - SG_ HIGH_BEAM : 30|1@0+ (1,0) [0|1] "" XXX - SG_ DAYTIME_RUNNING_LIGHT : 31|1@0+ (1,0) [0|1] "" XXX +BO_ 1083 AUTOPARK_STATUS: 8 IPAS + SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX BO_ 1161 RSA1: 8 FCM SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX SG_ TSGNGRY1 : 12|3@0+ (1,0) [0|0] "" XXX SG_ TSGNHLT1 : 9|2@0+ (1,0) [0|0] "" XXX - SG_ SPDVAL1 : 23|8@0+ (1,0) [0|0] "kph" XXX + SG_ SPDVAL1 : 23|8@0+ (1,0) [0|0] "km/h" XXX SG_ SPLSGN1 : 31|4@0+ (1,0) [0|0] "" XXX SG_ SPLSGN2 : 27|4@0+ (1,0) [0|0] "" XXX SG_ TSGN2 : 39|8@0+ (1,0) [0|0] "" XXX @@ -294,21 +339,79 @@ BO_ 1163 RSA3: 8 FCM SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" XXX -BO_ 1571 CENTRAL_GATEWAY_UNIT: 8 CGW +BO_ 1408 VIN_PART_1: 8 CGW + SG_ VIN_1 : 7|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_2 : 15|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_3 : 23|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_4 : 31|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_5 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_6 : 47|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_7 : 55|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_8 : 63|8@0+ (1,0) [0|0] "" XXX + +BO_ 1409 VIN_PART_2: 8 CGW + SG_ VIN_9 : 7|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_10 : 15|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_11 : 23|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_12 : 31|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_13 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_14 : 47|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_15 : 55|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_16 : 63|8@0+ (1,0) [0|0] "" XXX + +BO_ 1410 VIN_PART_3: 8 CGW + SG_ VIN_17 : 7|8@0+ (1,0) [0|0] "" XXX + +BO_ 1552 BODY_CONTROL_STATE_2: 8 XXX + SG_ METER_SLIDER_BRIGHTNESS_PCT : 30|7@0+ (1,0) [12|100] "%" XXX + SG_ METER_SLIDER_LOW_BRIGHTNESS : 37|1@0+ (1,0) [0|1] "" XXX + SG_ METER_SLIDER_DIMMED : 38|1@0+ (1,0) [0|1] "" XXX + +BO_ 1553 UI_SETTING: 8 XXX + SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX + SG_ ODOMETER : 43|20@0+ (1,0) [0|1048575] "" XXX + +BO_ 1556 BLINKERS_STATE: 8 XXX + SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX + SG_ HAZARD_LIGHT : 27|1@0+ (1,0) [0|1] "" XXX + +BO_ 1568 BODY_CONTROL_STATE: 8 XXX + SG_ METER_DIMMED : 38|1@0+ (1,0) [0|1] "" XXX + SG_ PARKING_BRAKE : 60|1@0+ (1,0) [0|1] "" XXX + SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RR : 43|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FR : 44|1@0+ (1,0) [0|1] "" XXX + +BO_ 1570 LIGHT_STALK: 8 SCM + SG_ AUTO_HIGH_BEAM : 37|1@0+ (1,0) [0|1] "" XXX + SG_ FRONT_FOG : 27|1@0+ (1,0) [0|1] "" XXX + SG_ PARKING_LIGHT : 28|1@0+ (1,0) [0|1] "" XXX + SG_ LOW_BEAM : 29|1@0+ (1,0) [0|1] "" XXX + SG_ HIGH_BEAM : 30|1@0+ (1,0) [0|1] "" XXX + SG_ DAYTIME_RUNNING_LIGHT : 31|1@0+ (1,0) [0|1] "" XXX + +BO_ 1571 CERTIFICATION_ECU: 8 CGW SG_ DOOR_LOCK_FEEDBACK_LIGHT : 15|1@0+ (1,0) [0|0] "" XXX SG_ KEYFOB_LOCKING_FEEDBACK_LIGHT : 61|1@0+ (1,0) [0|0] "" XXX SG_ KEYFOB_UNLOCKING_FEEDBACK_LIGHT : 62|1@0+ (1,0) [0|0] "" XXX -CM_ SG_ 36 ACCEL_Y "unit is tbd"; +BO_ 1592 DOOR_LOCKS: 8 XXX + SG_ LOCK_STATUS_CHANGED : 15|1@0+ (1,0) [0|1] "" XXX + SG_ LOCK_STATUS : 20|1@0+ (1,0) [0|1] "" XXX + SG_ LOCKED_VIA_KEYFOB : 23|1@0+ (1,0) [0|1] "" XXX + CM_ SG_ 36 YAW_RATE "verify"; CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; CM_ SG_ 37 STEER_RATE "factor is tbd"; CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; CM_ SG_ 466 CRUISE_STATE "Active state is 8, if standstill is requested will switch to state 11(3 sec timer), after timer is elapsed will switch into state 7(standstill). If plus button was pressed - status 9, minus button pressed - status 10"; -CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isn't perfect"; +CM_ SG_ 467 SET_SPEED "43 km/h are shown as 28 mph, so conversion isn't perfect"; CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; +CM_ SG_ 581 GAS_PEDAL "it seems slightly filtered"; CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; CM_ SG_ 608 STEER_OVERRIDE "set when driver torque exceeds a certain value"; CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; @@ -320,15 +423,31 @@ CM_ SG_ 835 RADAR_DIRTY "Display Clean Radar Sensor message on HUD"; CM_ SG_ 835 ACC_MALFUNCTION "display ACC fault on dash if set to 1"; CM_ SG_ 835 ACC_CUT_IN "Display blinking yellow lead if set to 1"; CM_ SG_ 835 DISTANCE "Display Distance Bars on HUD Permanently"; +CM_ SG_ 835 ITS_CONNECT_LEAD "Displayed when lead car is capable of ITS Connect"; CM_ SG_ 835 ALLOW_LONG_PRESS "Enable Toyota's factory set speed increment behaviour, available on both metrics cars and imperial unit cars"; CM_ SG_ 835 PERMIT_BRAKING "Original ACC has this going high when a car in front is detected. In openpilot and before the PERMIT_BRAKING name, this was 'SET_ME_1' and is hardcoded to be high. Unsure if only informational or has an effect though existing usage in openpilot is to always set it to 1. Originally 'PMTBRKG' in the leaked toyota_2017_ref_pt.dbc file and name expansion speculated to be PerMiT BRaKinG."; CM_ SG_ 835 ACCEL_CMD_ALT "Copy of main ACCEL_CMD, but across 8 bits instead of 16 bits like ACCEL_CMD. Unsure if only informational or has an effect. Likely informational as existing openpilot sets this to 0 and no loss of functionality observed. Originally 'AT_RAW' in leaked toyota_2017_ref_pt.dbc file."; CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; CM_ SG_ 951 BRAKE_LIGHTS_ACC "brake lights when ACC commands decel"; +CM_ SG_ 1009 SET_SPEED "units seem to be whatever the car is set to"; CM_ SG_ 1041 PCS_INDICATOR "Pre-Collision System Indicator"; CM_ SG_ 1041 PCS_SENSITIVITY "Pre-Collision System Sensitivity"; -CM_ SG_ 1042 SET_ME_1 "unclear what this is, but it's always 1 in drive traces"; -CM_ SG_ 1042 REPEATED_BEEPS "recommended for fcw and other important alerts"; +CM_ SG_ 1042 LDA_SA_TOGGLE "LDA Steering Assist Toggle"; +CM_ SG_ 1042 LDW_EXIST "Unclear what this is, it's usually set to 0"; +CM_ SG_ 1042 LDA_SENSITIVITY "LDA Sensitivity"; +CM_ SG_ 1042 LDA_ON_MESSAGE "Display LDA Turned ON message"; +CM_ SG_ 1042 REPEATED_BEEPS "LDA audible warning"; +CM_ SG_ 1042 LDA_UNAVAILABLE_QUIET "LDA toggles and sensitivity settings are greyed out if set to 1"; +CM_ SG_ 1042 LDA_SPEED_TOO_LOW "length is 3 bits in the leaked DBC, displays LDA unavailable below approx 50 km/h if set to 1"; +CM_ SG_ 1042 LDA_FRONT_CAMERA_BLOCKED "originally LDAFCVB, LDA related settings are greyed out if set to 1"; +CM_ SG_ 1042 TAKE_CONTROL "Please Control Steering Wheel warning"; +CM_ SG_ 1042 LANE_SWAY_TOGGLE "Lane Sway Warning System SWS Switch"; +CM_ SG_ 1042 LANE_SWAY_WARNING "Lane Sway Warning System Triggered"; +CM_ SG_ 1042 LANE_SWAY_FLD "Unknown signal for Lane Sway Warning System, set to 7 on stock system when SWS is enabled, 0 when SWS is disabled"; +CM_ SG_ 1042 LANE_SWAY_BUZZER "Similar to TWO_BEEPS"; +CM_ SG_ 1042 SET_ME_X01 "empty bit on leaked dbc, always set to 1 during normal operations"; +CM_ SG_ 1042 SET_ME_X02 "empty bit on leaked dbc, always set to 2 during normal operations"; +CM_ SG_ 1083 STATE "when the dashboard button is pressed, the value changes from zero to non-zero"; CM_ SG_ 1161 SPDVAL1 "Numbers 0-199 is displayed, 200-254 displays circle without number and 255 is for no limit."; CM_ SG_ 1161 SYNCID1 "counter from 1 to f at 1 Hz"; CM_ SG_ 1161 SPDVAL2 "conditional speed value 70"; @@ -343,8 +462,15 @@ CM_ SG_ 1163 OVSPVALL "-5 at start then 2 after 2 seconds"; CM_ SG_ 1163 OVSPVALM "-5 at start then 5 after 2 seconds"; CM_ SG_ 1163 OVSPVALH "-5 at start then 10 after 2 seconds"; CM_ SG_ 1163 TSRSPU "always 1"; +CM_ SG_ 1552 METER_SLIDER_BRIGHTNESS_PCT "Combination display brightness setting, scales from 12 per cent to 100 per cent, reflects combination meter settings only, not linked with headlight state"; +CM_ SG_ 1552 METER_SLIDER_LOW_BRIGHTNESS "Combination display low brightness mode, also controls footwell lighting"; +CM_ SG_ 1552 METER_SLIDER_DIMMED "Combination display slider not at max, reflects combination meter settings only, not linked with headlight state"; CM_ SG_ 1553 ODOMETER "Unit is dependent upon units signal"; +CM_ SG_ 1592 LOCK_STATUS_CHANGED "1 on rising edge of lock/unlocking"; +CM_ SG_ 1592 LOCK_STATUS "The next 3 bits always seem to follow this signal."; +CM_ SG_ 1592 LOCKED_VIA_KEYFOB "1 for as long as car is locked with key fob or door handle touch"; +VAL_ 295 GEAR 0 "P" 1 "R" 2 "N" 3 "D" 4 "B"; VAL_ 466 CRUISE_STATE 11 "timer_3sec" 10 "adaptive click down" 9 "adaptive click up" 8 "adaptive engaged" 7 "standstill" 6 "non-adaptive click up" 5 "non-adaptive click down" 4 "non-adaptive hold down" 3 "non-adaptive hold up" 2 "non-adaptive being engaged" 1 "non-adaptive engaged" 0 "off"; VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok"; VAL_ 614 STATE 3 "enabled" 1 "disabled"; @@ -355,99 +481,55 @@ VAL_ 835 ACC_MALFUNCTION 1 "faulted" 0 "ok"; VAL_ 835 ACC_CUT_IN 1 "CUT-IN Detected" 0 "clear"; VAL_ 835 ALLOW_LONG_PRESS 2 "set speed increase by 5 speed units regardless" 1 "set speed increase by 1 speed unit on short press, 5 speed units on long press"; VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted"; +VAL_ 956 SPORT_ON 0 "off" 1 "on"; +VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; +VAL_ 956 SPORT_GEAR_ON 0 "off" 1 "on"; +VAL_ 956 SPORT_GEAR 1 "S1" 2 "S2" 3 "S3" 4 "S4" 5 "S5" 6 "S6"; +VAL_ 956 ECON_ON 0 "off" 1 "on"; +VAL_ 956 B_GEAR_ENGAGED 0 "off" 1 "on"; +VAL_ 956 DRIVE_ENGAGED 0 "off" 1 "on"; +VAL_ 1005 REVERSE_CAMERA_GUIDELINES 3 "No guidelines" 2 "Static guidelines" 1 "Active guidelines"; VAL_ 1041 PCS_INDICATOR 2 "PCS Faulted" 1 "PCS Turned Off By User" 0 "PCS Enabled"; VAL_ 1041 PCS_SENSITIVITY 64 "high sensitivity" 128 "mid sensitivity" 192 "low sensitivity" 0 "off"; VAL_ 1042 LDA_ALERT 3 "hold with continuous beep" 2 "LDA unavailable" 1 "hold" 0 "none"; -VAL_ 1042 BARRIERS 3 "both" 2 "right" 1 "left" 0 "none"; +VAL_ 1042 BARRIERS 3 "left" 2 "right" 1 "both" 0 "none"; VAL_ 1042 RIGHT_LINE 3 "orange" 2 "faded" 1 "solid" 0 "none"; +VAL_ 1042 LKAS_STATUS 1 "on" 0 "off"; VAL_ 1042 LEFT_LINE 3 "orange" 2 "faded" 1 "solid" 0 "none"; -VAL_ 1553 UNITS 1 "km" 2 "miles"; -VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left"; +VAL_ 1042 LDA_ON_MESSAGE 2 "Lane Departure Alert Turned ON, Steering Assist Inactive" 1 "Lane Departure Alert Turned ON, Steering Assist Active" 0 "clear"; +VAL_ 1042 LDA_SA_TOGGLE 2 "steering assist off" 1 "steering assist on"; +VAL_ 1042 LDA_SENSITIVITY 2 "standard" 1 "high" 0 "undefined"; +VAL_ 1042 LDA_SPEED_TOO_LOW 1 "lda unavailable, speed too low" 0 "ok"; +VAL_ 1042 LDA_FRONT_CAMERA_BLOCKED 1 "lda unavailable" 0 "ok"; +VAL_ 1042 TAKE_CONTROL 1 "take control" 0 "ok"; +VAL_ 1042 LANE_SWAY_WARNING 3 "ok" 2 "orange please take a break" 1 "prompt would you like to take a break" 0 "ok"; +VAL_ 1042 LANE_SWAY_BUZZER 3 "ok" 2 "beep twice" 1 "beep twice" 0 "ok"; VAL_ 1161 TSGN1 1 "speed sign" 0 "none"; VAL_ 1161 TSGN2 1 "speed sign" 0 "none"; VAL_ 1161 SPLSGN2 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none"; VAL_ 1162 TSGN3 0 "none" 1 "speed sign" 2 "0 unlimited" 7 "unlimited" 16 "highway" 17 "no highway" 18 "motorway" 19 "no motorway" 20 "in city" 21 "outside city" 22 "pedestrian area" 23 "no pedestrian area" 65 "no overtaking left" 66 "no overtaking right" 67 "overtaking allowed again" 81 "no right turn" 97 "stop" 105 "yield" 113 "stop" 114 "yield us" 129 "no entry" 138 "no entry tss2" 145 "do not enter"; VAL_ 1162 SPLSGN3 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none"; +VAL_ 1552 METER_SLIDER_LOW_BRIGHTNESS 1 "Low brightness mode, footwell lights off" 0 "Normal mode, footwell lights on"; +VAL_ 1552 METER_SLIDER_DIMMED 1 "Dimmed" 0 "Not Dimmed"; +VAL_ 1553 UNITS 1 "km" 2 "miles"; +VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left"; +VAL_ 1592 LOCK_STATUS 0 "locked" 1 "unlocked"; - - - -CM_ "Imported file _comma.dbc starts here"; -BO_ 359 STEERING_IPAS_COMMA: 8 IPAS - SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX - SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX - SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX - SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant"; - - BO_ 512 GAS_COMMAND: 6 EON - SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR - SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR - SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR - - BO_ 513 GAS_SENSOR: 6 INTERCEPTOR - SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON - SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON - SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON - - VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; - -BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX - SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX - -CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss"; - -BO_ 767 SDSU: 8 XXX - SG_ FD_BUTTON : 7|1@0+ (1,0) [0|1] "" XXX - -CM_ "BO_ SDSU: The sDSU is a modified DSU for use in TSS1 Toyotas. Learn more: https://github.com/wocsor/panda/tree/smart_dsu"; - -CM_ SG_ 767 FD_BUTTON "The follow distance button signal as forwarded by the sdsu"; - -CM_ "lexus_ct200h_2018_pt.dbc starts here"; - - +CM_ "toyota_new_mc_pt.dbc starts here"; BO_ 548 BRAKE_MODULE: 8 XXX SG_ BRAKE_PRESSURE : 43|12@0+ (1,0) [0|4047] "" XXX SG_ BRAKE_PRESSED : 5|1@0+ (1,0) [0|1] "" XXX -BO_ 581 GAS_PEDAL: 5 XXX - SG_ GAS_PEDAL : 23|8@0+ (0.005,0) [0|1] "" XXX - -BO_ 608 STEER_TORQUE_SENSOR: 8 XXX - SG_ STEER_TORQUE_EPS : 47|16@0- (1,0) [-20000|20000] "" XXX - SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX - SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - SG_ STEER_ANGLE : 31|16@0- (0.0573,0) [-500|500] "" XXX - BO_ 610 EPS_STATUS: 5 EPS SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX -BO_ 956 GEAR_PACKET: 8 XXX - SG_ SPORT_ON : 2|1@0+ (1,0) [0|1] "" XXX - SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX - SG_ ECON_ON : 40|1@0+ (1,0) [0|1] "" XXX - CM_ SG_ 548 BRAKE_PRESSURE "seems prop to pedal force"; CM_ SG_ 548 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; -CM_ SG_ 581 GAS_PEDAL "it seems slightly filtered"; CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; + VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled"; VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby"; -VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; -VAL_ 956 SPORT_ON 0 "off" 1 "on"; -VAL_ 956 ECON_ON 0 "off" 1 "on"; diff --git a/opendbc/toyota_nodsu_hybrid_pt_generated.dbc b/opendbc/toyota_nodsu_hybrid_pt_generated.dbc deleted file mode 100644 index 8102d48cc..000000000 --- a/opendbc/toyota_nodsu_hybrid_pt_generated.dbc +++ /dev/null @@ -1,484 +0,0 @@ -CM_ "AUTOGENERATED FILE, DO NOT EDIT"; - - -CM_ "Imported file _toyota_2017.dbc starts here"; -VERSION "" - - -NS_ : - NS_DESC_ - CM_ - BA_DEF_ - BA_ - VAL_ - CAT_DEF_ - CAT_ - FILTER - BA_DEF_DEF_ - EV_DATA_ - ENVVAR_DATA_ - SGTYPE_ - SGTYPE_VAL_ - BA_DEF_SGTYPE_ - BA_SGTYPE_ - SIG_TYPE_REF_ - VAL_TABLE_ - SIG_GROUP_ - SIG_VALTYPE_ - SIGTYPE_VALTYPE_ - BO_TX_BU_ - BA_DEF_REL_ - BA_REL_ - BA_DEF_DEF_REL_ - BU_SG_REL_ - BU_EV_REL_ - BU_BO_REL_ - SG_MUL_VAL_ - -BS_: - -BU_: XXX DSU HCU EPS IPAS CGW - -BO_ 36 KINEMATICS: 8 XXX - SG_ ACCEL_Y : 33|10@0+ (0.03589,-18.375) [0|65535] "m/s^2" XXX - SG_ YAW_RATE : 1|10@0+ (0.244,-125) [0|65535] "deg/sec" XXX - SG_ STEERING_TORQUE : 17|10@0+ (1,-512) [0|65535] "" XXX - -BO_ 37 STEER_ANGLE_SENSOR: 8 XXX - SG_ STEER_ANGLE : 3|12@0- (1.5,0) [-500|500] "deg" XXX - SG_ STEER_FRACTION : 39|4@0- (0.1,0) [-0.7|0.7] "deg" XXX - SG_ STEER_RATE : 35|12@0- (1,0) [-2000|2000] "deg/s" XXX - -BO_ 166 BRAKE: 8 XXX - SG_ BRAKE_AMOUNT : 7|8@0+ (1,0) [0|255] "" XXX - SG_ BRAKE_PEDAL : 23|8@0+ (1,0) [0|255] "" XXX - -BO_ 170 WHEEL_SPEEDS: 8 XXX - SG_ WHEEL_SPEED_FR : 7|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_FL : 23|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_RR : 39|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_RL : 55|16@0+ (0.01,-67.67) [0|250] "kph" XXX - -BO_ 180 SPEED: 8 XXX - SG_ ENCODER : 39|8@0+ (1,0) [0|255] "" XXX - SG_ SPEED : 47|16@0+ (0.01,0) [0|250] "kph" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 353 DSU_SPEED: 7 XXX - SG_ FORWARD_SPEED : 15|16@0- (0.00390625,-30) [0|255] "kph" XXX - -BO_ 452 ENGINE_RPM: 8 CGW - SG_ RPM : 7|16@0- (0.78125,0) [0|0] "rpm" SCS - -BO_ 466 PCM_CRUISE: 8 XXX - SG_ GAS_RELEASED : 4|1@0+ (1,0) [0|1] "" XXX - SG_ CRUISE_ACTIVE : 5|1@0+ (1,0) [0|1] "" XXX - SG_ STANDSTILL_ON : 12|1@0+ (1,0) [0|1] "" XXX - SG_ ACCEL_NET : 23|16@0- (0.001,0) [-20|20] "m/s2" XXX - SG_ CRUISE_STATE : 55|4@0+ (1,0) [0|15] "" XXX - SG_ CANCEL_REQ : 49|1@1+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 467 PCM_CRUISE_2: 8 XXX - SG_ MAIN_ON : 15|1@0+ (1,0) [0|1] "" XXX - SG_ LOW_SPEED_LOCKOUT : 14|2@0+ (1,0) [0|3] "kph" XXX - SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "kph" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 552 ACCELEROMETER: 8 XXX - SG_ ACCEL_Z : 22|15@0- (1,0) [0|32767] "" XXX - SG_ ACCEL_X : 6|15@0- (0.001,0) [-20|20] "m/s2" XXX - -BO_ 560 BRAKE_MODULE2: 7 XXX - SG_ BRAKE_PRESSED : 26|1@0+ (1,0) [0|1] "" XXX - -BO_ 614 STEERING_IPAS: 8 IPAS - SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX - SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX - SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX - SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 643 PRE_COLLISION: 7 DSU - SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 15|8@0+ (1,0) [0|255] "" XXX - SG_ FORCE : 23|16@0- (2,0) [0|255] "N" XXX - SG_ SET_ME_X002 : 33|8@0+ (1,0) [0|3] "" XXX - SG_ BRAKE_STATUS : 39|3@0+ (1,0) [0|255] "" XXX - SG_ STATE : 36|3@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X003 : 40|1@0+ (1,0) [0|1] "" XXX - SG_ PRECOLLISION_ACTIVE : 41|1@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 55|8@0+ (1,0) [0|255] "" XXX - -BO_ 740 STEERING_LKA: 5 XXX - SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX - SG_ STEER_REQUEST : 0|1@0+ (1,0) [0|1] "" XXX - SG_ COUNTER : 6|6@0+ (1,0) [0|63] "" XXX - SG_ SET_ME_1 : 7|1@0+ (1,0) [0|1] "" XXX - SG_ STEER_TORQUE_CMD : 15|16@0- (1,0) [0|65535] "" XXX - SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX - -BO_ 742 LEAD_INFO: 8 DSU - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" HCU - SG_ LEAD_REL_SPEED : 23|12@0- (0.025,0) [-100|100] "m/s" HCU - SG_ LEAD_LONG_DIST : 7|13@0+ (0.05,0) [0|300] "m" HCU - -BO_ 835 ACC_CONTROL: 8 DSU - SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU - SG_ ACC_MALFUNCTION : 18|1@0+ (1,0) [0|0] "" XXX - SG_ ACC_CUT_IN : 25|1@0+ (1,0) [0|1] "" XXX - SG_ ALLOW_LONG_PRESS : 17|2@0+ (1,0) [0|2] "" XXX - SG_ ACC_TYPE : 23|2@0+ (1,0) [0|3] "" HCU - SG_ DISTANCE : 20|1@0+ (1,0) [0|1] "" XXX - SG_ MINI_CAR : 21|1@0+ (1,0) [0|1] "" XXX - SG_ PERMIT_BRAKING : 30|1@0+ (1,0) [0|1] "" HCU - SG_ RELEASE_STANDSTILL : 31|1@0+ (1,0) [0|1] "" HCU - SG_ CANCEL_REQ : 24|1@0+ (1,0) [0|1] "" HCU - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - SG_ ACCEL_CMD_ALT : 47|8@0- (0.05,0) [0|0] "m/s^2" XXX - SG_ RADAR_DIRTY : 19|1@0+ (1,0) [0|1] "" XXX - -BO_ 836 PRE_COLLISION_2: 8 DSU - SG_ CHECKSUM : 63|8@0+ (1,0) [0|0] "" XXX - -BO_ 869 DSU_CRUISE : 7 DSU - SG_ RES_BTN : 3|1@0+ (1,0) [0|0] "" XXX - SG_ SET_BTN : 2|1@0+ (1,0) [0|0] "" XXX - SG_ CANCEL_BTN : 1|1@0+ (1,0) [0|0] "" XXX - SG_ MAIN_ON : 0|1@0+ (1,0) [0|0] "" XXX - SG_ SET_SPEED : 15|8@0+ (1,0) [0|0] "km/h" XXX - SG_ CRUISE_REQUEST : 31|8@0+ (100,-12800) [0|0] "N" XXX - SG_ LEAD_DISTANCE : 39|8@0+ (1,0) [0|0] "m" XXX - -BO_ 921 PCM_CRUISE_SM: 8 XXX - SG_ MAIN_ON : 4|1@0+ (1,0) [0|1] "" XXX - SG_ CRUISE_CONTROL_STATE : 11|4@0+ (1,0) [0|15] "" XXX - SG_ DISTANCE_LINES : 14|2@0+ (1,0) [0|3] "" XXX - SG_ UI_SET_SPEED : 31|8@0+ (1,0) [0|255] "" XXX - -BO_ 951 ESP_CONTROL: 8 ESP - SG_ TC_DISABLED : 13|1@0+ (1,0) [0|1] "" XXX - SG_ VSC_DISABLED : 12|2@0+ (1,0) [0|1] "" XXX - SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" XXX - SG_ BRAKE_HOLD_ENABLED : 33|1@1+ (1,0) [0|1] "" XXX - SG_ BRAKE_HOLD_ACTIVE : 36|1@0+ (1,0) [0|1] "" XXX - -BO_ 1020 SOLAR_SENSOR: 8 XXX - SG_ LUX_SENSOR : 55|13@0+ (1,0) [0|0] "" XXX - -BO_ 1041 ACC_HUD: 8 DSU - SG_ PCS_INDICATOR : 7|2@0+ (1,0) [0|3] "" XXX - SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X20 : 15|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X10 : 39|8@0+ (1,0) [0|1] "" XXX - SG_ PCS_OFF : 40|1@0+ (1,0) [0|0] "" XXX - SG_ PCS_SENSITIVITY : 55|8@0+ (1,0) [0|1] "" XXX - -BO_ 1042 LKAS_HUD: 8 XXX - SG_ BARRIERS : 1|2@0+ (1,0) [0|3] "" XXX - SG_ RIGHT_LINE : 3|2@0+ (1,0) [0|3] "" XXX - SG_ LEFT_LINE : 5|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X01 : 7|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X01_2 : 11|2@0+ (1,0) [0|3] "" XXX - SG_ LDA_ALERT : 9|2@0+ (1,0) [0|3] "" XXX - SG_ TWO_BEEPS : 12|1@0+ (1,0) [0|1] "" XXX - SG_ ADJUSTING_CAMERA : 13|1@0+ (1,0) [0|1] "" XXX - SG_ LDA_MALFUNCTION : 15|1@0+ (1,0) [0|1] "" XXX - SG_ REPEATED_BEEPS : 32|1@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X0C : 23|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X2C : 47|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X38 : 55|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X02 : 63|8@0+ (1,0) [0|1] "" XXX - -BO_ 1043 TIME : 8 CGW - SG_ YEAR : 7|8@0+ (1,0) [0|0] "year" XXX - SG_ MONTH : 15|8@0+ (1,0) [0|0] "month" XXX - SG_ DAY : 23|8@0+ (1,0) [0|0] "day" XXX - SG_ HOUR : 31|8@0+ (1,0) [0|0] "hour" XXX - SG_ MINUTE : 39|8@0+ (1,0) [0|0] "minute" XXX - SG_ GMT_DIFF : 55|1@0+ (1,0) [0|0] "" XXX - SG_ GMTDIFF_HOURS : 54|4@0+ (1,0) [0|0] "hours" XXX - SG_ GMTDIFF_MINUTES : 50|6@0+ (1,0) [0|0] "minutes" XXX - SG_ SUMMER : 60|1@0+ (1,0) [0|0] "" XXX - -BO_ 1408 VIN_PART_1: 8 CGW - SG_ VIN_1 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_2 : 15|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_3 : 23|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_4 : 31|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_5 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_6 : 47|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_7 : 55|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_8 : 63|8@0+ (1,0) [0|0] "" XXX - -BO_ 1409 VIN_PART_2: 8 CGW - SG_ VIN_9 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_10 : 15|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_11 : 23|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_12 : 31|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_13 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_14 : 47|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_15 : 55|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_16 : 63|8@0+ (1,0) [0|0] "" XXX - -BO_ 1410 VIN_PART_3: 8 CGW - SG_ VIN_17 : 7|8@0+ (1,0) [0|0] "" XXX - -BO_ 1553 UI_SETTING: 8 XXX - SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX - SG_ ODOMETER : 43|20@0+ (1,0) [0|1048575] "" XXX - -BO_ 1556 STEERING_LEVERS: 8 XXX - SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX - SG_ HAZARD_LIGHT : 27|1@0+ (1,0) [0|1] "" XXX - -BO_ 1568 SEATS_DOORS: 8 XXX - SG_ METER_DIMMED : 38|1@0+ (1,0) [0|1] "" XXX - SG_ PARKING_BRAKE : 60|1@0+ (1,0) [0|1] "" XXX - SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_RR : 43|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_FR : 44|1@0+ (1,0) [0|1] "" XXX - -BO_ 1570 LIGHT_STALK: 8 SCM - SG_ AUTO_HIGH_BEAM : 37|1@0+ (1,0) [0|1] "" XXX - SG_ FRONT_FOG : 27|1@0+ (1,0) [0|1] "" XXX - SG_ PARKING_LIGHT : 28|1@0+ (1,0) [0|1] "" XXX - SG_ LOW_BEAM : 29|1@0+ (1,0) [0|1] "" XXX - SG_ HIGH_BEAM : 30|1@0+ (1,0) [0|1] "" XXX - SG_ DAYTIME_RUNNING_LIGHT : 31|1@0+ (1,0) [0|1] "" XXX - -BO_ 1161 RSA1: 8 FCM - SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY1 : 12|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT1 : 9|2@0+ (1,0) [0|0] "" XXX - SG_ SPDVAL1 : 23|8@0+ (1,0) [0|0] "kph" XXX - SG_ SPLSGN1 : 31|4@0+ (1,0) [0|0] "" XXX - SG_ SPLSGN2 : 27|4@0+ (1,0) [0|0] "" XXX - SG_ TSGN2 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY2 : 44|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT2 : 41|2@0+ (1,0) [0|0] "" XXX - SG_ SPDVAL2 : 55|8@0+ (1,0) [0|0] "" XXX - SG_ BZRRQ_P : 63|2@0+ (1,0) [0|0] "" XXX - SG_ BZRRQ_A : 61|2@0+ (1,0) [0|0] "" XXX - SG_ SYNCID1 : 59|4@0+ (1,0) [0|0] "" XXX - -BO_ 1162 RSA2: 8 FCM - SG_ TSGN3 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY3 : 12|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT3 : 9|2@0+ (1,0) [0|0] "" XXX - SG_ SPLSGN3 : 31|4@0+ (1,0) [0|0] "" XXX - SG_ SPLSGN4 : 27|4@0+ (1,0) [0|0] "" XXX - SG_ TSGN4 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY4 : 44|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT4 : 41|2@0+ (1,0) [0|0] "" XXX - SG_ DPSGNREQ : 54|1@0+ (1,0) [0|0] "" XXX - SG_ SGNNUMP : 53|3@0+ (1,0) [0|0] "" XXX - SG_ SGNNUMA : 50|3@0+ (1,0) [0|0] "" XXX - SG_ SPDUNT : 63|2@0+ (1,0) [0|0] "" XXX - SG_ TSRWMSG : 61|2@0+ (1,0) [0|0] "" XXX - SG_ SYNCID2 : 59|4@0+ (1,0) [0|0] "" XXX - -BO_ 1163 RSA3: 8 FCM - SG_ TSREQPD : 7|1@0+ (1,0) [0|0] "" XXX - SG_ TSRMSW : 6|1@0+ (1,0) [0|0] "" XXX - SG_ OTSGNNTM : 5|2@0+ (1,0) [0|0] "" XXX - SG_ NTLVLSPD : 3|2@0+ (1,0) [0|0] "" XXX - SG_ OVSPNTM : 1|2@0+ (1,0) [0|0] "" XXX - SG_ OVSPVALL : 11|4@0+ (1,-5) [0|0] "" XXX - SG_ OVSPVALM : 19|4@0+ (1,-5) [0|0] "" XXX - SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX - SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" XXX - -BO_ 1571 CENTRAL_GATEWAY_UNIT: 8 CGW - SG_ DOOR_LOCK_FEEDBACK_LIGHT : 15|1@0+ (1,0) [0|0] "" XXX - SG_ KEYFOB_LOCKING_FEEDBACK_LIGHT : 61|1@0+ (1,0) [0|0] "" XXX - SG_ KEYFOB_UNLOCKING_FEEDBACK_LIGHT : 62|1@0+ (1,0) [0|0] "" XXX - -CM_ SG_ 36 ACCEL_Y "unit is tbd"; -CM_ SG_ 36 YAW_RATE "verify"; -CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; -CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; -CM_ SG_ 37 STEER_RATE "factor is tbd"; -CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; -CM_ SG_ 466 CRUISE_STATE "Active state is 8, if standstill is requested will switch to state 11(3 sec timer), after timer is elapsed will switch into state 7(standstill). If plus button was pressed - status 9, minus button pressed - status 10"; -CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isn't perfect"; -CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; -CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; -CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; -CM_ SG_ 608 STEER_OVERRIDE "set when driver torque exceeds a certain value"; -CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; -CM_ SG_ 643 COUNTER "only used on cars that use this msg for cruise control"; -CM_ SG_ 643 BRAKE_STATUS "only used on cars that use this msg for cruise control"; -CM_ SG_ 643 PRECOLLISION_ACTIVE "set 0.5s before any braking"; -CM_ SG_ 835 ACC_TYPE "if 2, car is likely to have a permanent low speed lockout. 1 is ok"; -CM_ SG_ 835 RADAR_DIRTY "Display Clean Radar Sensor message on HUD"; -CM_ SG_ 835 ACC_MALFUNCTION "display ACC fault on dash if set to 1"; -CM_ SG_ 835 ACC_CUT_IN "Display blinking yellow lead if set to 1"; -CM_ SG_ 835 DISTANCE "Display Distance Bars on HUD Permanently"; -CM_ SG_ 835 ALLOW_LONG_PRESS "Enable Toyota's factory set speed increment behaviour, available on both metrics cars and imperial unit cars"; -CM_ SG_ 835 PERMIT_BRAKING "Original ACC has this going high when a car in front is detected. In openpilot and before the PERMIT_BRAKING name, this was 'SET_ME_1' and is hardcoded to be high. Unsure if only informational or has an effect though existing usage in openpilot is to always set it to 1. Originally 'PMTBRKG' in the leaked toyota_2017_ref_pt.dbc file and name expansion speculated to be PerMiT BRaKinG."; -CM_ SG_ 835 ACCEL_CMD_ALT "Copy of main ACCEL_CMD, but across 8 bits instead of 16 bits like ACCEL_CMD. Unsure if only informational or has an effect. Likely informational as existing openpilot sets this to 0 and no loss of functionality observed. Originally 'AT_RAW' in leaked toyota_2017_ref_pt.dbc file."; -CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; -CM_ SG_ 951 BRAKE_LIGHTS_ACC "brake lights when ACC commands decel"; -CM_ SG_ 1041 PCS_INDICATOR "Pre-Collision System Indicator"; -CM_ SG_ 1041 PCS_SENSITIVITY "Pre-Collision System Sensitivity"; -CM_ SG_ 1042 SET_ME_1 "unclear what this is, but it's always 1 in drive traces"; -CM_ SG_ 1042 REPEATED_BEEPS "recommended for fcw and other important alerts"; -CM_ SG_ 1161 SPDVAL1 "Numbers 0-199 is displayed, 200-254 displays circle without number and 255 is for no limit."; -CM_ SG_ 1161 SYNCID1 "counter from 1 to f at 1 Hz"; -CM_ SG_ 1161 SPDVAL2 "conditional speed value 70"; -CM_ SG_ 1162 SGNNUMP "1 if SPDVAL1 is set, otherwise 0"; -CM_ SG_ 1162 SYNCID2 "counter from 1 to f at 1 Hz"; -CM_ SG_ 1163 TSREQPD "always 1"; -CM_ SG_ 1163 TSRMSW "always 1"; -CM_ SG_ 1163 OTSGNNTM "always 3"; -CM_ SG_ 1163 NTLVLSPD "always 3"; -CM_ SG_ 1163 OVSPNTM "always 3"; -CM_ SG_ 1163 OVSPVALL "-5 at start then 2 after 2 seconds"; -CM_ SG_ 1163 OVSPVALM "-5 at start then 5 after 2 seconds"; -CM_ SG_ 1163 OVSPVALH "-5 at start then 10 after 2 seconds"; -CM_ SG_ 1163 TSRSPU "always 1"; -CM_ SG_ 1553 ODOMETER "Unit is dependent upon units signal"; - -VAL_ 466 CRUISE_STATE 11 "timer_3sec" 10 "adaptive click down" 9 "adaptive click up" 8 "adaptive engaged" 7 "standstill" 6 "non-adaptive click up" 5 "non-adaptive click down" 4 "non-adaptive hold down" 3 "non-adaptive hold up" 2 "non-adaptive being engaged" 1 "non-adaptive engaged" 0 "off"; -VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok"; -VAL_ 614 STATE 3 "enabled" 1 "disabled"; -VAL_ 614 DIRECTION_CMD 3 "right" 2 "center" 1 "left"; -VAL_ 643 STATE 0 "normal" 1 "adaptive_cruise_control" 3 "emergency_braking"; -VAL_ 835 ACC_TYPE 2 "permanent low speed lockout" 1 "ok"; -VAL_ 835 ACC_MALFUNCTION 1 "faulted" 0 "ok"; -VAL_ 835 ACC_CUT_IN 1 "CUT-IN Detected" 0 "clear"; -VAL_ 835 ALLOW_LONG_PRESS 2 "set speed increase by 5 speed units regardless" 1 "set speed increase by 1 speed unit on short press, 5 speed units on long press"; -VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted"; -VAL_ 1041 PCS_INDICATOR 2 "PCS Faulted" 1 "PCS Turned Off By User" 0 "PCS Enabled"; -VAL_ 1041 PCS_SENSITIVITY 64 "high sensitivity" 128 "mid sensitivity" 192 "low sensitivity" 0 "off"; -VAL_ 1042 LDA_ALERT 3 "hold with continuous beep" 2 "LDA unavailable" 1 "hold" 0 "none"; -VAL_ 1042 BARRIERS 3 "both" 2 "right" 1 "left" 0 "none"; -VAL_ 1042 RIGHT_LINE 3 "orange" 2 "faded" 1 "solid" 0 "none"; -VAL_ 1042 LEFT_LINE 3 "orange" 2 "faded" 1 "solid" 0 "none"; -VAL_ 1553 UNITS 1 "km" 2 "miles"; -VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left"; -VAL_ 1161 TSGN1 1 "speed sign" 0 "none"; -VAL_ 1161 TSGN2 1 "speed sign" 0 "none"; -VAL_ 1161 SPLSGN2 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none"; -VAL_ 1162 TSGN3 0 "none" 1 "speed sign" 2 "0 unlimited" 7 "unlimited" 16 "highway" 17 "no highway" 18 "motorway" 19 "no motorway" 20 "in city" 21 "outside city" 22 "pedestrian area" 23 "no pedestrian area" 65 "no overtaking left" 66 "no overtaking right" 67 "overtaking allowed again" 81 "no right turn" 97 "stop" 105 "yield" 113 "stop" 114 "yield us" 129 "no entry" 138 "no entry tss2" 145 "do not enter"; -VAL_ 1162 SPLSGN3 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none"; - - - - -CM_ "Imported file _comma.dbc starts here"; -BO_ 359 STEERING_IPAS_COMMA: 8 IPAS - SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX - SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX - SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX - SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant"; - - BO_ 512 GAS_COMMAND: 6 EON - SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR - SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR - SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR - - BO_ 513 GAS_SENSOR: 6 INTERCEPTOR - SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON - SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON - SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON - - VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; - -BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX - SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX - -CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss"; - -BO_ 767 SDSU: 8 XXX - SG_ FD_BUTTON : 7|1@0+ (1,0) [0|1] "" XXX - -CM_ "BO_ SDSU: The sDSU is a modified DSU for use in TSS1 Toyotas. Learn more: https://github.com/wocsor/panda/tree/smart_dsu"; - -CM_ SG_ 767 FD_BUTTON "The follow distance button signal as forwarded by the sdsu"; - - -CM_ "Imported file _toyota_nodsu_common.dbc starts here"; -BO_ 401 STEERING_LTA: 8 XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - SG_ SETME_X3 : 29|2@0+ (1,0) [0|3] "" XXX - SG_ PERCENTAGE : 39|8@0+ (1,0) [0|255] "" XXX - SG_ SETME_X64 : 47|8@0+ (1,0) [0|255] "" XXX - SG_ ANGLE : 55|8@0- (0.5,0) [0|255] "" XXX - SG_ STEER_ANGLE_CMD : 15|16@0- (0.0573,0) [-540|540] "" XXX - SG_ STEER_REQUEST : 25|1@0+ (1,0) [0|1] "" XXX - SG_ BIT : 30|1@0+ (1,0) [0|1] "" XXX - SG_ COUNTER : 6|6@0+ (1,0) [0|255] "" XXX - SG_ STEER_REQUEST_2 : 0|1@0+ (1,0) [0|1] "" XXX - SG_ SETME_X1 : 7|1@0+ (1,0) [0|1] "" XXX - -BO_ 1014 BSM: 8 XXX - SG_ L_ADJACENT : 0|1@0+ (1,0) [0|1] "" XXX - SG_ L_APPROACHING : 8|1@0+ (1,0) [0|1] "" XXX - SG_ R_ADJACENT : 1|1@0+ (1,0) [0|1] "" XXX - SG_ R_APPROACHING : 10|1@0+ (1,0) [0|1] "" XXX - SG_ ADJACENT_ENABLED : 7|1@0+ (1,0) [0|1] "" XXX - SG_ APPROACHING_ENABLED : 15|1@0+ (1,0) [0|1] "" XXX - -CM_ SG_ 1014 L_ADJACENT "vehicle adjacent left side of car. enabled above 10mph, regardless of ADJACENT_ENABLED or APPROACHING_ENABLED"; -CM_ SG_ 1014 L_APPROACHING "vehicle approaching from left side of car. enabled above 10mph, regardless of ADJACENT_ENABLED or APPROACHING_ENABLED"; -CM_ SG_ 1014 R_ADJACENT "vehicle adjacent right side of car. enabled above 10mph, regardless of ADJACENT_ENABLED or APPROACHING_ENABLED"; -CM_ SG_ 1014 R_APPROACHING "vehicle approaching from right side of car. enabled above 10mph, regardless of ADJACENT_ENABLED or APPROACHING_ENABLED"; -CM_ SG_ 1014 ADJACENT_ENABLED "when BSM is enabled in settings, this is on along with APPROACHING_ENABLED. this controls bsm alert visibility"; -CM_ SG_ 1014 APPROACHING_ENABLED "when BSM is enabled in settings, this is on along with ADJACENT_ENABLED. this controls bsm alert visibility"; - -CM_ "toyota_nodsu_hybrid_pt.dbc starts here"; - - - - -BO_ 295 GEAR_PACKET: 8 XXX - SG_ CAR_MOVEMENT : 39|8@0- (1,0) [0|255] "" XXX - SG_ COUNTER : 55|8@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - SG_ GEAR : 47|4@0+ (1,0) [0|15] "" XXX - -BO_ 550 BRAKE_MODULE: 8 XXX - SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|511] "" XXX - SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|511] "" XXX - SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|1] "" XXX - -BO_ 581 GAS_PEDAL: 8 XXX - SG_ GAS_PEDAL : 23|8@0+ (0.005,0) [0|1] "" XXX - -BO_ 608 STEER_TORQUE_SENSOR: 8 XXX - SG_ STEER_TORQUE_EPS : 47|16@0- (0.73,0) [-20000|20000] "" XXX - SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX - SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - SG_ STEER_ANGLE : 31|16@0- (0.0573,0) [-500|500] "" XXX - -BO_ 610 EPS_STATUS: 8 EPS - SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX - SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX - SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -CM_ SG_ 548 BRAKE_PRESSURE "seems prop to pedal force"; -CM_ SG_ 548 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; -CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; -CM_ SG_ 581 GAS_PEDAL "it seems slightly filtered"; -VAL_ 295 GEAR 0 "P" 1 "R" 2 "N" 3 "D" 4 "B"; -VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled"; -VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby"; diff --git a/opendbc/toyota_nodsu_pt_generated.dbc b/opendbc/toyota_nodsu_pt_generated.dbc index 58ca9c51a..858690106 100644 --- a/opendbc/toyota_nodsu_pt_generated.dbc +++ b/opendbc/toyota_nodsu_pt_generated.dbc @@ -1,6 +1,47 @@ CM_ "AUTOGENERATED FILE, DO NOT EDIT"; +CM_ "Imported file _comma.dbc starts here"; +BO_ 359 STEERING_IPAS_COMMA: 8 IPAS + SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX + SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX + SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant"; + +BO_ 512 GAS_COMMAND: 6 EON + SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR + SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR + SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR + SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR + SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR + +BO_ 513 GAS_SENSOR: 6 INTERCEPTOR + SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON + SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON + SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON + SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON + +VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; + +BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX + SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX + +CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss"; + +BO_ 767 SDSU: 8 XXX + SG_ FD_BUTTON : 7|1@0+ (1,0) [0|1] "" XXX + +CM_ "BO_ SDSU: The sDSU is a modified DSU for use in TSS1 Toyotas. Learn more: https://github.com/wocsor/panda/tree/smart_dsu"; +CM_ SG_ 767 FD_BUTTON "The follow distance button signal as forwarded by the sdsu"; + + CM_ "Imported file _toyota_2017.dbc starts here"; VERSION "" @@ -37,11 +78,11 @@ NS_ : BS_: -BU_: XXX DSU HCU EPS IPAS CGW +BU_: XXX DSU HCU EPS IPAS CGW BGM BO_ 36 KINEMATICS: 8 XXX SG_ ACCEL_Y : 33|10@0+ (0.03589,-18.375) [0|65535] "m/s^2" XXX - SG_ YAW_RATE : 1|10@0+ (0.244,-125) [0|65535] "deg/sec" XXX + SG_ YAW_RATE : 1|10@0+ (0.244,-125) [0|65535] "deg/s" XXX SG_ STEERING_TORQUE : 17|10@0+ (1,-512) [0|65535] "" XXX BO_ 37 STEER_ANGLE_SENSOR: 8 XXX @@ -54,18 +95,24 @@ BO_ 166 BRAKE: 8 XXX SG_ BRAKE_PEDAL : 23|8@0+ (1,0) [0|255] "" XXX BO_ 170 WHEEL_SPEEDS: 8 XXX - SG_ WHEEL_SPEED_FR : 7|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_FL : 23|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_RR : 39|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_RL : 55|16@0+ (0.01,-67.67) [0|250] "kph" XXX + SG_ WHEEL_SPEED_FR : 7|16@0+ (0.01,-67.67) [0|250] "km/h" XXX + SG_ WHEEL_SPEED_FL : 23|16@0+ (0.01,-67.67) [0|250] "km/h" XXX + SG_ WHEEL_SPEED_RR : 39|16@0+ (0.01,-67.67) [0|250] "km/h" XXX + SG_ WHEEL_SPEED_RL : 55|16@0+ (0.01,-67.67) [0|250] "km/h" XXX BO_ 180 SPEED: 8 XXX SG_ ENCODER : 39|8@0+ (1,0) [0|255] "" XXX - SG_ SPEED : 47|16@0+ (0.01,0) [0|250] "kph" XXX + SG_ SPEED : 47|16@0+ (0.01,0) [0|250] "km/h" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX +BO_ 295 GEAR_PACKET_HYBRID: 8 XXX + SG_ CAR_MOVEMENT : 39|8@0- (1,0) [0|255] "" XXX + SG_ COUNTER : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ GEAR : 47|4@0+ (1,0) [0|15] "" XXX + BO_ 353 DSU_SPEED: 7 XXX - SG_ FORWARD_SPEED : 15|16@0- (0.00390625,-30) [0|255] "kph" XXX + SG_ FORWARD_SPEED : 15|16@0- (0.00390625,-30) [0|255] "km/h" XXX BO_ 452 ENGINE_RPM: 8 CGW SG_ RPM : 7|16@0- (0.78125,0) [0|0] "rpm" SCS @@ -74,24 +121,34 @@ BO_ 466 PCM_CRUISE: 8 XXX SG_ GAS_RELEASED : 4|1@0+ (1,0) [0|1] "" XXX SG_ CRUISE_ACTIVE : 5|1@0+ (1,0) [0|1] "" XXX SG_ STANDSTILL_ON : 12|1@0+ (1,0) [0|1] "" XXX - SG_ ACCEL_NET : 23|16@0- (0.001,0) [-20|20] "m/s2" XXX + SG_ ACCEL_NET : 23|16@0- (0.001,0) [-20|20] "m/s^2" XXX SG_ CRUISE_STATE : 55|4@0+ (1,0) [0|15] "" XXX SG_ CANCEL_REQ : 49|1@1+ (1,0) [0|1] "" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX BO_ 467 PCM_CRUISE_2: 8 XXX SG_ MAIN_ON : 15|1@0+ (1,0) [0|1] "" XXX - SG_ LOW_SPEED_LOCKOUT : 14|2@0+ (1,0) [0|3] "kph" XXX - SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "kph" XXX + SG_ LOW_SPEED_LOCKOUT : 14|2@0+ (1,0) [0|3] "" XXX + SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "km/h" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX BO_ 552 ACCELEROMETER: 8 XXX - SG_ ACCEL_Z : 22|15@0- (1,0) [0|32767] "" XXX - SG_ ACCEL_X : 6|15@0- (0.001,0) [-20|20] "m/s2" XXX + SG_ ACCEL_Z : 22|15@0- (1,0) [0|32767] "m/s^2" XXX + SG_ ACCEL_X : 6|15@0- (0.001,0) [-20|20] "m/s^2" XXX -BO_ 560 BRAKE_MODULE2: 7 XXX +BO_ 560 BRAKE_2: 7 XXX SG_ BRAKE_PRESSED : 26|1@0+ (1,0) [0|1] "" XXX +BO_ 581 GAS_PEDAL_HYBRID: 8 XXX + SG_ GAS_PEDAL : 23|8@0+ (0.005,0) [0|1] "" XXX + +BO_ 608 STEER_TORQUE_SENSOR: 8 XXX + SG_ STEER_TORQUE_EPS : 47|16@0- (1,0) [-32768|32767] "" XXX + SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX + SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ STEER_ANGLE : 31|16@0- (0.0573,0) [-500|500] "" XXX + BO_ 614 STEERING_IPAS: 8 IPAS SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX @@ -113,6 +170,10 @@ BO_ 643 PRE_COLLISION: 7 DSU SG_ PRECOLLISION_ACTIVE : 41|1@0+ (1,0) [0|255] "" XXX SG_ CHECKSUM : 55|8@0+ (1,0) [0|255] "" XXX +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 + BO_ 740 STEERING_LKA: 5 XXX SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX SG_ STEER_REQUEST : 0|1@0+ (1,0) [0|1] "" XXX @@ -127,10 +188,11 @@ BO_ 742 LEAD_INFO: 8 DSU SG_ LEAD_LONG_DIST : 7|13@0+ (0.05,0) [0|300] "m" HCU BO_ 835 ACC_CONTROL: 8 DSU - SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU + SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s^2" HCU SG_ ACC_MALFUNCTION : 18|1@0+ (1,0) [0|0] "" XXX SG_ ACC_CUT_IN : 25|1@0+ (1,0) [0|1] "" XXX SG_ ALLOW_LONG_PRESS : 17|2@0+ (1,0) [0|2] "" XXX + SG_ ITS_CONNECT_LEAD : 39|8@0+ (1,0) [0|1] "" Vector__XXX SG_ ACC_TYPE : 23|2@0+ (1,0) [0|3] "" HCU SG_ DISTANCE : 20|1@0+ (1,0) [0|1] "" XXX SG_ MINI_CAR : 21|1@0+ (1,0) [0|1] "" XXX @@ -166,6 +228,23 @@ BO_ 951 ESP_CONTROL: 8 ESP SG_ BRAKE_HOLD_ENABLED : 33|1@1+ (1,0) [0|1] "" XXX SG_ BRAKE_HOLD_ACTIVE : 36|1@0+ (1,0) [0|1] "" XXX +BO_ 956 GEAR_PACKET: 8 XXX + SG_ SPORT_ON : 2|1@0+ (1,0) [0|1] "" XXX + SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX + SG_ SPORT_GEAR_ON : 33|1@0+ (1,0) [0|1] "" XXX + SG_ SPORT_GEAR : 38|3@0+ (1,0) [0|7] "" XXX + SG_ ECON_ON : 40|1@0+ (1,0) [0|1] "" XXX + SG_ B_GEAR_ENGAGED : 41|1@0+ (1,0) [0|1] "" XXX + SG_ DRIVE_ENGAGED : 47|1@0+ (1,0) [0|1] "" XXX + +BO_ 1005 REVERSE_CAMERA_STATE: 2 BGM + SG_ REVERSE_CAMERA_GUIDELINES : 9|2@0+ (1,0) [1|3] "" XXX + +BO_ 1009 PCM_CRUISE_ALT: 8 XXX + SG_ MAIN_ON : 13|1@0+ (1,0) [0|3] "" XXX + SG_ CRUISE_STATE : 10|1@0+ (1,0) [0|1] "" XXX + SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "mph" XXX + BO_ 1020 SOLAR_SENSOR: 8 XXX SG_ LUX_SENSOR : 55|13@0+ (1,0) [0|0] "" XXX @@ -177,20 +256,31 @@ BO_ 1041 ACC_HUD: 8 DSU SG_ PCS_OFF : 40|1@0+ (1,0) [0|0] "" XXX SG_ PCS_SENSITIVITY : 55|8@0+ (1,0) [0|1] "" XXX -BO_ 1042 LKAS_HUD: 8 XXX +BO_ 1042 LKAS_HUD: 8 DSU SG_ BARRIERS : 1|2@0+ (1,0) [0|3] "" XXX SG_ RIGHT_LINE : 3|2@0+ (1,0) [0|3] "" XXX SG_ LEFT_LINE : 5|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X01 : 7|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X01_2 : 11|2@0+ (1,0) [0|3] "" XXX + SG_ LKAS_STATUS : 7|2@0+ (1,0) [0|3] "" XXX SG_ LDA_ALERT : 9|2@0+ (1,0) [0|3] "" XXX + SG_ LDW_EXIST : 10|1@0+ (1,0) [0|1] "" XXX SG_ TWO_BEEPS : 12|1@0+ (1,0) [0|1] "" XXX SG_ ADJUSTING_CAMERA : 13|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_UNAVAILABLE_QUIET : 14|1@0+ (1,0) [0|1] "" XXX SG_ LDA_MALFUNCTION : 15|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_UNAVAILABLE : 16|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_SENSITIVITY : 18|2@0+ (1,0) [0|3] "" XXX + SG_ LDA_SA_TOGGLE : 20|2@0+ (1,0) [0|3] "" XXX + SG_ LDA_SPEED_TOO_LOW : 21|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_ON_MESSAGE : 31|2@0+ (1,0) [0|3] "" XXX SG_ REPEATED_BEEPS : 32|1@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X0C : 23|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X2C : 47|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X38 : 55|8@0+ (1,0) [0|1] "" XXX + SG_ LANE_SWAY_TOGGLE : 43|1@0+ (1,0) [0|1] "" XXX + SG_ LANE_SWAY_SENSITIVITY : 45|2@0+ (1,0) [0|3] "" XXX + SG_ TAKE_CONTROL : 46|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_FRONT_CAMERA_BLOCKED : 47|1@0+ (1,0) [0|1] "" XXX + SG_ LANE_SWAY_BUZZER : 50|2@0+ (1,0) [0|0] "" XXX + SG_ LANE_SWAY_FLD : 53|3@0+ (1,0) [0|7] "" XXX + SG_ LANE_SWAY_WARNING : 55|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X01 : 42|1@0+ (1,0) [0|1] "" XXX SG_ SET_ME_X02 : 63|8@0+ (1,0) [0|1] "" XXX BO_ 1043 TIME : 8 CGW @@ -204,59 +294,14 @@ BO_ 1043 TIME : 8 CGW SG_ GMTDIFF_MINUTES : 50|6@0+ (1,0) [0|0] "minutes" XXX SG_ SUMMER : 60|1@0+ (1,0) [0|0] "" XXX -BO_ 1408 VIN_PART_1: 8 CGW - SG_ VIN_1 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_2 : 15|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_3 : 23|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_4 : 31|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_5 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_6 : 47|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_7 : 55|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_8 : 63|8@0+ (1,0) [0|0] "" XXX - -BO_ 1409 VIN_PART_2: 8 CGW - SG_ VIN_9 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_10 : 15|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_11 : 23|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_12 : 31|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_13 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_14 : 47|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_15 : 55|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_16 : 63|8@0+ (1,0) [0|0] "" XXX - -BO_ 1410 VIN_PART_3: 8 CGW - SG_ VIN_17 : 7|8@0+ (1,0) [0|0] "" XXX - -BO_ 1553 UI_SETTING: 8 XXX - SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX - SG_ ODOMETER : 43|20@0+ (1,0) [0|1048575] "" XXX - -BO_ 1556 STEERING_LEVERS: 8 XXX - SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX - SG_ HAZARD_LIGHT : 27|1@0+ (1,0) [0|1] "" XXX - -BO_ 1568 SEATS_DOORS: 8 XXX - SG_ METER_DIMMED : 38|1@0+ (1,0) [0|1] "" XXX - SG_ PARKING_BRAKE : 60|1@0+ (1,0) [0|1] "" XXX - SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_RR : 43|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_FR : 44|1@0+ (1,0) [0|1] "" XXX - -BO_ 1570 LIGHT_STALK: 8 SCM - SG_ AUTO_HIGH_BEAM : 37|1@0+ (1,0) [0|1] "" XXX - SG_ FRONT_FOG : 27|1@0+ (1,0) [0|1] "" XXX - SG_ PARKING_LIGHT : 28|1@0+ (1,0) [0|1] "" XXX - SG_ LOW_BEAM : 29|1@0+ (1,0) [0|1] "" XXX - SG_ HIGH_BEAM : 30|1@0+ (1,0) [0|1] "" XXX - SG_ DAYTIME_RUNNING_LIGHT : 31|1@0+ (1,0) [0|1] "" XXX +BO_ 1083 AUTOPARK_STATUS: 8 IPAS + SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX BO_ 1161 RSA1: 8 FCM SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX SG_ TSGNGRY1 : 12|3@0+ (1,0) [0|0] "" XXX SG_ TSGNHLT1 : 9|2@0+ (1,0) [0|0] "" XXX - SG_ SPDVAL1 : 23|8@0+ (1,0) [0|0] "kph" XXX + SG_ SPDVAL1 : 23|8@0+ (1,0) [0|0] "km/h" XXX SG_ SPLSGN1 : 31|4@0+ (1,0) [0|0] "" XXX SG_ SPLSGN2 : 27|4@0+ (1,0) [0|0] "" XXX SG_ TSGN2 : 39|8@0+ (1,0) [0|0] "" XXX @@ -294,21 +339,79 @@ BO_ 1163 RSA3: 8 FCM SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" XXX -BO_ 1571 CENTRAL_GATEWAY_UNIT: 8 CGW +BO_ 1408 VIN_PART_1: 8 CGW + SG_ VIN_1 : 7|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_2 : 15|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_3 : 23|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_4 : 31|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_5 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_6 : 47|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_7 : 55|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_8 : 63|8@0+ (1,0) [0|0] "" XXX + +BO_ 1409 VIN_PART_2: 8 CGW + SG_ VIN_9 : 7|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_10 : 15|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_11 : 23|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_12 : 31|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_13 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_14 : 47|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_15 : 55|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_16 : 63|8@0+ (1,0) [0|0] "" XXX + +BO_ 1410 VIN_PART_3: 8 CGW + SG_ VIN_17 : 7|8@0+ (1,0) [0|0] "" XXX + +BO_ 1552 BODY_CONTROL_STATE_2: 8 XXX + SG_ METER_SLIDER_BRIGHTNESS_PCT : 30|7@0+ (1,0) [12|100] "%" XXX + SG_ METER_SLIDER_LOW_BRIGHTNESS : 37|1@0+ (1,0) [0|1] "" XXX + SG_ METER_SLIDER_DIMMED : 38|1@0+ (1,0) [0|1] "" XXX + +BO_ 1553 UI_SETTING: 8 XXX + SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX + SG_ ODOMETER : 43|20@0+ (1,0) [0|1048575] "" XXX + +BO_ 1556 BLINKERS_STATE: 8 XXX + SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX + SG_ HAZARD_LIGHT : 27|1@0+ (1,0) [0|1] "" XXX + +BO_ 1568 BODY_CONTROL_STATE: 8 XXX + SG_ METER_DIMMED : 38|1@0+ (1,0) [0|1] "" XXX + SG_ PARKING_BRAKE : 60|1@0+ (1,0) [0|1] "" XXX + SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RR : 43|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FR : 44|1@0+ (1,0) [0|1] "" XXX + +BO_ 1570 LIGHT_STALK: 8 SCM + SG_ AUTO_HIGH_BEAM : 37|1@0+ (1,0) [0|1] "" XXX + SG_ FRONT_FOG : 27|1@0+ (1,0) [0|1] "" XXX + SG_ PARKING_LIGHT : 28|1@0+ (1,0) [0|1] "" XXX + SG_ LOW_BEAM : 29|1@0+ (1,0) [0|1] "" XXX + SG_ HIGH_BEAM : 30|1@0+ (1,0) [0|1] "" XXX + SG_ DAYTIME_RUNNING_LIGHT : 31|1@0+ (1,0) [0|1] "" XXX + +BO_ 1571 CERTIFICATION_ECU: 8 CGW SG_ DOOR_LOCK_FEEDBACK_LIGHT : 15|1@0+ (1,0) [0|0] "" XXX SG_ KEYFOB_LOCKING_FEEDBACK_LIGHT : 61|1@0+ (1,0) [0|0] "" XXX SG_ KEYFOB_UNLOCKING_FEEDBACK_LIGHT : 62|1@0+ (1,0) [0|0] "" XXX -CM_ SG_ 36 ACCEL_Y "unit is tbd"; +BO_ 1592 DOOR_LOCKS: 8 XXX + SG_ LOCK_STATUS_CHANGED : 15|1@0+ (1,0) [0|1] "" XXX + SG_ LOCK_STATUS : 20|1@0+ (1,0) [0|1] "" XXX + SG_ LOCKED_VIA_KEYFOB : 23|1@0+ (1,0) [0|1] "" XXX + CM_ SG_ 36 YAW_RATE "verify"; CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; CM_ SG_ 37 STEER_RATE "factor is tbd"; CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; CM_ SG_ 466 CRUISE_STATE "Active state is 8, if standstill is requested will switch to state 11(3 sec timer), after timer is elapsed will switch into state 7(standstill). If plus button was pressed - status 9, minus button pressed - status 10"; -CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isn't perfect"; +CM_ SG_ 467 SET_SPEED "43 km/h are shown as 28 mph, so conversion isn't perfect"; CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; +CM_ SG_ 581 GAS_PEDAL "it seems slightly filtered"; CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; CM_ SG_ 608 STEER_OVERRIDE "set when driver torque exceeds a certain value"; CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; @@ -320,15 +423,31 @@ CM_ SG_ 835 RADAR_DIRTY "Display Clean Radar Sensor message on HUD"; CM_ SG_ 835 ACC_MALFUNCTION "display ACC fault on dash if set to 1"; CM_ SG_ 835 ACC_CUT_IN "Display blinking yellow lead if set to 1"; CM_ SG_ 835 DISTANCE "Display Distance Bars on HUD Permanently"; +CM_ SG_ 835 ITS_CONNECT_LEAD "Displayed when lead car is capable of ITS Connect"; CM_ SG_ 835 ALLOW_LONG_PRESS "Enable Toyota's factory set speed increment behaviour, available on both metrics cars and imperial unit cars"; CM_ SG_ 835 PERMIT_BRAKING "Original ACC has this going high when a car in front is detected. In openpilot and before the PERMIT_BRAKING name, this was 'SET_ME_1' and is hardcoded to be high. Unsure if only informational or has an effect though existing usage in openpilot is to always set it to 1. Originally 'PMTBRKG' in the leaked toyota_2017_ref_pt.dbc file and name expansion speculated to be PerMiT BRaKinG."; CM_ SG_ 835 ACCEL_CMD_ALT "Copy of main ACCEL_CMD, but across 8 bits instead of 16 bits like ACCEL_CMD. Unsure if only informational or has an effect. Likely informational as existing openpilot sets this to 0 and no loss of functionality observed. Originally 'AT_RAW' in leaked toyota_2017_ref_pt.dbc file."; CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; CM_ SG_ 951 BRAKE_LIGHTS_ACC "brake lights when ACC commands decel"; +CM_ SG_ 1009 SET_SPEED "units seem to be whatever the car is set to"; CM_ SG_ 1041 PCS_INDICATOR "Pre-Collision System Indicator"; CM_ SG_ 1041 PCS_SENSITIVITY "Pre-Collision System Sensitivity"; -CM_ SG_ 1042 SET_ME_1 "unclear what this is, but it's always 1 in drive traces"; -CM_ SG_ 1042 REPEATED_BEEPS "recommended for fcw and other important alerts"; +CM_ SG_ 1042 LDA_SA_TOGGLE "LDA Steering Assist Toggle"; +CM_ SG_ 1042 LDW_EXIST "Unclear what this is, it's usually set to 0"; +CM_ SG_ 1042 LDA_SENSITIVITY "LDA Sensitivity"; +CM_ SG_ 1042 LDA_ON_MESSAGE "Display LDA Turned ON message"; +CM_ SG_ 1042 REPEATED_BEEPS "LDA audible warning"; +CM_ SG_ 1042 LDA_UNAVAILABLE_QUIET "LDA toggles and sensitivity settings are greyed out if set to 1"; +CM_ SG_ 1042 LDA_SPEED_TOO_LOW "length is 3 bits in the leaked DBC, displays LDA unavailable below approx 50 km/h if set to 1"; +CM_ SG_ 1042 LDA_FRONT_CAMERA_BLOCKED "originally LDAFCVB, LDA related settings are greyed out if set to 1"; +CM_ SG_ 1042 TAKE_CONTROL "Please Control Steering Wheel warning"; +CM_ SG_ 1042 LANE_SWAY_TOGGLE "Lane Sway Warning System SWS Switch"; +CM_ SG_ 1042 LANE_SWAY_WARNING "Lane Sway Warning System Triggered"; +CM_ SG_ 1042 LANE_SWAY_FLD "Unknown signal for Lane Sway Warning System, set to 7 on stock system when SWS is enabled, 0 when SWS is disabled"; +CM_ SG_ 1042 LANE_SWAY_BUZZER "Similar to TWO_BEEPS"; +CM_ SG_ 1042 SET_ME_X01 "empty bit on leaked dbc, always set to 1 during normal operations"; +CM_ SG_ 1042 SET_ME_X02 "empty bit on leaked dbc, always set to 2 during normal operations"; +CM_ SG_ 1083 STATE "when the dashboard button is pressed, the value changes from zero to non-zero"; CM_ SG_ 1161 SPDVAL1 "Numbers 0-199 is displayed, 200-254 displays circle without number and 255 is for no limit."; CM_ SG_ 1161 SYNCID1 "counter from 1 to f at 1 Hz"; CM_ SG_ 1161 SPDVAL2 "conditional speed value 70"; @@ -343,8 +462,15 @@ CM_ SG_ 1163 OVSPVALL "-5 at start then 2 after 2 seconds"; CM_ SG_ 1163 OVSPVALM "-5 at start then 5 after 2 seconds"; CM_ SG_ 1163 OVSPVALH "-5 at start then 10 after 2 seconds"; CM_ SG_ 1163 TSRSPU "always 1"; +CM_ SG_ 1552 METER_SLIDER_BRIGHTNESS_PCT "Combination display brightness setting, scales from 12 per cent to 100 per cent, reflects combination meter settings only, not linked with headlight state"; +CM_ SG_ 1552 METER_SLIDER_LOW_BRIGHTNESS "Combination display low brightness mode, also controls footwell lighting"; +CM_ SG_ 1552 METER_SLIDER_DIMMED "Combination display slider not at max, reflects combination meter settings only, not linked with headlight state"; CM_ SG_ 1553 ODOMETER "Unit is dependent upon units signal"; +CM_ SG_ 1592 LOCK_STATUS_CHANGED "1 on rising edge of lock/unlocking"; +CM_ SG_ 1592 LOCK_STATUS "The next 3 bits always seem to follow this signal."; +CM_ SG_ 1592 LOCKED_VIA_KEYFOB "1 for as long as car is locked with key fob or door handle touch"; +VAL_ 295 GEAR 0 "P" 1 "R" 2 "N" 3 "D" 4 "B"; VAL_ 466 CRUISE_STATE 11 "timer_3sec" 10 "adaptive click down" 9 "adaptive click up" 8 "adaptive engaged" 7 "standstill" 6 "non-adaptive click up" 5 "non-adaptive click down" 4 "non-adaptive hold down" 3 "non-adaptive hold up" 2 "non-adaptive being engaged" 1 "non-adaptive engaged" 0 "off"; VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok"; VAL_ 614 STATE 3 "enabled" 1 "disabled"; @@ -355,66 +481,42 @@ VAL_ 835 ACC_MALFUNCTION 1 "faulted" 0 "ok"; VAL_ 835 ACC_CUT_IN 1 "CUT-IN Detected" 0 "clear"; VAL_ 835 ALLOW_LONG_PRESS 2 "set speed increase by 5 speed units regardless" 1 "set speed increase by 1 speed unit on short press, 5 speed units on long press"; VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted"; +VAL_ 956 SPORT_ON 0 "off" 1 "on"; +VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; +VAL_ 956 SPORT_GEAR_ON 0 "off" 1 "on"; +VAL_ 956 SPORT_GEAR 1 "S1" 2 "S2" 3 "S3" 4 "S4" 5 "S5" 6 "S6"; +VAL_ 956 ECON_ON 0 "off" 1 "on"; +VAL_ 956 B_GEAR_ENGAGED 0 "off" 1 "on"; +VAL_ 956 DRIVE_ENGAGED 0 "off" 1 "on"; +VAL_ 1005 REVERSE_CAMERA_GUIDELINES 3 "No guidelines" 2 "Static guidelines" 1 "Active guidelines"; VAL_ 1041 PCS_INDICATOR 2 "PCS Faulted" 1 "PCS Turned Off By User" 0 "PCS Enabled"; VAL_ 1041 PCS_SENSITIVITY 64 "high sensitivity" 128 "mid sensitivity" 192 "low sensitivity" 0 "off"; VAL_ 1042 LDA_ALERT 3 "hold with continuous beep" 2 "LDA unavailable" 1 "hold" 0 "none"; -VAL_ 1042 BARRIERS 3 "both" 2 "right" 1 "left" 0 "none"; +VAL_ 1042 BARRIERS 3 "left" 2 "right" 1 "both" 0 "none"; VAL_ 1042 RIGHT_LINE 3 "orange" 2 "faded" 1 "solid" 0 "none"; +VAL_ 1042 LKAS_STATUS 1 "on" 0 "off"; VAL_ 1042 LEFT_LINE 3 "orange" 2 "faded" 1 "solid" 0 "none"; -VAL_ 1553 UNITS 1 "km" 2 "miles"; -VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left"; +VAL_ 1042 LDA_ON_MESSAGE 2 "Lane Departure Alert Turned ON, Steering Assist Inactive" 1 "Lane Departure Alert Turned ON, Steering Assist Active" 0 "clear"; +VAL_ 1042 LDA_SA_TOGGLE 2 "steering assist off" 1 "steering assist on"; +VAL_ 1042 LDA_SENSITIVITY 2 "standard" 1 "high" 0 "undefined"; +VAL_ 1042 LDA_SPEED_TOO_LOW 1 "lda unavailable, speed too low" 0 "ok"; +VAL_ 1042 LDA_FRONT_CAMERA_BLOCKED 1 "lda unavailable" 0 "ok"; +VAL_ 1042 TAKE_CONTROL 1 "take control" 0 "ok"; +VAL_ 1042 LANE_SWAY_WARNING 3 "ok" 2 "orange please take a break" 1 "prompt would you like to take a break" 0 "ok"; +VAL_ 1042 LANE_SWAY_BUZZER 3 "ok" 2 "beep twice" 1 "beep twice" 0 "ok"; VAL_ 1161 TSGN1 1 "speed sign" 0 "none"; VAL_ 1161 TSGN2 1 "speed sign" 0 "none"; VAL_ 1161 SPLSGN2 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none"; VAL_ 1162 TSGN3 0 "none" 1 "speed sign" 2 "0 unlimited" 7 "unlimited" 16 "highway" 17 "no highway" 18 "motorway" 19 "no motorway" 20 "in city" 21 "outside city" 22 "pedestrian area" 23 "no pedestrian area" 65 "no overtaking left" 66 "no overtaking right" 67 "overtaking allowed again" 81 "no right turn" 97 "stop" 105 "yield" 113 "stop" 114 "yield us" 129 "no entry" 138 "no entry tss2" 145 "do not enter"; VAL_ 1162 SPLSGN3 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none"; +VAL_ 1552 METER_SLIDER_LOW_BRIGHTNESS 1 "Low brightness mode, footwell lights off" 0 "Normal mode, footwell lights on"; +VAL_ 1552 METER_SLIDER_DIMMED 1 "Dimmed" 0 "Not Dimmed"; +VAL_ 1553 UNITS 1 "km" 2 "miles"; +VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left"; +VAL_ 1592 LOCK_STATUS 0 "locked" 1 "unlocked"; +CM_ "toyota_nodsu_pt.dbc starts here"; - - -CM_ "Imported file _comma.dbc starts here"; -BO_ 359 STEERING_IPAS_COMMA: 8 IPAS - SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX - SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX - SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX - SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant"; - - BO_ 512 GAS_COMMAND: 6 EON - SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR - SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR - SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR - - BO_ 513 GAS_SENSOR: 6 INTERCEPTOR - SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON - SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON - SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON - - VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; - -BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX - SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX - -CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss"; - -BO_ 767 SDSU: 8 XXX - SG_ FD_BUTTON : 7|1@0+ (1,0) [0|1] "" XXX - -CM_ "BO_ SDSU: The sDSU is a modified DSU for use in TSS1 Toyotas. Learn more: https://github.com/wocsor/panda/tree/smart_dsu"; - -CM_ SG_ 767 FD_BUTTON "The follow distance button signal as forwarded by the sdsu"; - - -CM_ "Imported file _toyota_nodsu_common.dbc starts here"; BO_ 401 STEERING_LTA: 8 XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX SG_ SETME_X3 : 29|2@0+ (1,0) [0|3] "" XXX @@ -428,6 +530,17 @@ BO_ 401 STEERING_LTA: 8 XXX SG_ STEER_REQUEST_2 : 0|1@0+ (1,0) [0|1] "" XXX SG_ SETME_X1 : 7|1@0+ (1,0) [0|1] "" XXX +BO_ 550 BRAKE_MODULE: 8 XXX + SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|511] "" XXX + SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|1] "" XXX + +BO_ 610 EPS_STATUS: 8 EPS + SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX + SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX + SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + BO_ 1014 BSM: 8 XXX SG_ L_ADJACENT : 0|1@0+ (1,0) [0|1] "" XXX SG_ L_APPROACHING : 8|1@0+ (1,0) [0|1] "" XXX @@ -436,6 +549,9 @@ BO_ 1014 BSM: 8 XXX SG_ ADJACENT_ENABLED : 7|1@0+ (1,0) [0|1] "" XXX SG_ APPROACHING_ENABLED : 15|1@0+ (1,0) [0|1] "" XXX +CM_ SG_ 550 BRAKE_PRESSURE "seems prop to pedal force"; +CM_ SG_ 550 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; +CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; CM_ SG_ 1014 L_ADJACENT "vehicle adjacent left side of car. enabled above 10mph, regardless of ADJACENT_ENABLED or APPROACHING_ENABLED"; CM_ SG_ 1014 L_APPROACHING "vehicle approaching from left side of car. enabled above 10mph, regardless of ADJACENT_ENABLED or APPROACHING_ENABLED"; CM_ SG_ 1014 R_ADJACENT "vehicle adjacent right side of car. enabled above 10mph, regardless of ADJACENT_ENABLED or APPROACHING_ENABLED"; @@ -443,43 +559,5 @@ CM_ SG_ 1014 R_APPROACHING "vehicle approaching from right side of car. enabled CM_ SG_ 1014 ADJACENT_ENABLED "when BSM is enabled in settings, this is on along with APPROACHING_ENABLED. this controls bsm alert visibility"; CM_ SG_ 1014 APPROACHING_ENABLED "when BSM is enabled in settings, this is on along with ADJACENT_ENABLED. this controls bsm alert visibility"; -CM_ "toyota_nodsu_pt.dbc starts here"; - - - - -BO_ 550 BRAKE_MODULE: 8 XXX - SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|511] "" XXX - SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|511] "" XXX - SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|1] "" XXX - -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 - -BO_ 608 STEER_TORQUE_SENSOR: 8 XXX - SG_ STEER_TORQUE_EPS : 47|16@0- (0.73,0) [-20000|20000] "" XXX - SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX - SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - SG_ STEER_ANGLE : 31|16@0- (0.0573,0) [-500|500] "" XXX - -BO_ 610 EPS_STATUS: 8 EPS - SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX - SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX - SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 956 GEAR_PACKET: 8 XXX - SG_ SPORT_ON : 2|1@0+ (1,0) [0|1] "" XXX - SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX - SG_ ECON_ON : 40|1@0+ (1,0) [0|1] "" XXX - -CM_ SG_ 548 BRAKE_PRESSURE "seems prop to pedal force"; -CM_ SG_ 548 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; -CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled"; VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby"; -VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; -VAL_ 956 SPORT_ON 0 "off" 1 "on"; -VAL_ 956 ECON_ON 0 "off" 1 "on"; diff --git a/opendbc/toyota_prius_2017_pt_generated.dbc b/opendbc/toyota_prius_2017_pt_generated.dbc deleted file mode 100644 index c3857583c..000000000 --- a/opendbc/toyota_prius_2017_pt_generated.dbc +++ /dev/null @@ -1,457 +0,0 @@ -CM_ "AUTOGENERATED FILE, DO NOT EDIT"; - - -CM_ "Imported file _toyota_2017.dbc starts here"; -VERSION "" - - -NS_ : - NS_DESC_ - CM_ - BA_DEF_ - BA_ - VAL_ - CAT_DEF_ - CAT_ - FILTER - BA_DEF_DEF_ - EV_DATA_ - ENVVAR_DATA_ - SGTYPE_ - SGTYPE_VAL_ - BA_DEF_SGTYPE_ - BA_SGTYPE_ - SIG_TYPE_REF_ - VAL_TABLE_ - SIG_GROUP_ - SIG_VALTYPE_ - SIGTYPE_VALTYPE_ - BO_TX_BU_ - BA_DEF_REL_ - BA_REL_ - BA_DEF_DEF_REL_ - BU_SG_REL_ - BU_EV_REL_ - BU_BO_REL_ - SG_MUL_VAL_ - -BS_: - -BU_: XXX DSU HCU EPS IPAS CGW - -BO_ 36 KINEMATICS: 8 XXX - SG_ ACCEL_Y : 33|10@0+ (0.03589,-18.375) [0|65535] "m/s^2" XXX - SG_ YAW_RATE : 1|10@0+ (0.244,-125) [0|65535] "deg/sec" XXX - SG_ STEERING_TORQUE : 17|10@0+ (1,-512) [0|65535] "" XXX - -BO_ 37 STEER_ANGLE_SENSOR: 8 XXX - SG_ STEER_ANGLE : 3|12@0- (1.5,0) [-500|500] "deg" XXX - SG_ STEER_FRACTION : 39|4@0- (0.1,0) [-0.7|0.7] "deg" XXX - SG_ STEER_RATE : 35|12@0- (1,0) [-2000|2000] "deg/s" XXX - -BO_ 166 BRAKE: 8 XXX - SG_ BRAKE_AMOUNT : 7|8@0+ (1,0) [0|255] "" XXX - SG_ BRAKE_PEDAL : 23|8@0+ (1,0) [0|255] "" XXX - -BO_ 170 WHEEL_SPEEDS: 8 XXX - SG_ WHEEL_SPEED_FR : 7|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_FL : 23|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_RR : 39|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_RL : 55|16@0+ (0.01,-67.67) [0|250] "kph" XXX - -BO_ 180 SPEED: 8 XXX - SG_ ENCODER : 39|8@0+ (1,0) [0|255] "" XXX - SG_ SPEED : 47|16@0+ (0.01,0) [0|250] "kph" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 353 DSU_SPEED: 7 XXX - SG_ FORWARD_SPEED : 15|16@0- (0.00390625,-30) [0|255] "kph" XXX - -BO_ 452 ENGINE_RPM: 8 CGW - SG_ RPM : 7|16@0- (0.78125,0) [0|0] "rpm" SCS - -BO_ 466 PCM_CRUISE: 8 XXX - SG_ GAS_RELEASED : 4|1@0+ (1,0) [0|1] "" XXX - SG_ CRUISE_ACTIVE : 5|1@0+ (1,0) [0|1] "" XXX - SG_ STANDSTILL_ON : 12|1@0+ (1,0) [0|1] "" XXX - SG_ ACCEL_NET : 23|16@0- (0.001,0) [-20|20] "m/s2" XXX - SG_ CRUISE_STATE : 55|4@0+ (1,0) [0|15] "" XXX - SG_ CANCEL_REQ : 49|1@1+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 467 PCM_CRUISE_2: 8 XXX - SG_ MAIN_ON : 15|1@0+ (1,0) [0|1] "" XXX - SG_ LOW_SPEED_LOCKOUT : 14|2@0+ (1,0) [0|3] "kph" XXX - SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "kph" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 552 ACCELEROMETER: 8 XXX - SG_ ACCEL_Z : 22|15@0- (1,0) [0|32767] "" XXX - SG_ ACCEL_X : 6|15@0- (0.001,0) [-20|20] "m/s2" XXX - -BO_ 560 BRAKE_MODULE2: 7 XXX - SG_ BRAKE_PRESSED : 26|1@0+ (1,0) [0|1] "" XXX - -BO_ 614 STEERING_IPAS: 8 IPAS - SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX - SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX - SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX - SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 643 PRE_COLLISION: 7 DSU - SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 15|8@0+ (1,0) [0|255] "" XXX - SG_ FORCE : 23|16@0- (2,0) [0|255] "N" XXX - SG_ SET_ME_X002 : 33|8@0+ (1,0) [0|3] "" XXX - SG_ BRAKE_STATUS : 39|3@0+ (1,0) [0|255] "" XXX - SG_ STATE : 36|3@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X003 : 40|1@0+ (1,0) [0|1] "" XXX - SG_ PRECOLLISION_ACTIVE : 41|1@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 55|8@0+ (1,0) [0|255] "" XXX - -BO_ 740 STEERING_LKA: 5 XXX - SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX - SG_ STEER_REQUEST : 0|1@0+ (1,0) [0|1] "" XXX - SG_ COUNTER : 6|6@0+ (1,0) [0|63] "" XXX - SG_ SET_ME_1 : 7|1@0+ (1,0) [0|1] "" XXX - SG_ STEER_TORQUE_CMD : 15|16@0- (1,0) [0|65535] "" XXX - SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX - -BO_ 742 LEAD_INFO: 8 DSU - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" HCU - SG_ LEAD_REL_SPEED : 23|12@0- (0.025,0) [-100|100] "m/s" HCU - SG_ LEAD_LONG_DIST : 7|13@0+ (0.05,0) [0|300] "m" HCU - -BO_ 835 ACC_CONTROL: 8 DSU - SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU - SG_ ACC_MALFUNCTION : 18|1@0+ (1,0) [0|0] "" XXX - SG_ ACC_CUT_IN : 25|1@0+ (1,0) [0|1] "" XXX - SG_ ALLOW_LONG_PRESS : 17|2@0+ (1,0) [0|2] "" XXX - SG_ ACC_TYPE : 23|2@0+ (1,0) [0|3] "" HCU - SG_ DISTANCE : 20|1@0+ (1,0) [0|1] "" XXX - SG_ MINI_CAR : 21|1@0+ (1,0) [0|1] "" XXX - SG_ PERMIT_BRAKING : 30|1@0+ (1,0) [0|1] "" HCU - SG_ RELEASE_STANDSTILL : 31|1@0+ (1,0) [0|1] "" HCU - SG_ CANCEL_REQ : 24|1@0+ (1,0) [0|1] "" HCU - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - SG_ ACCEL_CMD_ALT : 47|8@0- (0.05,0) [0|0] "m/s^2" XXX - SG_ RADAR_DIRTY : 19|1@0+ (1,0) [0|1] "" XXX - -BO_ 836 PRE_COLLISION_2: 8 DSU - SG_ CHECKSUM : 63|8@0+ (1,0) [0|0] "" XXX - -BO_ 869 DSU_CRUISE : 7 DSU - SG_ RES_BTN : 3|1@0+ (1,0) [0|0] "" XXX - SG_ SET_BTN : 2|1@0+ (1,0) [0|0] "" XXX - SG_ CANCEL_BTN : 1|1@0+ (1,0) [0|0] "" XXX - SG_ MAIN_ON : 0|1@0+ (1,0) [0|0] "" XXX - SG_ SET_SPEED : 15|8@0+ (1,0) [0|0] "km/h" XXX - SG_ CRUISE_REQUEST : 31|8@0+ (100,-12800) [0|0] "N" XXX - SG_ LEAD_DISTANCE : 39|8@0+ (1,0) [0|0] "m" XXX - -BO_ 921 PCM_CRUISE_SM: 8 XXX - SG_ MAIN_ON : 4|1@0+ (1,0) [0|1] "" XXX - SG_ CRUISE_CONTROL_STATE : 11|4@0+ (1,0) [0|15] "" XXX - SG_ DISTANCE_LINES : 14|2@0+ (1,0) [0|3] "" XXX - SG_ UI_SET_SPEED : 31|8@0+ (1,0) [0|255] "" XXX - -BO_ 951 ESP_CONTROL: 8 ESP - SG_ TC_DISABLED : 13|1@0+ (1,0) [0|1] "" XXX - SG_ VSC_DISABLED : 12|2@0+ (1,0) [0|1] "" XXX - SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" XXX - SG_ BRAKE_HOLD_ENABLED : 33|1@1+ (1,0) [0|1] "" XXX - SG_ BRAKE_HOLD_ACTIVE : 36|1@0+ (1,0) [0|1] "" XXX - -BO_ 1020 SOLAR_SENSOR: 8 XXX - SG_ LUX_SENSOR : 55|13@0+ (1,0) [0|0] "" XXX - -BO_ 1041 ACC_HUD: 8 DSU - SG_ PCS_INDICATOR : 7|2@0+ (1,0) [0|3] "" XXX - SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X20 : 15|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X10 : 39|8@0+ (1,0) [0|1] "" XXX - SG_ PCS_OFF : 40|1@0+ (1,0) [0|0] "" XXX - SG_ PCS_SENSITIVITY : 55|8@0+ (1,0) [0|1] "" XXX - -BO_ 1042 LKAS_HUD: 8 XXX - SG_ BARRIERS : 1|2@0+ (1,0) [0|3] "" XXX - SG_ RIGHT_LINE : 3|2@0+ (1,0) [0|3] "" XXX - SG_ LEFT_LINE : 5|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X01 : 7|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X01_2 : 11|2@0+ (1,0) [0|3] "" XXX - SG_ LDA_ALERT : 9|2@0+ (1,0) [0|3] "" XXX - SG_ TWO_BEEPS : 12|1@0+ (1,0) [0|1] "" XXX - SG_ ADJUSTING_CAMERA : 13|1@0+ (1,0) [0|1] "" XXX - SG_ LDA_MALFUNCTION : 15|1@0+ (1,0) [0|1] "" XXX - SG_ REPEATED_BEEPS : 32|1@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X0C : 23|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X2C : 47|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X38 : 55|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X02 : 63|8@0+ (1,0) [0|1] "" XXX - -BO_ 1043 TIME : 8 CGW - SG_ YEAR : 7|8@0+ (1,0) [0|0] "year" XXX - SG_ MONTH : 15|8@0+ (1,0) [0|0] "month" XXX - SG_ DAY : 23|8@0+ (1,0) [0|0] "day" XXX - SG_ HOUR : 31|8@0+ (1,0) [0|0] "hour" XXX - SG_ MINUTE : 39|8@0+ (1,0) [0|0] "minute" XXX - SG_ GMT_DIFF : 55|1@0+ (1,0) [0|0] "" XXX - SG_ GMTDIFF_HOURS : 54|4@0+ (1,0) [0|0] "hours" XXX - SG_ GMTDIFF_MINUTES : 50|6@0+ (1,0) [0|0] "minutes" XXX - SG_ SUMMER : 60|1@0+ (1,0) [0|0] "" XXX - -BO_ 1408 VIN_PART_1: 8 CGW - SG_ VIN_1 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_2 : 15|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_3 : 23|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_4 : 31|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_5 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_6 : 47|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_7 : 55|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_8 : 63|8@0+ (1,0) [0|0] "" XXX - -BO_ 1409 VIN_PART_2: 8 CGW - SG_ VIN_9 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_10 : 15|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_11 : 23|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_12 : 31|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_13 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_14 : 47|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_15 : 55|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_16 : 63|8@0+ (1,0) [0|0] "" XXX - -BO_ 1410 VIN_PART_3: 8 CGW - SG_ VIN_17 : 7|8@0+ (1,0) [0|0] "" XXX - -BO_ 1553 UI_SETTING: 8 XXX - SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX - SG_ ODOMETER : 43|20@0+ (1,0) [0|1048575] "" XXX - -BO_ 1556 STEERING_LEVERS: 8 XXX - SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX - SG_ HAZARD_LIGHT : 27|1@0+ (1,0) [0|1] "" XXX - -BO_ 1568 SEATS_DOORS: 8 XXX - SG_ METER_DIMMED : 38|1@0+ (1,0) [0|1] "" XXX - SG_ PARKING_BRAKE : 60|1@0+ (1,0) [0|1] "" XXX - SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_RR : 43|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_FR : 44|1@0+ (1,0) [0|1] "" XXX - -BO_ 1570 LIGHT_STALK: 8 SCM - SG_ AUTO_HIGH_BEAM : 37|1@0+ (1,0) [0|1] "" XXX - SG_ FRONT_FOG : 27|1@0+ (1,0) [0|1] "" XXX - SG_ PARKING_LIGHT : 28|1@0+ (1,0) [0|1] "" XXX - SG_ LOW_BEAM : 29|1@0+ (1,0) [0|1] "" XXX - SG_ HIGH_BEAM : 30|1@0+ (1,0) [0|1] "" XXX - SG_ DAYTIME_RUNNING_LIGHT : 31|1@0+ (1,0) [0|1] "" XXX - -BO_ 1161 RSA1: 8 FCM - SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY1 : 12|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT1 : 9|2@0+ (1,0) [0|0] "" XXX - SG_ SPDVAL1 : 23|8@0+ (1,0) [0|0] "kph" XXX - SG_ SPLSGN1 : 31|4@0+ (1,0) [0|0] "" XXX - SG_ SPLSGN2 : 27|4@0+ (1,0) [0|0] "" XXX - SG_ TSGN2 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY2 : 44|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT2 : 41|2@0+ (1,0) [0|0] "" XXX - SG_ SPDVAL2 : 55|8@0+ (1,0) [0|0] "" XXX - SG_ BZRRQ_P : 63|2@0+ (1,0) [0|0] "" XXX - SG_ BZRRQ_A : 61|2@0+ (1,0) [0|0] "" XXX - SG_ SYNCID1 : 59|4@0+ (1,0) [0|0] "" XXX - -BO_ 1162 RSA2: 8 FCM - SG_ TSGN3 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY3 : 12|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT3 : 9|2@0+ (1,0) [0|0] "" XXX - SG_ SPLSGN3 : 31|4@0+ (1,0) [0|0] "" XXX - SG_ SPLSGN4 : 27|4@0+ (1,0) [0|0] "" XXX - SG_ TSGN4 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY4 : 44|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT4 : 41|2@0+ (1,0) [0|0] "" XXX - SG_ DPSGNREQ : 54|1@0+ (1,0) [0|0] "" XXX - SG_ SGNNUMP : 53|3@0+ (1,0) [0|0] "" XXX - SG_ SGNNUMA : 50|3@0+ (1,0) [0|0] "" XXX - SG_ SPDUNT : 63|2@0+ (1,0) [0|0] "" XXX - SG_ TSRWMSG : 61|2@0+ (1,0) [0|0] "" XXX - SG_ SYNCID2 : 59|4@0+ (1,0) [0|0] "" XXX - -BO_ 1163 RSA3: 8 FCM - SG_ TSREQPD : 7|1@0+ (1,0) [0|0] "" XXX - SG_ TSRMSW : 6|1@0+ (1,0) [0|0] "" XXX - SG_ OTSGNNTM : 5|2@0+ (1,0) [0|0] "" XXX - SG_ NTLVLSPD : 3|2@0+ (1,0) [0|0] "" XXX - SG_ OVSPNTM : 1|2@0+ (1,0) [0|0] "" XXX - SG_ OVSPVALL : 11|4@0+ (1,-5) [0|0] "" XXX - SG_ OVSPVALM : 19|4@0+ (1,-5) [0|0] "" XXX - SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX - SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" XXX - -BO_ 1571 CENTRAL_GATEWAY_UNIT: 8 CGW - SG_ DOOR_LOCK_FEEDBACK_LIGHT : 15|1@0+ (1,0) [0|0] "" XXX - SG_ KEYFOB_LOCKING_FEEDBACK_LIGHT : 61|1@0+ (1,0) [0|0] "" XXX - SG_ KEYFOB_UNLOCKING_FEEDBACK_LIGHT : 62|1@0+ (1,0) [0|0] "" XXX - -CM_ SG_ 36 ACCEL_Y "unit is tbd"; -CM_ SG_ 36 YAW_RATE "verify"; -CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; -CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; -CM_ SG_ 37 STEER_RATE "factor is tbd"; -CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; -CM_ SG_ 466 CRUISE_STATE "Active state is 8, if standstill is requested will switch to state 11(3 sec timer), after timer is elapsed will switch into state 7(standstill). If plus button was pressed - status 9, minus button pressed - status 10"; -CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isn't perfect"; -CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; -CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; -CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; -CM_ SG_ 608 STEER_OVERRIDE "set when driver torque exceeds a certain value"; -CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; -CM_ SG_ 643 COUNTER "only used on cars that use this msg for cruise control"; -CM_ SG_ 643 BRAKE_STATUS "only used on cars that use this msg for cruise control"; -CM_ SG_ 643 PRECOLLISION_ACTIVE "set 0.5s before any braking"; -CM_ SG_ 835 ACC_TYPE "if 2, car is likely to have a permanent low speed lockout. 1 is ok"; -CM_ SG_ 835 RADAR_DIRTY "Display Clean Radar Sensor message on HUD"; -CM_ SG_ 835 ACC_MALFUNCTION "display ACC fault on dash if set to 1"; -CM_ SG_ 835 ACC_CUT_IN "Display blinking yellow lead if set to 1"; -CM_ SG_ 835 DISTANCE "Display Distance Bars on HUD Permanently"; -CM_ SG_ 835 ALLOW_LONG_PRESS "Enable Toyota's factory set speed increment behaviour, available on both metrics cars and imperial unit cars"; -CM_ SG_ 835 PERMIT_BRAKING "Original ACC has this going high when a car in front is detected. In openpilot and before the PERMIT_BRAKING name, this was 'SET_ME_1' and is hardcoded to be high. Unsure if only informational or has an effect though existing usage in openpilot is to always set it to 1. Originally 'PMTBRKG' in the leaked toyota_2017_ref_pt.dbc file and name expansion speculated to be PerMiT BRaKinG."; -CM_ SG_ 835 ACCEL_CMD_ALT "Copy of main ACCEL_CMD, but across 8 bits instead of 16 bits like ACCEL_CMD. Unsure if only informational or has an effect. Likely informational as existing openpilot sets this to 0 and no loss of functionality observed. Originally 'AT_RAW' in leaked toyota_2017_ref_pt.dbc file."; -CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; -CM_ SG_ 951 BRAKE_LIGHTS_ACC "brake lights when ACC commands decel"; -CM_ SG_ 1041 PCS_INDICATOR "Pre-Collision System Indicator"; -CM_ SG_ 1041 PCS_SENSITIVITY "Pre-Collision System Sensitivity"; -CM_ SG_ 1042 SET_ME_1 "unclear what this is, but it's always 1 in drive traces"; -CM_ SG_ 1042 REPEATED_BEEPS "recommended for fcw and other important alerts"; -CM_ SG_ 1161 SPDVAL1 "Numbers 0-199 is displayed, 200-254 displays circle without number and 255 is for no limit."; -CM_ SG_ 1161 SYNCID1 "counter from 1 to f at 1 Hz"; -CM_ SG_ 1161 SPDVAL2 "conditional speed value 70"; -CM_ SG_ 1162 SGNNUMP "1 if SPDVAL1 is set, otherwise 0"; -CM_ SG_ 1162 SYNCID2 "counter from 1 to f at 1 Hz"; -CM_ SG_ 1163 TSREQPD "always 1"; -CM_ SG_ 1163 TSRMSW "always 1"; -CM_ SG_ 1163 OTSGNNTM "always 3"; -CM_ SG_ 1163 NTLVLSPD "always 3"; -CM_ SG_ 1163 OVSPNTM "always 3"; -CM_ SG_ 1163 OVSPVALL "-5 at start then 2 after 2 seconds"; -CM_ SG_ 1163 OVSPVALM "-5 at start then 5 after 2 seconds"; -CM_ SG_ 1163 OVSPVALH "-5 at start then 10 after 2 seconds"; -CM_ SG_ 1163 TSRSPU "always 1"; -CM_ SG_ 1553 ODOMETER "Unit is dependent upon units signal"; - -VAL_ 466 CRUISE_STATE 11 "timer_3sec" 10 "adaptive click down" 9 "adaptive click up" 8 "adaptive engaged" 7 "standstill" 6 "non-adaptive click up" 5 "non-adaptive click down" 4 "non-adaptive hold down" 3 "non-adaptive hold up" 2 "non-adaptive being engaged" 1 "non-adaptive engaged" 0 "off"; -VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok"; -VAL_ 614 STATE 3 "enabled" 1 "disabled"; -VAL_ 614 DIRECTION_CMD 3 "right" 2 "center" 1 "left"; -VAL_ 643 STATE 0 "normal" 1 "adaptive_cruise_control" 3 "emergency_braking"; -VAL_ 835 ACC_TYPE 2 "permanent low speed lockout" 1 "ok"; -VAL_ 835 ACC_MALFUNCTION 1 "faulted" 0 "ok"; -VAL_ 835 ACC_CUT_IN 1 "CUT-IN Detected" 0 "clear"; -VAL_ 835 ALLOW_LONG_PRESS 2 "set speed increase by 5 speed units regardless" 1 "set speed increase by 1 speed unit on short press, 5 speed units on long press"; -VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted"; -VAL_ 1041 PCS_INDICATOR 2 "PCS Faulted" 1 "PCS Turned Off By User" 0 "PCS Enabled"; -VAL_ 1041 PCS_SENSITIVITY 64 "high sensitivity" 128 "mid sensitivity" 192 "low sensitivity" 0 "off"; -VAL_ 1042 LDA_ALERT 3 "hold with continuous beep" 2 "LDA unavailable" 1 "hold" 0 "none"; -VAL_ 1042 BARRIERS 3 "both" 2 "right" 1 "left" 0 "none"; -VAL_ 1042 RIGHT_LINE 3 "orange" 2 "faded" 1 "solid" 0 "none"; -VAL_ 1042 LEFT_LINE 3 "orange" 2 "faded" 1 "solid" 0 "none"; -VAL_ 1553 UNITS 1 "km" 2 "miles"; -VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left"; -VAL_ 1161 TSGN1 1 "speed sign" 0 "none"; -VAL_ 1161 TSGN2 1 "speed sign" 0 "none"; -VAL_ 1161 SPLSGN2 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none"; -VAL_ 1162 TSGN3 0 "none" 1 "speed sign" 2 "0 unlimited" 7 "unlimited" 16 "highway" 17 "no highway" 18 "motorway" 19 "no motorway" 20 "in city" 21 "outside city" 22 "pedestrian area" 23 "no pedestrian area" 65 "no overtaking left" 66 "no overtaking right" 67 "overtaking allowed again" 81 "no right turn" 97 "stop" 105 "yield" 113 "stop" 114 "yield us" 129 "no entry" 138 "no entry tss2" 145 "do not enter"; -VAL_ 1162 SPLSGN3 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none"; - - - - -CM_ "Imported file _comma.dbc starts here"; -BO_ 359 STEERING_IPAS_COMMA: 8 IPAS - SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX - SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX - SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX - SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant"; - - BO_ 512 GAS_COMMAND: 6 EON - SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR - SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR - SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR - - BO_ 513 GAS_SENSOR: 6 INTERCEPTOR - SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON - SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON - SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON - - VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; - -BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX - SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX - -CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss"; - -BO_ 767 SDSU: 8 XXX - SG_ FD_BUTTON : 7|1@0+ (1,0) [0|1] "" XXX - -CM_ "BO_ SDSU: The sDSU is a modified DSU for use in TSS1 Toyotas. Learn more: https://github.com/wocsor/panda/tree/smart_dsu"; - -CM_ SG_ 767 FD_BUTTON "The follow distance button signal as forwarded by the sdsu"; - -CM_ "toyota_prius_2017_pt.dbc starts here"; - - - -BO_ 295 GEAR_PACKET: 8 XXX - SG_ CAR_MOVEMENT : 39|8@0- (1,0) [0|255] "" XXX - SG_ COUNTER : 55|8@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - SG_ GEAR : 47|4@0+ (1,0) [0|15] "" XXX - -BO_ 550 BRAKE_MODULE: 8 XXX - SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|511] "" XXX - SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|511] "" XXX - SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|1] "" XXX - -BO_ 581 GAS_PEDAL: 8 XXX - SG_ GAS_PEDAL : 23|8@0+ (0.005,0) [0|1] "" XXX - -BO_ 608 STEER_TORQUE_SENSOR: 8 XXX - SG_ STEER_TORQUE_EPS : 47|16@0- (0.66,0) [-20000|20000] "" XXX - SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX - SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - SG_ STEER_ANGLE : 31|16@0- (0.0573,0) [-500|500] "" XXX - -BO_ 610 EPS_STATUS: 8 EPS - SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX - SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX - SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 1083 AUTOPARK_STATUS: 8 IPAS - SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX - -CM_ SG_ 550 BRAKE_PRESSURE "seems prop to pedal force"; -CM_ SG_ 550 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; -CM_ SG_ 581 GAS_PEDAL "it seems slightly filtered"; -CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; -CM_ SG_ 1083 STATE "when the dashboard button is pressed, the value changes from zero to non-zero"; -VAL_ 295 GEAR 0 "P" 1 "R" 2 "N" 3 "D" 4 "B"; -VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled"; -VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby"; diff --git a/opendbc/toyota_rav4_2017_pt_generated.dbc b/opendbc/toyota_rav4_2017_pt_generated.dbc deleted file mode 100644 index f70b86982..000000000 --- a/opendbc/toyota_rav4_2017_pt_generated.dbc +++ /dev/null @@ -1,449 +0,0 @@ -CM_ "AUTOGENERATED FILE, DO NOT EDIT"; - - -CM_ "Imported file _toyota_2017.dbc starts here"; -VERSION "" - - -NS_ : - NS_DESC_ - CM_ - BA_DEF_ - BA_ - VAL_ - CAT_DEF_ - CAT_ - FILTER - BA_DEF_DEF_ - EV_DATA_ - ENVVAR_DATA_ - SGTYPE_ - SGTYPE_VAL_ - BA_DEF_SGTYPE_ - BA_SGTYPE_ - SIG_TYPE_REF_ - VAL_TABLE_ - SIG_GROUP_ - SIG_VALTYPE_ - SIGTYPE_VALTYPE_ - BO_TX_BU_ - BA_DEF_REL_ - BA_REL_ - BA_DEF_DEF_REL_ - BU_SG_REL_ - BU_EV_REL_ - BU_BO_REL_ - SG_MUL_VAL_ - -BS_: - -BU_: XXX DSU HCU EPS IPAS CGW - -BO_ 36 KINEMATICS: 8 XXX - SG_ ACCEL_Y : 33|10@0+ (0.03589,-18.375) [0|65535] "m/s^2" XXX - SG_ YAW_RATE : 1|10@0+ (0.244,-125) [0|65535] "deg/sec" XXX - SG_ STEERING_TORQUE : 17|10@0+ (1,-512) [0|65535] "" XXX - -BO_ 37 STEER_ANGLE_SENSOR: 8 XXX - SG_ STEER_ANGLE : 3|12@0- (1.5,0) [-500|500] "deg" XXX - SG_ STEER_FRACTION : 39|4@0- (0.1,0) [-0.7|0.7] "deg" XXX - SG_ STEER_RATE : 35|12@0- (1,0) [-2000|2000] "deg/s" XXX - -BO_ 166 BRAKE: 8 XXX - SG_ BRAKE_AMOUNT : 7|8@0+ (1,0) [0|255] "" XXX - SG_ BRAKE_PEDAL : 23|8@0+ (1,0) [0|255] "" XXX - -BO_ 170 WHEEL_SPEEDS: 8 XXX - SG_ WHEEL_SPEED_FR : 7|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_FL : 23|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_RR : 39|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_RL : 55|16@0+ (0.01,-67.67) [0|250] "kph" XXX - -BO_ 180 SPEED: 8 XXX - SG_ ENCODER : 39|8@0+ (1,0) [0|255] "" XXX - SG_ SPEED : 47|16@0+ (0.01,0) [0|250] "kph" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 353 DSU_SPEED: 7 XXX - SG_ FORWARD_SPEED : 15|16@0- (0.00390625,-30) [0|255] "kph" XXX - -BO_ 452 ENGINE_RPM: 8 CGW - SG_ RPM : 7|16@0- (0.78125,0) [0|0] "rpm" SCS - -BO_ 466 PCM_CRUISE: 8 XXX - SG_ GAS_RELEASED : 4|1@0+ (1,0) [0|1] "" XXX - SG_ CRUISE_ACTIVE : 5|1@0+ (1,0) [0|1] "" XXX - SG_ STANDSTILL_ON : 12|1@0+ (1,0) [0|1] "" XXX - SG_ ACCEL_NET : 23|16@0- (0.001,0) [-20|20] "m/s2" XXX - SG_ CRUISE_STATE : 55|4@0+ (1,0) [0|15] "" XXX - SG_ CANCEL_REQ : 49|1@1+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 467 PCM_CRUISE_2: 8 XXX - SG_ MAIN_ON : 15|1@0+ (1,0) [0|1] "" XXX - SG_ LOW_SPEED_LOCKOUT : 14|2@0+ (1,0) [0|3] "kph" XXX - SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "kph" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 552 ACCELEROMETER: 8 XXX - SG_ ACCEL_Z : 22|15@0- (1,0) [0|32767] "" XXX - SG_ ACCEL_X : 6|15@0- (0.001,0) [-20|20] "m/s2" XXX - -BO_ 560 BRAKE_MODULE2: 7 XXX - SG_ BRAKE_PRESSED : 26|1@0+ (1,0) [0|1] "" XXX - -BO_ 614 STEERING_IPAS: 8 IPAS - SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX - SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX - SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX - SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 643 PRE_COLLISION: 7 DSU - SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 15|8@0+ (1,0) [0|255] "" XXX - SG_ FORCE : 23|16@0- (2,0) [0|255] "N" XXX - SG_ SET_ME_X002 : 33|8@0+ (1,0) [0|3] "" XXX - SG_ BRAKE_STATUS : 39|3@0+ (1,0) [0|255] "" XXX - SG_ STATE : 36|3@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X003 : 40|1@0+ (1,0) [0|1] "" XXX - SG_ PRECOLLISION_ACTIVE : 41|1@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 55|8@0+ (1,0) [0|255] "" XXX - -BO_ 740 STEERING_LKA: 5 XXX - SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX - SG_ STEER_REQUEST : 0|1@0+ (1,0) [0|1] "" XXX - SG_ COUNTER : 6|6@0+ (1,0) [0|63] "" XXX - SG_ SET_ME_1 : 7|1@0+ (1,0) [0|1] "" XXX - SG_ STEER_TORQUE_CMD : 15|16@0- (1,0) [0|65535] "" XXX - SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX - -BO_ 742 LEAD_INFO: 8 DSU - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" HCU - SG_ LEAD_REL_SPEED : 23|12@0- (0.025,0) [-100|100] "m/s" HCU - SG_ LEAD_LONG_DIST : 7|13@0+ (0.05,0) [0|300] "m" HCU - -BO_ 835 ACC_CONTROL: 8 DSU - SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU - SG_ ACC_MALFUNCTION : 18|1@0+ (1,0) [0|0] "" XXX - SG_ ACC_CUT_IN : 25|1@0+ (1,0) [0|1] "" XXX - SG_ ALLOW_LONG_PRESS : 17|2@0+ (1,0) [0|2] "" XXX - SG_ ACC_TYPE : 23|2@0+ (1,0) [0|3] "" HCU - SG_ DISTANCE : 20|1@0+ (1,0) [0|1] "" XXX - SG_ MINI_CAR : 21|1@0+ (1,0) [0|1] "" XXX - SG_ PERMIT_BRAKING : 30|1@0+ (1,0) [0|1] "" HCU - SG_ RELEASE_STANDSTILL : 31|1@0+ (1,0) [0|1] "" HCU - SG_ CANCEL_REQ : 24|1@0+ (1,0) [0|1] "" HCU - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - SG_ ACCEL_CMD_ALT : 47|8@0- (0.05,0) [0|0] "m/s^2" XXX - SG_ RADAR_DIRTY : 19|1@0+ (1,0) [0|1] "" XXX - -BO_ 836 PRE_COLLISION_2: 8 DSU - SG_ CHECKSUM : 63|8@0+ (1,0) [0|0] "" XXX - -BO_ 869 DSU_CRUISE : 7 DSU - SG_ RES_BTN : 3|1@0+ (1,0) [0|0] "" XXX - SG_ SET_BTN : 2|1@0+ (1,0) [0|0] "" XXX - SG_ CANCEL_BTN : 1|1@0+ (1,0) [0|0] "" XXX - SG_ MAIN_ON : 0|1@0+ (1,0) [0|0] "" XXX - SG_ SET_SPEED : 15|8@0+ (1,0) [0|0] "km/h" XXX - SG_ CRUISE_REQUEST : 31|8@0+ (100,-12800) [0|0] "N" XXX - SG_ LEAD_DISTANCE : 39|8@0+ (1,0) [0|0] "m" XXX - -BO_ 921 PCM_CRUISE_SM: 8 XXX - SG_ MAIN_ON : 4|1@0+ (1,0) [0|1] "" XXX - SG_ CRUISE_CONTROL_STATE : 11|4@0+ (1,0) [0|15] "" XXX - SG_ DISTANCE_LINES : 14|2@0+ (1,0) [0|3] "" XXX - SG_ UI_SET_SPEED : 31|8@0+ (1,0) [0|255] "" XXX - -BO_ 951 ESP_CONTROL: 8 ESP - SG_ TC_DISABLED : 13|1@0+ (1,0) [0|1] "" XXX - SG_ VSC_DISABLED : 12|2@0+ (1,0) [0|1] "" XXX - SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" XXX - SG_ BRAKE_HOLD_ENABLED : 33|1@1+ (1,0) [0|1] "" XXX - SG_ BRAKE_HOLD_ACTIVE : 36|1@0+ (1,0) [0|1] "" XXX - -BO_ 1020 SOLAR_SENSOR: 8 XXX - SG_ LUX_SENSOR : 55|13@0+ (1,0) [0|0] "" XXX - -BO_ 1041 ACC_HUD: 8 DSU - SG_ PCS_INDICATOR : 7|2@0+ (1,0) [0|3] "" XXX - SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X20 : 15|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X10 : 39|8@0+ (1,0) [0|1] "" XXX - SG_ PCS_OFF : 40|1@0+ (1,0) [0|0] "" XXX - SG_ PCS_SENSITIVITY : 55|8@0+ (1,0) [0|1] "" XXX - -BO_ 1042 LKAS_HUD: 8 XXX - SG_ BARRIERS : 1|2@0+ (1,0) [0|3] "" XXX - SG_ RIGHT_LINE : 3|2@0+ (1,0) [0|3] "" XXX - SG_ LEFT_LINE : 5|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X01 : 7|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X01_2 : 11|2@0+ (1,0) [0|3] "" XXX - SG_ LDA_ALERT : 9|2@0+ (1,0) [0|3] "" XXX - SG_ TWO_BEEPS : 12|1@0+ (1,0) [0|1] "" XXX - SG_ ADJUSTING_CAMERA : 13|1@0+ (1,0) [0|1] "" XXX - SG_ LDA_MALFUNCTION : 15|1@0+ (1,0) [0|1] "" XXX - SG_ REPEATED_BEEPS : 32|1@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X0C : 23|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X2C : 47|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X38 : 55|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X02 : 63|8@0+ (1,0) [0|1] "" XXX - -BO_ 1043 TIME : 8 CGW - SG_ YEAR : 7|8@0+ (1,0) [0|0] "year" XXX - SG_ MONTH : 15|8@0+ (1,0) [0|0] "month" XXX - SG_ DAY : 23|8@0+ (1,0) [0|0] "day" XXX - SG_ HOUR : 31|8@0+ (1,0) [0|0] "hour" XXX - SG_ MINUTE : 39|8@0+ (1,0) [0|0] "minute" XXX - SG_ GMT_DIFF : 55|1@0+ (1,0) [0|0] "" XXX - SG_ GMTDIFF_HOURS : 54|4@0+ (1,0) [0|0] "hours" XXX - SG_ GMTDIFF_MINUTES : 50|6@0+ (1,0) [0|0] "minutes" XXX - SG_ SUMMER : 60|1@0+ (1,0) [0|0] "" XXX - -BO_ 1408 VIN_PART_1: 8 CGW - SG_ VIN_1 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_2 : 15|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_3 : 23|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_4 : 31|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_5 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_6 : 47|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_7 : 55|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_8 : 63|8@0+ (1,0) [0|0] "" XXX - -BO_ 1409 VIN_PART_2: 8 CGW - SG_ VIN_9 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_10 : 15|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_11 : 23|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_12 : 31|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_13 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_14 : 47|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_15 : 55|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_16 : 63|8@0+ (1,0) [0|0] "" XXX - -BO_ 1410 VIN_PART_3: 8 CGW - SG_ VIN_17 : 7|8@0+ (1,0) [0|0] "" XXX - -BO_ 1553 UI_SETTING: 8 XXX - SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX - SG_ ODOMETER : 43|20@0+ (1,0) [0|1048575] "" XXX - -BO_ 1556 STEERING_LEVERS: 8 XXX - SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX - SG_ HAZARD_LIGHT : 27|1@0+ (1,0) [0|1] "" XXX - -BO_ 1568 SEATS_DOORS: 8 XXX - SG_ METER_DIMMED : 38|1@0+ (1,0) [0|1] "" XXX - SG_ PARKING_BRAKE : 60|1@0+ (1,0) [0|1] "" XXX - SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_RR : 43|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_FR : 44|1@0+ (1,0) [0|1] "" XXX - -BO_ 1570 LIGHT_STALK: 8 SCM - SG_ AUTO_HIGH_BEAM : 37|1@0+ (1,0) [0|1] "" XXX - SG_ FRONT_FOG : 27|1@0+ (1,0) [0|1] "" XXX - SG_ PARKING_LIGHT : 28|1@0+ (1,0) [0|1] "" XXX - SG_ LOW_BEAM : 29|1@0+ (1,0) [0|1] "" XXX - SG_ HIGH_BEAM : 30|1@0+ (1,0) [0|1] "" XXX - SG_ DAYTIME_RUNNING_LIGHT : 31|1@0+ (1,0) [0|1] "" XXX - -BO_ 1161 RSA1: 8 FCM - SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY1 : 12|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT1 : 9|2@0+ (1,0) [0|0] "" XXX - SG_ SPDVAL1 : 23|8@0+ (1,0) [0|0] "kph" XXX - SG_ SPLSGN1 : 31|4@0+ (1,0) [0|0] "" XXX - SG_ SPLSGN2 : 27|4@0+ (1,0) [0|0] "" XXX - SG_ TSGN2 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY2 : 44|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT2 : 41|2@0+ (1,0) [0|0] "" XXX - SG_ SPDVAL2 : 55|8@0+ (1,0) [0|0] "" XXX - SG_ BZRRQ_P : 63|2@0+ (1,0) [0|0] "" XXX - SG_ BZRRQ_A : 61|2@0+ (1,0) [0|0] "" XXX - SG_ SYNCID1 : 59|4@0+ (1,0) [0|0] "" XXX - -BO_ 1162 RSA2: 8 FCM - SG_ TSGN3 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY3 : 12|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT3 : 9|2@0+ (1,0) [0|0] "" XXX - SG_ SPLSGN3 : 31|4@0+ (1,0) [0|0] "" XXX - SG_ SPLSGN4 : 27|4@0+ (1,0) [0|0] "" XXX - SG_ TSGN4 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY4 : 44|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT4 : 41|2@0+ (1,0) [0|0] "" XXX - SG_ DPSGNREQ : 54|1@0+ (1,0) [0|0] "" XXX - SG_ SGNNUMP : 53|3@0+ (1,0) [0|0] "" XXX - SG_ SGNNUMA : 50|3@0+ (1,0) [0|0] "" XXX - SG_ SPDUNT : 63|2@0+ (1,0) [0|0] "" XXX - SG_ TSRWMSG : 61|2@0+ (1,0) [0|0] "" XXX - SG_ SYNCID2 : 59|4@0+ (1,0) [0|0] "" XXX - -BO_ 1163 RSA3: 8 FCM - SG_ TSREQPD : 7|1@0+ (1,0) [0|0] "" XXX - SG_ TSRMSW : 6|1@0+ (1,0) [0|0] "" XXX - SG_ OTSGNNTM : 5|2@0+ (1,0) [0|0] "" XXX - SG_ NTLVLSPD : 3|2@0+ (1,0) [0|0] "" XXX - SG_ OVSPNTM : 1|2@0+ (1,0) [0|0] "" XXX - SG_ OVSPVALL : 11|4@0+ (1,-5) [0|0] "" XXX - SG_ OVSPVALM : 19|4@0+ (1,-5) [0|0] "" XXX - SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX - SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" XXX - -BO_ 1571 CENTRAL_GATEWAY_UNIT: 8 CGW - SG_ DOOR_LOCK_FEEDBACK_LIGHT : 15|1@0+ (1,0) [0|0] "" XXX - SG_ KEYFOB_LOCKING_FEEDBACK_LIGHT : 61|1@0+ (1,0) [0|0] "" XXX - SG_ KEYFOB_UNLOCKING_FEEDBACK_LIGHT : 62|1@0+ (1,0) [0|0] "" XXX - -CM_ SG_ 36 ACCEL_Y "unit is tbd"; -CM_ SG_ 36 YAW_RATE "verify"; -CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; -CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; -CM_ SG_ 37 STEER_RATE "factor is tbd"; -CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; -CM_ SG_ 466 CRUISE_STATE "Active state is 8, if standstill is requested will switch to state 11(3 sec timer), after timer is elapsed will switch into state 7(standstill). If plus button was pressed - status 9, minus button pressed - status 10"; -CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isn't perfect"; -CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; -CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; -CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; -CM_ SG_ 608 STEER_OVERRIDE "set when driver torque exceeds a certain value"; -CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; -CM_ SG_ 643 COUNTER "only used on cars that use this msg for cruise control"; -CM_ SG_ 643 BRAKE_STATUS "only used on cars that use this msg for cruise control"; -CM_ SG_ 643 PRECOLLISION_ACTIVE "set 0.5s before any braking"; -CM_ SG_ 835 ACC_TYPE "if 2, car is likely to have a permanent low speed lockout. 1 is ok"; -CM_ SG_ 835 RADAR_DIRTY "Display Clean Radar Sensor message on HUD"; -CM_ SG_ 835 ACC_MALFUNCTION "display ACC fault on dash if set to 1"; -CM_ SG_ 835 ACC_CUT_IN "Display blinking yellow lead if set to 1"; -CM_ SG_ 835 DISTANCE "Display Distance Bars on HUD Permanently"; -CM_ SG_ 835 ALLOW_LONG_PRESS "Enable Toyota's factory set speed increment behaviour, available on both metrics cars and imperial unit cars"; -CM_ SG_ 835 PERMIT_BRAKING "Original ACC has this going high when a car in front is detected. In openpilot and before the PERMIT_BRAKING name, this was 'SET_ME_1' and is hardcoded to be high. Unsure if only informational or has an effect though existing usage in openpilot is to always set it to 1. Originally 'PMTBRKG' in the leaked toyota_2017_ref_pt.dbc file and name expansion speculated to be PerMiT BRaKinG."; -CM_ SG_ 835 ACCEL_CMD_ALT "Copy of main ACCEL_CMD, but across 8 bits instead of 16 bits like ACCEL_CMD. Unsure if only informational or has an effect. Likely informational as existing openpilot sets this to 0 and no loss of functionality observed. Originally 'AT_RAW' in leaked toyota_2017_ref_pt.dbc file."; -CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; -CM_ SG_ 951 BRAKE_LIGHTS_ACC "brake lights when ACC commands decel"; -CM_ SG_ 1041 PCS_INDICATOR "Pre-Collision System Indicator"; -CM_ SG_ 1041 PCS_SENSITIVITY "Pre-Collision System Sensitivity"; -CM_ SG_ 1042 SET_ME_1 "unclear what this is, but it's always 1 in drive traces"; -CM_ SG_ 1042 REPEATED_BEEPS "recommended for fcw and other important alerts"; -CM_ SG_ 1161 SPDVAL1 "Numbers 0-199 is displayed, 200-254 displays circle without number and 255 is for no limit."; -CM_ SG_ 1161 SYNCID1 "counter from 1 to f at 1 Hz"; -CM_ SG_ 1161 SPDVAL2 "conditional speed value 70"; -CM_ SG_ 1162 SGNNUMP "1 if SPDVAL1 is set, otherwise 0"; -CM_ SG_ 1162 SYNCID2 "counter from 1 to f at 1 Hz"; -CM_ SG_ 1163 TSREQPD "always 1"; -CM_ SG_ 1163 TSRMSW "always 1"; -CM_ SG_ 1163 OTSGNNTM "always 3"; -CM_ SG_ 1163 NTLVLSPD "always 3"; -CM_ SG_ 1163 OVSPNTM "always 3"; -CM_ SG_ 1163 OVSPVALL "-5 at start then 2 after 2 seconds"; -CM_ SG_ 1163 OVSPVALM "-5 at start then 5 after 2 seconds"; -CM_ SG_ 1163 OVSPVALH "-5 at start then 10 after 2 seconds"; -CM_ SG_ 1163 TSRSPU "always 1"; -CM_ SG_ 1553 ODOMETER "Unit is dependent upon units signal"; - -VAL_ 466 CRUISE_STATE 11 "timer_3sec" 10 "adaptive click down" 9 "adaptive click up" 8 "adaptive engaged" 7 "standstill" 6 "non-adaptive click up" 5 "non-adaptive click down" 4 "non-adaptive hold down" 3 "non-adaptive hold up" 2 "non-adaptive being engaged" 1 "non-adaptive engaged" 0 "off"; -VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok"; -VAL_ 614 STATE 3 "enabled" 1 "disabled"; -VAL_ 614 DIRECTION_CMD 3 "right" 2 "center" 1 "left"; -VAL_ 643 STATE 0 "normal" 1 "adaptive_cruise_control" 3 "emergency_braking"; -VAL_ 835 ACC_TYPE 2 "permanent low speed lockout" 1 "ok"; -VAL_ 835 ACC_MALFUNCTION 1 "faulted" 0 "ok"; -VAL_ 835 ACC_CUT_IN 1 "CUT-IN Detected" 0 "clear"; -VAL_ 835 ALLOW_LONG_PRESS 2 "set speed increase by 5 speed units regardless" 1 "set speed increase by 1 speed unit on short press, 5 speed units on long press"; -VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted"; -VAL_ 1041 PCS_INDICATOR 2 "PCS Faulted" 1 "PCS Turned Off By User" 0 "PCS Enabled"; -VAL_ 1041 PCS_SENSITIVITY 64 "high sensitivity" 128 "mid sensitivity" 192 "low sensitivity" 0 "off"; -VAL_ 1042 LDA_ALERT 3 "hold with continuous beep" 2 "LDA unavailable" 1 "hold" 0 "none"; -VAL_ 1042 BARRIERS 3 "both" 2 "right" 1 "left" 0 "none"; -VAL_ 1042 RIGHT_LINE 3 "orange" 2 "faded" 1 "solid" 0 "none"; -VAL_ 1042 LEFT_LINE 3 "orange" 2 "faded" 1 "solid" 0 "none"; -VAL_ 1553 UNITS 1 "km" 2 "miles"; -VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left"; -VAL_ 1161 TSGN1 1 "speed sign" 0 "none"; -VAL_ 1161 TSGN2 1 "speed sign" 0 "none"; -VAL_ 1161 SPLSGN2 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none"; -VAL_ 1162 TSGN3 0 "none" 1 "speed sign" 2 "0 unlimited" 7 "unlimited" 16 "highway" 17 "no highway" 18 "motorway" 19 "no motorway" 20 "in city" 21 "outside city" 22 "pedestrian area" 23 "no pedestrian area" 65 "no overtaking left" 66 "no overtaking right" 67 "overtaking allowed again" 81 "no right turn" 97 "stop" 105 "yield" 113 "stop" 114 "yield us" 129 "no entry" 138 "no entry tss2" 145 "do not enter"; -VAL_ 1162 SPLSGN3 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none"; - - - - -CM_ "Imported file _comma.dbc starts here"; -BO_ 359 STEERING_IPAS_COMMA: 8 IPAS - SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX - SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX - SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX - SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant"; - - BO_ 512 GAS_COMMAND: 6 EON - SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR - SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR - SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR - - BO_ 513 GAS_SENSOR: 6 INTERCEPTOR - SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON - SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON - SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON - - VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; - -BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX - SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX - -CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss"; - -BO_ 767 SDSU: 8 XXX - SG_ FD_BUTTON : 7|1@0+ (1,0) [0|1] "" XXX - -CM_ "BO_ SDSU: The sDSU is a modified DSU for use in TSS1 Toyotas. Learn more: https://github.com/wocsor/panda/tree/smart_dsu"; - -CM_ SG_ 767 FD_BUTTON "The follow distance button signal as forwarded by the sdsu"; - -CM_ "toyota_rav4_2017_pt.dbc starts here"; - - - -BO_ 548 BRAKE_MODULE: 8 XXX - SG_ BRAKE_PRESSURE : 43|12@0+ (1,0) [0|4047] "" XXX - SG_ BRAKE_PRESSED : 5|1@0+ (1,0) [0|1] "" XXX - -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 - -BO_ 608 STEER_TORQUE_SENSOR: 8 XXX - SG_ STEER_TORQUE_EPS : 47|16@0- (0.73,0) [-20000|20000] "" XXX - SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX - SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - SG_ STEER_ANGLE : 31|16@0- (0.0573,0) [-500|500] "" XXX - -BO_ 610 EPS_STATUS: 5 EPS - SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX - SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX - SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX - -BO_ 956 GEAR_PACKET: 8 XXX - SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX - -CM_ SG_ 548 BRAKE_PRESSURE "seems prop to pedal force"; -CM_ SG_ 548 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; -CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; -VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; -VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled"; -VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby"; diff --git a/opendbc/toyota_sienna_xle_2018_pt_generated.dbc b/opendbc/toyota_sienna_xle_2018_pt_generated.dbc deleted file mode 100644 index 9141a34b0..000000000 --- a/opendbc/toyota_sienna_xle_2018_pt_generated.dbc +++ /dev/null @@ -1,450 +0,0 @@ -CM_ "AUTOGENERATED FILE, DO NOT EDIT"; - - -CM_ "Imported file _toyota_2017.dbc starts here"; -VERSION "" - - -NS_ : - NS_DESC_ - CM_ - BA_DEF_ - BA_ - VAL_ - CAT_DEF_ - CAT_ - FILTER - BA_DEF_DEF_ - EV_DATA_ - ENVVAR_DATA_ - SGTYPE_ - SGTYPE_VAL_ - BA_DEF_SGTYPE_ - BA_SGTYPE_ - SIG_TYPE_REF_ - VAL_TABLE_ - SIG_GROUP_ - SIG_VALTYPE_ - SIGTYPE_VALTYPE_ - BO_TX_BU_ - BA_DEF_REL_ - BA_REL_ - BA_DEF_DEF_REL_ - BU_SG_REL_ - BU_EV_REL_ - BU_BO_REL_ - SG_MUL_VAL_ - -BS_: - -BU_: XXX DSU HCU EPS IPAS CGW - -BO_ 36 KINEMATICS: 8 XXX - SG_ ACCEL_Y : 33|10@0+ (0.03589,-18.375) [0|65535] "m/s^2" XXX - SG_ YAW_RATE : 1|10@0+ (0.244,-125) [0|65535] "deg/sec" XXX - SG_ STEERING_TORQUE : 17|10@0+ (1,-512) [0|65535] "" XXX - -BO_ 37 STEER_ANGLE_SENSOR: 8 XXX - SG_ STEER_ANGLE : 3|12@0- (1.5,0) [-500|500] "deg" XXX - SG_ STEER_FRACTION : 39|4@0- (0.1,0) [-0.7|0.7] "deg" XXX - SG_ STEER_RATE : 35|12@0- (1,0) [-2000|2000] "deg/s" XXX - -BO_ 166 BRAKE: 8 XXX - SG_ BRAKE_AMOUNT : 7|8@0+ (1,0) [0|255] "" XXX - SG_ BRAKE_PEDAL : 23|8@0+ (1,0) [0|255] "" XXX - -BO_ 170 WHEEL_SPEEDS: 8 XXX - SG_ WHEEL_SPEED_FR : 7|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_FL : 23|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_RR : 39|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_RL : 55|16@0+ (0.01,-67.67) [0|250] "kph" XXX - -BO_ 180 SPEED: 8 XXX - SG_ ENCODER : 39|8@0+ (1,0) [0|255] "" XXX - SG_ SPEED : 47|16@0+ (0.01,0) [0|250] "kph" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 353 DSU_SPEED: 7 XXX - SG_ FORWARD_SPEED : 15|16@0- (0.00390625,-30) [0|255] "kph" XXX - -BO_ 452 ENGINE_RPM: 8 CGW - SG_ RPM : 7|16@0- (0.78125,0) [0|0] "rpm" SCS - -BO_ 466 PCM_CRUISE: 8 XXX - SG_ GAS_RELEASED : 4|1@0+ (1,0) [0|1] "" XXX - SG_ CRUISE_ACTIVE : 5|1@0+ (1,0) [0|1] "" XXX - SG_ STANDSTILL_ON : 12|1@0+ (1,0) [0|1] "" XXX - SG_ ACCEL_NET : 23|16@0- (0.001,0) [-20|20] "m/s2" XXX - SG_ CRUISE_STATE : 55|4@0+ (1,0) [0|15] "" XXX - SG_ CANCEL_REQ : 49|1@1+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 467 PCM_CRUISE_2: 8 XXX - SG_ MAIN_ON : 15|1@0+ (1,0) [0|1] "" XXX - SG_ LOW_SPEED_LOCKOUT : 14|2@0+ (1,0) [0|3] "kph" XXX - SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "kph" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 552 ACCELEROMETER: 8 XXX - SG_ ACCEL_Z : 22|15@0- (1,0) [0|32767] "" XXX - SG_ ACCEL_X : 6|15@0- (0.001,0) [-20|20] "m/s2" XXX - -BO_ 560 BRAKE_MODULE2: 7 XXX - SG_ BRAKE_PRESSED : 26|1@0+ (1,0) [0|1] "" XXX - -BO_ 614 STEERING_IPAS: 8 IPAS - SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX - SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX - SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX - SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -BO_ 643 PRE_COLLISION: 7 DSU - SG_ COUNTER : 7|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 15|8@0+ (1,0) [0|255] "" XXX - SG_ FORCE : 23|16@0- (2,0) [0|255] "N" XXX - SG_ SET_ME_X002 : 33|8@0+ (1,0) [0|3] "" XXX - SG_ BRAKE_STATUS : 39|3@0+ (1,0) [0|255] "" XXX - SG_ STATE : 36|3@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X003 : 40|1@0+ (1,0) [0|1] "" XXX - SG_ PRECOLLISION_ACTIVE : 41|1@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 55|8@0+ (1,0) [0|255] "" XXX - -BO_ 740 STEERING_LKA: 5 XXX - SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX - SG_ STEER_REQUEST : 0|1@0+ (1,0) [0|1] "" XXX - SG_ COUNTER : 6|6@0+ (1,0) [0|63] "" XXX - SG_ SET_ME_1 : 7|1@0+ (1,0) [0|1] "" XXX - SG_ STEER_TORQUE_CMD : 15|16@0- (1,0) [0|65535] "" XXX - SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX - -BO_ 742 LEAD_INFO: 8 DSU - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" HCU - SG_ LEAD_REL_SPEED : 23|12@0- (0.025,0) [-100|100] "m/s" HCU - SG_ LEAD_LONG_DIST : 7|13@0+ (0.05,0) [0|300] "m" HCU - -BO_ 835 ACC_CONTROL: 8 DSU - SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU - SG_ ACC_MALFUNCTION : 18|1@0+ (1,0) [0|0] "" XXX - SG_ ACC_CUT_IN : 25|1@0+ (1,0) [0|1] "" XXX - SG_ ALLOW_LONG_PRESS : 17|2@0+ (1,0) [0|2] "" XXX - SG_ ACC_TYPE : 23|2@0+ (1,0) [0|3] "" HCU - SG_ DISTANCE : 20|1@0+ (1,0) [0|1] "" XXX - SG_ MINI_CAR : 21|1@0+ (1,0) [0|1] "" XXX - SG_ PERMIT_BRAKING : 30|1@0+ (1,0) [0|1] "" HCU - SG_ RELEASE_STANDSTILL : 31|1@0+ (1,0) [0|1] "" HCU - SG_ CANCEL_REQ : 24|1@0+ (1,0) [0|1] "" HCU - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - SG_ ACCEL_CMD_ALT : 47|8@0- (0.05,0) [0|0] "m/s^2" XXX - SG_ RADAR_DIRTY : 19|1@0+ (1,0) [0|1] "" XXX - -BO_ 836 PRE_COLLISION_2: 8 DSU - SG_ CHECKSUM : 63|8@0+ (1,0) [0|0] "" XXX - -BO_ 869 DSU_CRUISE : 7 DSU - SG_ RES_BTN : 3|1@0+ (1,0) [0|0] "" XXX - SG_ SET_BTN : 2|1@0+ (1,0) [0|0] "" XXX - SG_ CANCEL_BTN : 1|1@0+ (1,0) [0|0] "" XXX - SG_ MAIN_ON : 0|1@0+ (1,0) [0|0] "" XXX - SG_ SET_SPEED : 15|8@0+ (1,0) [0|0] "km/h" XXX - SG_ CRUISE_REQUEST : 31|8@0+ (100,-12800) [0|0] "N" XXX - SG_ LEAD_DISTANCE : 39|8@0+ (1,0) [0|0] "m" XXX - -BO_ 921 PCM_CRUISE_SM: 8 XXX - SG_ MAIN_ON : 4|1@0+ (1,0) [0|1] "" XXX - SG_ CRUISE_CONTROL_STATE : 11|4@0+ (1,0) [0|15] "" XXX - SG_ DISTANCE_LINES : 14|2@0+ (1,0) [0|3] "" XXX - SG_ UI_SET_SPEED : 31|8@0+ (1,0) [0|255] "" XXX - -BO_ 951 ESP_CONTROL: 8 ESP - SG_ TC_DISABLED : 13|1@0+ (1,0) [0|1] "" XXX - SG_ VSC_DISABLED : 12|2@0+ (1,0) [0|1] "" XXX - SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" XXX - SG_ BRAKE_HOLD_ENABLED : 33|1@1+ (1,0) [0|1] "" XXX - SG_ BRAKE_HOLD_ACTIVE : 36|1@0+ (1,0) [0|1] "" XXX - -BO_ 1020 SOLAR_SENSOR: 8 XXX - SG_ LUX_SENSOR : 55|13@0+ (1,0) [0|0] "" XXX - -BO_ 1041 ACC_HUD: 8 DSU - SG_ PCS_INDICATOR : 7|2@0+ (1,0) [0|3] "" XXX - SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X20 : 15|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X10 : 39|8@0+ (1,0) [0|1] "" XXX - SG_ PCS_OFF : 40|1@0+ (1,0) [0|0] "" XXX - SG_ PCS_SENSITIVITY : 55|8@0+ (1,0) [0|1] "" XXX - -BO_ 1042 LKAS_HUD: 8 XXX - SG_ BARRIERS : 1|2@0+ (1,0) [0|3] "" XXX - SG_ RIGHT_LINE : 3|2@0+ (1,0) [0|3] "" XXX - SG_ LEFT_LINE : 5|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X01 : 7|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X01_2 : 11|2@0+ (1,0) [0|3] "" XXX - SG_ LDA_ALERT : 9|2@0+ (1,0) [0|3] "" XXX - SG_ TWO_BEEPS : 12|1@0+ (1,0) [0|1] "" XXX - SG_ ADJUSTING_CAMERA : 13|1@0+ (1,0) [0|1] "" XXX - SG_ LDA_MALFUNCTION : 15|1@0+ (1,0) [0|1] "" XXX - SG_ REPEATED_BEEPS : 32|1@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X0C : 23|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X2C : 47|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X38 : 55|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X02 : 63|8@0+ (1,0) [0|1] "" XXX - -BO_ 1043 TIME : 8 CGW - SG_ YEAR : 7|8@0+ (1,0) [0|0] "year" XXX - SG_ MONTH : 15|8@0+ (1,0) [0|0] "month" XXX - SG_ DAY : 23|8@0+ (1,0) [0|0] "day" XXX - SG_ HOUR : 31|8@0+ (1,0) [0|0] "hour" XXX - SG_ MINUTE : 39|8@0+ (1,0) [0|0] "minute" XXX - SG_ GMT_DIFF : 55|1@0+ (1,0) [0|0] "" XXX - SG_ GMTDIFF_HOURS : 54|4@0+ (1,0) [0|0] "hours" XXX - SG_ GMTDIFF_MINUTES : 50|6@0+ (1,0) [0|0] "minutes" XXX - SG_ SUMMER : 60|1@0+ (1,0) [0|0] "" XXX - -BO_ 1408 VIN_PART_1: 8 CGW - SG_ VIN_1 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_2 : 15|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_3 : 23|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_4 : 31|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_5 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_6 : 47|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_7 : 55|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_8 : 63|8@0+ (1,0) [0|0] "" XXX - -BO_ 1409 VIN_PART_2: 8 CGW - SG_ VIN_9 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_10 : 15|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_11 : 23|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_12 : 31|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_13 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_14 : 47|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_15 : 55|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_16 : 63|8@0+ (1,0) [0|0] "" XXX - -BO_ 1410 VIN_PART_3: 8 CGW - SG_ VIN_17 : 7|8@0+ (1,0) [0|0] "" XXX - -BO_ 1553 UI_SETTING: 8 XXX - SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX - SG_ ODOMETER : 43|20@0+ (1,0) [0|1048575] "" XXX - -BO_ 1556 STEERING_LEVERS: 8 XXX - SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX - SG_ HAZARD_LIGHT : 27|1@0+ (1,0) [0|1] "" XXX - -BO_ 1568 SEATS_DOORS: 8 XXX - SG_ METER_DIMMED : 38|1@0+ (1,0) [0|1] "" XXX - SG_ PARKING_BRAKE : 60|1@0+ (1,0) [0|1] "" XXX - SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_RR : 43|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_FR : 44|1@0+ (1,0) [0|1] "" XXX - -BO_ 1570 LIGHT_STALK: 8 SCM - SG_ AUTO_HIGH_BEAM : 37|1@0+ (1,0) [0|1] "" XXX - SG_ FRONT_FOG : 27|1@0+ (1,0) [0|1] "" XXX - SG_ PARKING_LIGHT : 28|1@0+ (1,0) [0|1] "" XXX - SG_ LOW_BEAM : 29|1@0+ (1,0) [0|1] "" XXX - SG_ HIGH_BEAM : 30|1@0+ (1,0) [0|1] "" XXX - SG_ DAYTIME_RUNNING_LIGHT : 31|1@0+ (1,0) [0|1] "" XXX - -BO_ 1161 RSA1: 8 FCM - SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY1 : 12|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT1 : 9|2@0+ (1,0) [0|0] "" XXX - SG_ SPDVAL1 : 23|8@0+ (1,0) [0|0] "kph" XXX - SG_ SPLSGN1 : 31|4@0+ (1,0) [0|0] "" XXX - SG_ SPLSGN2 : 27|4@0+ (1,0) [0|0] "" XXX - SG_ TSGN2 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY2 : 44|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT2 : 41|2@0+ (1,0) [0|0] "" XXX - SG_ SPDVAL2 : 55|8@0+ (1,0) [0|0] "" XXX - SG_ BZRRQ_P : 63|2@0+ (1,0) [0|0] "" XXX - SG_ BZRRQ_A : 61|2@0+ (1,0) [0|0] "" XXX - SG_ SYNCID1 : 59|4@0+ (1,0) [0|0] "" XXX - -BO_ 1162 RSA2: 8 FCM - SG_ TSGN3 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY3 : 12|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT3 : 9|2@0+ (1,0) [0|0] "" XXX - SG_ SPLSGN3 : 31|4@0+ (1,0) [0|0] "" XXX - SG_ SPLSGN4 : 27|4@0+ (1,0) [0|0] "" XXX - SG_ TSGN4 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ TSGNGRY4 : 44|3@0+ (1,0) [0|0] "" XXX - SG_ TSGNHLT4 : 41|2@0+ (1,0) [0|0] "" XXX - SG_ DPSGNREQ : 54|1@0+ (1,0) [0|0] "" XXX - SG_ SGNNUMP : 53|3@0+ (1,0) [0|0] "" XXX - SG_ SGNNUMA : 50|3@0+ (1,0) [0|0] "" XXX - SG_ SPDUNT : 63|2@0+ (1,0) [0|0] "" XXX - SG_ TSRWMSG : 61|2@0+ (1,0) [0|0] "" XXX - SG_ SYNCID2 : 59|4@0+ (1,0) [0|0] "" XXX - -BO_ 1163 RSA3: 8 FCM - SG_ TSREQPD : 7|1@0+ (1,0) [0|0] "" XXX - SG_ TSRMSW : 6|1@0+ (1,0) [0|0] "" XXX - SG_ OTSGNNTM : 5|2@0+ (1,0) [0|0] "" XXX - SG_ NTLVLSPD : 3|2@0+ (1,0) [0|0] "" XXX - SG_ OVSPNTM : 1|2@0+ (1,0) [0|0] "" XXX - SG_ OVSPVALL : 11|4@0+ (1,-5) [0|0] "" XXX - SG_ OVSPVALM : 19|4@0+ (1,-5) [0|0] "" XXX - SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX - SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" XXX - -BO_ 1571 CENTRAL_GATEWAY_UNIT: 8 CGW - SG_ DOOR_LOCK_FEEDBACK_LIGHT : 15|1@0+ (1,0) [0|0] "" XXX - SG_ KEYFOB_LOCKING_FEEDBACK_LIGHT : 61|1@0+ (1,0) [0|0] "" XXX - SG_ KEYFOB_UNLOCKING_FEEDBACK_LIGHT : 62|1@0+ (1,0) [0|0] "" XXX - -CM_ SG_ 36 ACCEL_Y "unit is tbd"; -CM_ SG_ 36 YAW_RATE "verify"; -CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; -CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; -CM_ SG_ 37 STEER_RATE "factor is tbd"; -CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; -CM_ SG_ 466 CRUISE_STATE "Active state is 8, if standstill is requested will switch to state 11(3 sec timer), after timer is elapsed will switch into state 7(standstill). If plus button was pressed - status 9, minus button pressed - status 10"; -CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isn't perfect"; -CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; -CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; -CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; -CM_ SG_ 608 STEER_OVERRIDE "set when driver torque exceeds a certain value"; -CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; -CM_ SG_ 643 COUNTER "only used on cars that use this msg for cruise control"; -CM_ SG_ 643 BRAKE_STATUS "only used on cars that use this msg for cruise control"; -CM_ SG_ 643 PRECOLLISION_ACTIVE "set 0.5s before any braking"; -CM_ SG_ 835 ACC_TYPE "if 2, car is likely to have a permanent low speed lockout. 1 is ok"; -CM_ SG_ 835 RADAR_DIRTY "Display Clean Radar Sensor message on HUD"; -CM_ SG_ 835 ACC_MALFUNCTION "display ACC fault on dash if set to 1"; -CM_ SG_ 835 ACC_CUT_IN "Display blinking yellow lead if set to 1"; -CM_ SG_ 835 DISTANCE "Display Distance Bars on HUD Permanently"; -CM_ SG_ 835 ALLOW_LONG_PRESS "Enable Toyota's factory set speed increment behaviour, available on both metrics cars and imperial unit cars"; -CM_ SG_ 835 PERMIT_BRAKING "Original ACC has this going high when a car in front is detected. In openpilot and before the PERMIT_BRAKING name, this was 'SET_ME_1' and is hardcoded to be high. Unsure if only informational or has an effect though existing usage in openpilot is to always set it to 1. Originally 'PMTBRKG' in the leaked toyota_2017_ref_pt.dbc file and name expansion speculated to be PerMiT BRaKinG."; -CM_ SG_ 835 ACCEL_CMD_ALT "Copy of main ACCEL_CMD, but across 8 bits instead of 16 bits like ACCEL_CMD. Unsure if only informational or has an effect. Likely informational as existing openpilot sets this to 0 and no loss of functionality observed. Originally 'AT_RAW' in leaked toyota_2017_ref_pt.dbc file."; -CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; -CM_ SG_ 951 BRAKE_LIGHTS_ACC "brake lights when ACC commands decel"; -CM_ SG_ 1041 PCS_INDICATOR "Pre-Collision System Indicator"; -CM_ SG_ 1041 PCS_SENSITIVITY "Pre-Collision System Sensitivity"; -CM_ SG_ 1042 SET_ME_1 "unclear what this is, but it's always 1 in drive traces"; -CM_ SG_ 1042 REPEATED_BEEPS "recommended for fcw and other important alerts"; -CM_ SG_ 1161 SPDVAL1 "Numbers 0-199 is displayed, 200-254 displays circle without number and 255 is for no limit."; -CM_ SG_ 1161 SYNCID1 "counter from 1 to f at 1 Hz"; -CM_ SG_ 1161 SPDVAL2 "conditional speed value 70"; -CM_ SG_ 1162 SGNNUMP "1 if SPDVAL1 is set, otherwise 0"; -CM_ SG_ 1162 SYNCID2 "counter from 1 to f at 1 Hz"; -CM_ SG_ 1163 TSREQPD "always 1"; -CM_ SG_ 1163 TSRMSW "always 1"; -CM_ SG_ 1163 OTSGNNTM "always 3"; -CM_ SG_ 1163 NTLVLSPD "always 3"; -CM_ SG_ 1163 OVSPNTM "always 3"; -CM_ SG_ 1163 OVSPVALL "-5 at start then 2 after 2 seconds"; -CM_ SG_ 1163 OVSPVALM "-5 at start then 5 after 2 seconds"; -CM_ SG_ 1163 OVSPVALH "-5 at start then 10 after 2 seconds"; -CM_ SG_ 1163 TSRSPU "always 1"; -CM_ SG_ 1553 ODOMETER "Unit is dependent upon units signal"; - -VAL_ 466 CRUISE_STATE 11 "timer_3sec" 10 "adaptive click down" 9 "adaptive click up" 8 "adaptive engaged" 7 "standstill" 6 "non-adaptive click up" 5 "non-adaptive click down" 4 "non-adaptive hold down" 3 "non-adaptive hold up" 2 "non-adaptive being engaged" 1 "non-adaptive engaged" 0 "off"; -VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok"; -VAL_ 614 STATE 3 "enabled" 1 "disabled"; -VAL_ 614 DIRECTION_CMD 3 "right" 2 "center" 1 "left"; -VAL_ 643 STATE 0 "normal" 1 "adaptive_cruise_control" 3 "emergency_braking"; -VAL_ 835 ACC_TYPE 2 "permanent low speed lockout" 1 "ok"; -VAL_ 835 ACC_MALFUNCTION 1 "faulted" 0 "ok"; -VAL_ 835 ACC_CUT_IN 1 "CUT-IN Detected" 0 "clear"; -VAL_ 835 ALLOW_LONG_PRESS 2 "set speed increase by 5 speed units regardless" 1 "set speed increase by 1 speed unit on short press, 5 speed units on long press"; -VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted"; -VAL_ 1041 PCS_INDICATOR 2 "PCS Faulted" 1 "PCS Turned Off By User" 0 "PCS Enabled"; -VAL_ 1041 PCS_SENSITIVITY 64 "high sensitivity" 128 "mid sensitivity" 192 "low sensitivity" 0 "off"; -VAL_ 1042 LDA_ALERT 3 "hold with continuous beep" 2 "LDA unavailable" 1 "hold" 0 "none"; -VAL_ 1042 BARRIERS 3 "both" 2 "right" 1 "left" 0 "none"; -VAL_ 1042 RIGHT_LINE 3 "orange" 2 "faded" 1 "solid" 0 "none"; -VAL_ 1042 LEFT_LINE 3 "orange" 2 "faded" 1 "solid" 0 "none"; -VAL_ 1553 UNITS 1 "km" 2 "miles"; -VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left"; -VAL_ 1161 TSGN1 1 "speed sign" 0 "none"; -VAL_ 1161 TSGN2 1 "speed sign" 0 "none"; -VAL_ 1161 SPLSGN2 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none"; -VAL_ 1162 TSGN3 0 "none" 1 "speed sign" 2 "0 unlimited" 7 "unlimited" 16 "highway" 17 "no highway" 18 "motorway" 19 "no motorway" 20 "in city" 21 "outside city" 22 "pedestrian area" 23 "no pedestrian area" 65 "no overtaking left" 66 "no overtaking right" 67 "overtaking allowed again" 81 "no right turn" 97 "stop" 105 "yield" 113 "stop" 114 "yield us" 129 "no entry" 138 "no entry tss2" 145 "do not enter"; -VAL_ 1162 SPLSGN3 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none"; - - - - -CM_ "Imported file _comma.dbc starts here"; -BO_ 359 STEERING_IPAS_COMMA: 8 IPAS - SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX - SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX - SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX - SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant"; - - BO_ 512 GAS_COMMAND: 6 EON - SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR - SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR - SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR - - BO_ 513 GAS_SENSOR: 6 INTERCEPTOR - SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON - SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON - SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON - - VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; - -BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX - SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX - -CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss"; - -BO_ 767 SDSU: 8 XXX - SG_ FD_BUTTON : 7|1@0+ (1,0) [0|1] "" XXX - -CM_ "BO_ SDSU: The sDSU is a modified DSU for use in TSS1 Toyotas. Learn more: https://github.com/wocsor/panda/tree/smart_dsu"; - -CM_ SG_ 767 FD_BUTTON "The follow distance button signal as forwarded by the sdsu"; - -CM_ "toyota_sienna_xle_2018_pt.dbc starts here"; - - - -BO_ 550 BRAKE_MODULE: 8 XXX - SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|255] "" XXX - SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|65535] "" XXX - SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|3] "" XXX - -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 - -BO_ 608 STEER_TORQUE_SENSOR: 8 XXX - SG_ STEER_TORQUE_EPS : 47|16@0- (0.73,0) [-20000|20000] "" XXX - SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX - SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - SG_ STEER_ANGLE : 31|16@0- (0.0573,0) [-500|500] "" XXX - -BO_ 610 EPS_STATUS: 5 EPS - SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX - SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX - SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX - -BO_ 956 GEAR_PACKET: 8 XXX - SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX - -CM_ SG_ 548 BRAKE_PRESSURE "seems prop to pedal force"; -CM_ SG_ 548 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; -CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; -VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; -VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled"; -VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby" diff --git a/opendbc/toyota_rav4_hybrid_2017_pt_generated.dbc b/opendbc/toyota_tnga_k_pt_generated.dbc similarity index 70% rename from opendbc/toyota_rav4_hybrid_2017_pt_generated.dbc rename to opendbc/toyota_tnga_k_pt_generated.dbc index e6345fa8c..2f7e23606 100644 --- a/opendbc/toyota_rav4_hybrid_2017_pt_generated.dbc +++ b/opendbc/toyota_tnga_k_pt_generated.dbc @@ -1,6 +1,47 @@ CM_ "AUTOGENERATED FILE, DO NOT EDIT"; +CM_ "Imported file _comma.dbc starts here"; +BO_ 359 STEERING_IPAS_COMMA: 8 IPAS + SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX + SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX + SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX + SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX + SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + +CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant"; + +BO_ 512 GAS_COMMAND: 6 EON + SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR + SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR + SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR + SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR + SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR + +BO_ 513 GAS_SENSOR: 6 INTERCEPTOR + SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON + SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON + SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON + SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON + SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON + +VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; + +BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX + SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX + +CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss"; + +BO_ 767 SDSU: 8 XXX + SG_ FD_BUTTON : 7|1@0+ (1,0) [0|1] "" XXX + +CM_ "BO_ SDSU: The sDSU is a modified DSU for use in TSS1 Toyotas. Learn more: https://github.com/wocsor/panda/tree/smart_dsu"; +CM_ SG_ 767 FD_BUTTON "The follow distance button signal as forwarded by the sdsu"; + + CM_ "Imported file _toyota_2017.dbc starts here"; VERSION "" @@ -37,11 +78,11 @@ NS_ : BS_: -BU_: XXX DSU HCU EPS IPAS CGW +BU_: XXX DSU HCU EPS IPAS CGW BGM BO_ 36 KINEMATICS: 8 XXX SG_ ACCEL_Y : 33|10@0+ (0.03589,-18.375) [0|65535] "m/s^2" XXX - SG_ YAW_RATE : 1|10@0+ (0.244,-125) [0|65535] "deg/sec" XXX + SG_ YAW_RATE : 1|10@0+ (0.244,-125) [0|65535] "deg/s" XXX SG_ STEERING_TORQUE : 17|10@0+ (1,-512) [0|65535] "" XXX BO_ 37 STEER_ANGLE_SENSOR: 8 XXX @@ -54,18 +95,24 @@ BO_ 166 BRAKE: 8 XXX SG_ BRAKE_PEDAL : 23|8@0+ (1,0) [0|255] "" XXX BO_ 170 WHEEL_SPEEDS: 8 XXX - SG_ WHEEL_SPEED_FR : 7|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_FL : 23|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_RR : 39|16@0+ (0.01,-67.67) [0|250] "kph" XXX - SG_ WHEEL_SPEED_RL : 55|16@0+ (0.01,-67.67) [0|250] "kph" XXX + SG_ WHEEL_SPEED_FR : 7|16@0+ (0.01,-67.67) [0|250] "km/h" XXX + SG_ WHEEL_SPEED_FL : 23|16@0+ (0.01,-67.67) [0|250] "km/h" XXX + SG_ WHEEL_SPEED_RR : 39|16@0+ (0.01,-67.67) [0|250] "km/h" XXX + SG_ WHEEL_SPEED_RL : 55|16@0+ (0.01,-67.67) [0|250] "km/h" XXX BO_ 180 SPEED: 8 XXX SG_ ENCODER : 39|8@0+ (1,0) [0|255] "" XXX - SG_ SPEED : 47|16@0+ (0.01,0) [0|250] "kph" XXX + SG_ SPEED : 47|16@0+ (0.01,0) [0|250] "km/h" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX +BO_ 295 GEAR_PACKET_HYBRID: 8 XXX + SG_ CAR_MOVEMENT : 39|8@0- (1,0) [0|255] "" XXX + SG_ COUNTER : 55|8@0+ (1,0) [0|255] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ GEAR : 47|4@0+ (1,0) [0|15] "" XXX + BO_ 353 DSU_SPEED: 7 XXX - SG_ FORWARD_SPEED : 15|16@0- (0.00390625,-30) [0|255] "kph" XXX + SG_ FORWARD_SPEED : 15|16@0- (0.00390625,-30) [0|255] "km/h" XXX BO_ 452 ENGINE_RPM: 8 CGW SG_ RPM : 7|16@0- (0.78125,0) [0|0] "rpm" SCS @@ -74,24 +121,34 @@ BO_ 466 PCM_CRUISE: 8 XXX SG_ GAS_RELEASED : 4|1@0+ (1,0) [0|1] "" XXX SG_ CRUISE_ACTIVE : 5|1@0+ (1,0) [0|1] "" XXX SG_ STANDSTILL_ON : 12|1@0+ (1,0) [0|1] "" XXX - SG_ ACCEL_NET : 23|16@0- (0.001,0) [-20|20] "m/s2" XXX + SG_ ACCEL_NET : 23|16@0- (0.001,0) [-20|20] "m/s^2" XXX SG_ CRUISE_STATE : 55|4@0+ (1,0) [0|15] "" XXX SG_ CANCEL_REQ : 49|1@1+ (1,0) [0|1] "" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX BO_ 467 PCM_CRUISE_2: 8 XXX SG_ MAIN_ON : 15|1@0+ (1,0) [0|1] "" XXX - SG_ LOW_SPEED_LOCKOUT : 14|2@0+ (1,0) [0|3] "kph" XXX - SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "kph" XXX + SG_ LOW_SPEED_LOCKOUT : 14|2@0+ (1,0) [0|3] "" XXX + SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "km/h" XXX SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX BO_ 552 ACCELEROMETER: 8 XXX - SG_ ACCEL_Z : 22|15@0- (1,0) [0|32767] "" XXX - SG_ ACCEL_X : 6|15@0- (0.001,0) [-20|20] "m/s2" XXX + SG_ ACCEL_Z : 22|15@0- (1,0) [0|32767] "m/s^2" XXX + SG_ ACCEL_X : 6|15@0- (0.001,0) [-20|20] "m/s^2" XXX -BO_ 560 BRAKE_MODULE2: 7 XXX +BO_ 560 BRAKE_2: 7 XXX SG_ BRAKE_PRESSED : 26|1@0+ (1,0) [0|1] "" XXX +BO_ 581 GAS_PEDAL_HYBRID: 8 XXX + SG_ GAS_PEDAL : 23|8@0+ (0.005,0) [0|1] "" XXX + +BO_ 608 STEER_TORQUE_SENSOR: 8 XXX + SG_ STEER_TORQUE_EPS : 47|16@0- (1,0) [-32768|32767] "" XXX + SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX + SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX + SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX + SG_ STEER_ANGLE : 31|16@0- (0.0573,0) [-500|500] "" XXX + BO_ 614 STEERING_IPAS: 8 IPAS SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX @@ -113,6 +170,10 @@ BO_ 643 PRE_COLLISION: 7 DSU SG_ PRECOLLISION_ACTIVE : 41|1@0+ (1,0) [0|255] "" XXX SG_ CHECKSUM : 55|8@0+ (1,0) [0|255] "" XXX +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 + BO_ 740 STEERING_LKA: 5 XXX SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX SG_ STEER_REQUEST : 0|1@0+ (1,0) [0|1] "" XXX @@ -127,10 +188,11 @@ BO_ 742 LEAD_INFO: 8 DSU SG_ LEAD_LONG_DIST : 7|13@0+ (0.05,0) [0|300] "m" HCU BO_ 835 ACC_CONTROL: 8 DSU - SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU + SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s^2" HCU SG_ ACC_MALFUNCTION : 18|1@0+ (1,0) [0|0] "" XXX SG_ ACC_CUT_IN : 25|1@0+ (1,0) [0|1] "" XXX SG_ ALLOW_LONG_PRESS : 17|2@0+ (1,0) [0|2] "" XXX + SG_ ITS_CONNECT_LEAD : 39|8@0+ (1,0) [0|1] "" Vector__XXX SG_ ACC_TYPE : 23|2@0+ (1,0) [0|3] "" HCU SG_ DISTANCE : 20|1@0+ (1,0) [0|1] "" XXX SG_ MINI_CAR : 21|1@0+ (1,0) [0|1] "" XXX @@ -166,6 +228,23 @@ BO_ 951 ESP_CONTROL: 8 ESP SG_ BRAKE_HOLD_ENABLED : 33|1@1+ (1,0) [0|1] "" XXX SG_ BRAKE_HOLD_ACTIVE : 36|1@0+ (1,0) [0|1] "" XXX +BO_ 956 GEAR_PACKET: 8 XXX + SG_ SPORT_ON : 2|1@0+ (1,0) [0|1] "" XXX + SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX + SG_ SPORT_GEAR_ON : 33|1@0+ (1,0) [0|1] "" XXX + SG_ SPORT_GEAR : 38|3@0+ (1,0) [0|7] "" XXX + SG_ ECON_ON : 40|1@0+ (1,0) [0|1] "" XXX + SG_ B_GEAR_ENGAGED : 41|1@0+ (1,0) [0|1] "" XXX + SG_ DRIVE_ENGAGED : 47|1@0+ (1,0) [0|1] "" XXX + +BO_ 1005 REVERSE_CAMERA_STATE: 2 BGM + SG_ REVERSE_CAMERA_GUIDELINES : 9|2@0+ (1,0) [1|3] "" XXX + +BO_ 1009 PCM_CRUISE_ALT: 8 XXX + SG_ MAIN_ON : 13|1@0+ (1,0) [0|3] "" XXX + SG_ CRUISE_STATE : 10|1@0+ (1,0) [0|1] "" XXX + SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "mph" XXX + BO_ 1020 SOLAR_SENSOR: 8 XXX SG_ LUX_SENSOR : 55|13@0+ (1,0) [0|0] "" XXX @@ -177,20 +256,31 @@ BO_ 1041 ACC_HUD: 8 DSU SG_ PCS_OFF : 40|1@0+ (1,0) [0|0] "" XXX SG_ PCS_SENSITIVITY : 55|8@0+ (1,0) [0|1] "" XXX -BO_ 1042 LKAS_HUD: 8 XXX +BO_ 1042 LKAS_HUD: 8 DSU SG_ BARRIERS : 1|2@0+ (1,0) [0|3] "" XXX SG_ RIGHT_LINE : 3|2@0+ (1,0) [0|3] "" XXX SG_ LEFT_LINE : 5|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X01 : 7|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X01_2 : 11|2@0+ (1,0) [0|3] "" XXX + SG_ LKAS_STATUS : 7|2@0+ (1,0) [0|3] "" XXX SG_ LDA_ALERT : 9|2@0+ (1,0) [0|3] "" XXX + SG_ LDW_EXIST : 10|1@0+ (1,0) [0|1] "" XXX SG_ TWO_BEEPS : 12|1@0+ (1,0) [0|1] "" XXX SG_ ADJUSTING_CAMERA : 13|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_UNAVAILABLE_QUIET : 14|1@0+ (1,0) [0|1] "" XXX SG_ LDA_MALFUNCTION : 15|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_UNAVAILABLE : 16|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_SENSITIVITY : 18|2@0+ (1,0) [0|3] "" XXX + SG_ LDA_SA_TOGGLE : 20|2@0+ (1,0) [0|3] "" XXX + SG_ LDA_SPEED_TOO_LOW : 21|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_ON_MESSAGE : 31|2@0+ (1,0) [0|3] "" XXX SG_ REPEATED_BEEPS : 32|1@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X0C : 23|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X2C : 47|8@0+ (1,0) [0|1] "" XXX - SG_ SET_ME_X38 : 55|8@0+ (1,0) [0|1] "" XXX + SG_ LANE_SWAY_TOGGLE : 43|1@0+ (1,0) [0|1] "" XXX + SG_ LANE_SWAY_SENSITIVITY : 45|2@0+ (1,0) [0|3] "" XXX + SG_ TAKE_CONTROL : 46|1@0+ (1,0) [0|1] "" XXX + SG_ LDA_FRONT_CAMERA_BLOCKED : 47|1@0+ (1,0) [0|1] "" XXX + SG_ LANE_SWAY_BUZZER : 50|2@0+ (1,0) [0|0] "" XXX + SG_ LANE_SWAY_FLD : 53|3@0+ (1,0) [0|7] "" XXX + SG_ LANE_SWAY_WARNING : 55|2@0+ (1,0) [0|3] "" XXX + SG_ SET_ME_X01 : 42|1@0+ (1,0) [0|1] "" XXX SG_ SET_ME_X02 : 63|8@0+ (1,0) [0|1] "" XXX BO_ 1043 TIME : 8 CGW @@ -204,59 +294,14 @@ BO_ 1043 TIME : 8 CGW SG_ GMTDIFF_MINUTES : 50|6@0+ (1,0) [0|0] "minutes" XXX SG_ SUMMER : 60|1@0+ (1,0) [0|0] "" XXX -BO_ 1408 VIN_PART_1: 8 CGW - SG_ VIN_1 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_2 : 15|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_3 : 23|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_4 : 31|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_5 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_6 : 47|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_7 : 55|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_8 : 63|8@0+ (1,0) [0|0] "" XXX - -BO_ 1409 VIN_PART_2: 8 CGW - SG_ VIN_9 : 7|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_10 : 15|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_11 : 23|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_12 : 31|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_13 : 39|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_14 : 47|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_15 : 55|8@0+ (1,0) [0|0] "" XXX - SG_ VIN_16 : 63|8@0+ (1,0) [0|0] "" XXX - -BO_ 1410 VIN_PART_3: 8 CGW - SG_ VIN_17 : 7|8@0+ (1,0) [0|0] "" XXX - -BO_ 1553 UI_SETTING: 8 XXX - SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX - SG_ ODOMETER : 43|20@0+ (1,0) [0|1048575] "" XXX - -BO_ 1556 STEERING_LEVERS: 8 XXX - SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX - SG_ HAZARD_LIGHT : 27|1@0+ (1,0) [0|1] "" XXX - -BO_ 1568 SEATS_DOORS: 8 XXX - SG_ METER_DIMMED : 38|1@0+ (1,0) [0|1] "" XXX - SG_ PARKING_BRAKE : 60|1@0+ (1,0) [0|1] "" XXX - SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_RR : 43|1@0+ (1,0) [0|1] "" XXX - SG_ DOOR_OPEN_FR : 44|1@0+ (1,0) [0|1] "" XXX - -BO_ 1570 LIGHT_STALK: 8 SCM - SG_ AUTO_HIGH_BEAM : 37|1@0+ (1,0) [0|1] "" XXX - SG_ FRONT_FOG : 27|1@0+ (1,0) [0|1] "" XXX - SG_ PARKING_LIGHT : 28|1@0+ (1,0) [0|1] "" XXX - SG_ LOW_BEAM : 29|1@0+ (1,0) [0|1] "" XXX - SG_ HIGH_BEAM : 30|1@0+ (1,0) [0|1] "" XXX - SG_ DAYTIME_RUNNING_LIGHT : 31|1@0+ (1,0) [0|1] "" XXX +BO_ 1083 AUTOPARK_STATUS: 8 IPAS + SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX BO_ 1161 RSA1: 8 FCM SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX SG_ TSGNGRY1 : 12|3@0+ (1,0) [0|0] "" XXX SG_ TSGNHLT1 : 9|2@0+ (1,0) [0|0] "" XXX - SG_ SPDVAL1 : 23|8@0+ (1,0) [0|0] "kph" XXX + SG_ SPDVAL1 : 23|8@0+ (1,0) [0|0] "km/h" XXX SG_ SPLSGN1 : 31|4@0+ (1,0) [0|0] "" XXX SG_ SPLSGN2 : 27|4@0+ (1,0) [0|0] "" XXX SG_ TSGN2 : 39|8@0+ (1,0) [0|0] "" XXX @@ -294,21 +339,79 @@ BO_ 1163 RSA3: 8 FCM SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" XXX -BO_ 1571 CENTRAL_GATEWAY_UNIT: 8 CGW +BO_ 1408 VIN_PART_1: 8 CGW + SG_ VIN_1 : 7|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_2 : 15|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_3 : 23|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_4 : 31|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_5 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_6 : 47|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_7 : 55|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_8 : 63|8@0+ (1,0) [0|0] "" XXX + +BO_ 1409 VIN_PART_2: 8 CGW + SG_ VIN_9 : 7|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_10 : 15|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_11 : 23|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_12 : 31|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_13 : 39|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_14 : 47|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_15 : 55|8@0+ (1,0) [0|0] "" XXX + SG_ VIN_16 : 63|8@0+ (1,0) [0|0] "" XXX + +BO_ 1410 VIN_PART_3: 8 CGW + SG_ VIN_17 : 7|8@0+ (1,0) [0|0] "" XXX + +BO_ 1552 BODY_CONTROL_STATE_2: 8 XXX + SG_ METER_SLIDER_BRIGHTNESS_PCT : 30|7@0+ (1,0) [12|100] "%" XXX + SG_ METER_SLIDER_LOW_BRIGHTNESS : 37|1@0+ (1,0) [0|1] "" XXX + SG_ METER_SLIDER_DIMMED : 38|1@0+ (1,0) [0|1] "" XXX + +BO_ 1553 UI_SETTING: 8 XXX + SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX + SG_ ODOMETER : 43|20@0+ (1,0) [0|1048575] "" XXX + +BO_ 1556 BLINKERS_STATE: 8 XXX + SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX + SG_ HAZARD_LIGHT : 27|1@0+ (1,0) [0|1] "" XXX + +BO_ 1568 BODY_CONTROL_STATE: 8 XXX + SG_ METER_DIMMED : 38|1@0+ (1,0) [0|1] "" XXX + SG_ PARKING_BRAKE : 60|1@0+ (1,0) [0|1] "" XXX + SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_RR : 43|1@0+ (1,0) [0|1] "" XXX + SG_ DOOR_OPEN_FR : 44|1@0+ (1,0) [0|1] "" XXX + +BO_ 1570 LIGHT_STALK: 8 SCM + SG_ AUTO_HIGH_BEAM : 37|1@0+ (1,0) [0|1] "" XXX + SG_ FRONT_FOG : 27|1@0+ (1,0) [0|1] "" XXX + SG_ PARKING_LIGHT : 28|1@0+ (1,0) [0|1] "" XXX + SG_ LOW_BEAM : 29|1@0+ (1,0) [0|1] "" XXX + SG_ HIGH_BEAM : 30|1@0+ (1,0) [0|1] "" XXX + SG_ DAYTIME_RUNNING_LIGHT : 31|1@0+ (1,0) [0|1] "" XXX + +BO_ 1571 CERTIFICATION_ECU: 8 CGW SG_ DOOR_LOCK_FEEDBACK_LIGHT : 15|1@0+ (1,0) [0|0] "" XXX SG_ KEYFOB_LOCKING_FEEDBACK_LIGHT : 61|1@0+ (1,0) [0|0] "" XXX SG_ KEYFOB_UNLOCKING_FEEDBACK_LIGHT : 62|1@0+ (1,0) [0|0] "" XXX -CM_ SG_ 36 ACCEL_Y "unit is tbd"; +BO_ 1592 DOOR_LOCKS: 8 XXX + SG_ LOCK_STATUS_CHANGED : 15|1@0+ (1,0) [0|1] "" XXX + SG_ LOCK_STATUS : 20|1@0+ (1,0) [0|1] "" XXX + SG_ LOCKED_VIA_KEYFOB : 23|1@0+ (1,0) [0|1] "" XXX + CM_ SG_ 36 YAW_RATE "verify"; CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd"; CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set"; CM_ SG_ 37 STEER_RATE "factor is tbd"; CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors"; CM_ SG_ 466 CRUISE_STATE "Active state is 8, if standstill is requested will switch to state 11(3 sec timer), after timer is elapsed will switch into state 7(standstill). If plus button was pressed - status 9, minus button pressed - status 10"; -CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isn't perfect"; +CM_ SG_ 467 SET_SPEED "43 km/h are shown as 28 mph, so conversion isn't perfect"; CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph"; CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?"; +CM_ SG_ 581 GAS_PEDAL "it seems slightly filtered"; CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque"; CM_ SG_ 608 STEER_OVERRIDE "set when driver torque exceeds a certain value"; CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active"; @@ -320,15 +423,31 @@ CM_ SG_ 835 RADAR_DIRTY "Display Clean Radar Sensor message on HUD"; CM_ SG_ 835 ACC_MALFUNCTION "display ACC fault on dash if set to 1"; CM_ SG_ 835 ACC_CUT_IN "Display blinking yellow lead if set to 1"; CM_ SG_ 835 DISTANCE "Display Distance Bars on HUD Permanently"; +CM_ SG_ 835 ITS_CONNECT_LEAD "Displayed when lead car is capable of ITS Connect"; CM_ SG_ 835 ALLOW_LONG_PRESS "Enable Toyota's factory set speed increment behaviour, available on both metrics cars and imperial unit cars"; CM_ SG_ 835 PERMIT_BRAKING "Original ACC has this going high when a car in front is detected. In openpilot and before the PERMIT_BRAKING name, this was 'SET_ME_1' and is hardcoded to be high. Unsure if only informational or has an effect though existing usage in openpilot is to always set it to 1. Originally 'PMTBRKG' in the leaked toyota_2017_ref_pt.dbc file and name expansion speculated to be PerMiT BRaKinG."; CM_ SG_ 835 ACCEL_CMD_ALT "Copy of main ACCEL_CMD, but across 8 bits instead of 16 bits like ACCEL_CMD. Unsure if only informational or has an effect. Likely informational as existing openpilot sets this to 0 and no loss of functionality observed. Originally 'AT_RAW' in leaked toyota_2017_ref_pt.dbc file."; CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit"; CM_ SG_ 951 BRAKE_LIGHTS_ACC "brake lights when ACC commands decel"; +CM_ SG_ 1009 SET_SPEED "units seem to be whatever the car is set to"; CM_ SG_ 1041 PCS_INDICATOR "Pre-Collision System Indicator"; CM_ SG_ 1041 PCS_SENSITIVITY "Pre-Collision System Sensitivity"; -CM_ SG_ 1042 SET_ME_1 "unclear what this is, but it's always 1 in drive traces"; -CM_ SG_ 1042 REPEATED_BEEPS "recommended for fcw and other important alerts"; +CM_ SG_ 1042 LDA_SA_TOGGLE "LDA Steering Assist Toggle"; +CM_ SG_ 1042 LDW_EXIST "Unclear what this is, it's usually set to 0"; +CM_ SG_ 1042 LDA_SENSITIVITY "LDA Sensitivity"; +CM_ SG_ 1042 LDA_ON_MESSAGE "Display LDA Turned ON message"; +CM_ SG_ 1042 REPEATED_BEEPS "LDA audible warning"; +CM_ SG_ 1042 LDA_UNAVAILABLE_QUIET "LDA toggles and sensitivity settings are greyed out if set to 1"; +CM_ SG_ 1042 LDA_SPEED_TOO_LOW "length is 3 bits in the leaked DBC, displays LDA unavailable below approx 50 km/h if set to 1"; +CM_ SG_ 1042 LDA_FRONT_CAMERA_BLOCKED "originally LDAFCVB, LDA related settings are greyed out if set to 1"; +CM_ SG_ 1042 TAKE_CONTROL "Please Control Steering Wheel warning"; +CM_ SG_ 1042 LANE_SWAY_TOGGLE "Lane Sway Warning System SWS Switch"; +CM_ SG_ 1042 LANE_SWAY_WARNING "Lane Sway Warning System Triggered"; +CM_ SG_ 1042 LANE_SWAY_FLD "Unknown signal for Lane Sway Warning System, set to 7 on stock system when SWS is enabled, 0 when SWS is disabled"; +CM_ SG_ 1042 LANE_SWAY_BUZZER "Similar to TWO_BEEPS"; +CM_ SG_ 1042 SET_ME_X01 "empty bit on leaked dbc, always set to 1 during normal operations"; +CM_ SG_ 1042 SET_ME_X02 "empty bit on leaked dbc, always set to 2 during normal operations"; +CM_ SG_ 1083 STATE "when the dashboard button is pressed, the value changes from zero to non-zero"; CM_ SG_ 1161 SPDVAL1 "Numbers 0-199 is displayed, 200-254 displays circle without number and 255 is for no limit."; CM_ SG_ 1161 SYNCID1 "counter from 1 to f at 1 Hz"; CM_ SG_ 1161 SPDVAL2 "conditional speed value 70"; @@ -343,8 +462,15 @@ CM_ SG_ 1163 OVSPVALL "-5 at start then 2 after 2 seconds"; CM_ SG_ 1163 OVSPVALM "-5 at start then 5 after 2 seconds"; CM_ SG_ 1163 OVSPVALH "-5 at start then 10 after 2 seconds"; CM_ SG_ 1163 TSRSPU "always 1"; +CM_ SG_ 1552 METER_SLIDER_BRIGHTNESS_PCT "Combination display brightness setting, scales from 12 per cent to 100 per cent, reflects combination meter settings only, not linked with headlight state"; +CM_ SG_ 1552 METER_SLIDER_LOW_BRIGHTNESS "Combination display low brightness mode, also controls footwell lighting"; +CM_ SG_ 1552 METER_SLIDER_DIMMED "Combination display slider not at max, reflects combination meter settings only, not linked with headlight state"; CM_ SG_ 1553 ODOMETER "Unit is dependent upon units signal"; +CM_ SG_ 1592 LOCK_STATUS_CHANGED "1 on rising edge of lock/unlocking"; +CM_ SG_ 1592 LOCK_STATUS "The next 3 bits always seem to follow this signal."; +CM_ SG_ 1592 LOCKED_VIA_KEYFOB "1 for as long as car is locked with key fob or door handle touch"; +VAL_ 295 GEAR 0 "P" 1 "R" 2 "N" 3 "D" 4 "B"; VAL_ 466 CRUISE_STATE 11 "timer_3sec" 10 "adaptive click down" 9 "adaptive click up" 8 "adaptive engaged" 7 "standstill" 6 "non-adaptive click up" 5 "non-adaptive click down" 4 "non-adaptive hold down" 3 "non-adaptive hold up" 2 "non-adaptive being engaged" 1 "non-adaptive engaged" 0 "off"; VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok"; VAL_ 614 STATE 3 "enabled" 1 "disabled"; @@ -355,108 +481,56 @@ VAL_ 835 ACC_MALFUNCTION 1 "faulted" 0 "ok"; VAL_ 835 ACC_CUT_IN 1 "CUT-IN Detected" 0 "clear"; VAL_ 835 ALLOW_LONG_PRESS 2 "set speed increase by 5 speed units regardless" 1 "set speed increase by 1 speed unit on short press, 5 speed units on long press"; VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted"; +VAL_ 956 SPORT_ON 0 "off" 1 "on"; +VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; +VAL_ 956 SPORT_GEAR_ON 0 "off" 1 "on"; +VAL_ 956 SPORT_GEAR 1 "S1" 2 "S2" 3 "S3" 4 "S4" 5 "S5" 6 "S6"; +VAL_ 956 ECON_ON 0 "off" 1 "on"; +VAL_ 956 B_GEAR_ENGAGED 0 "off" 1 "on"; +VAL_ 956 DRIVE_ENGAGED 0 "off" 1 "on"; +VAL_ 1005 REVERSE_CAMERA_GUIDELINES 3 "No guidelines" 2 "Static guidelines" 1 "Active guidelines"; VAL_ 1041 PCS_INDICATOR 2 "PCS Faulted" 1 "PCS Turned Off By User" 0 "PCS Enabled"; VAL_ 1041 PCS_SENSITIVITY 64 "high sensitivity" 128 "mid sensitivity" 192 "low sensitivity" 0 "off"; VAL_ 1042 LDA_ALERT 3 "hold with continuous beep" 2 "LDA unavailable" 1 "hold" 0 "none"; -VAL_ 1042 BARRIERS 3 "both" 2 "right" 1 "left" 0 "none"; +VAL_ 1042 BARRIERS 3 "left" 2 "right" 1 "both" 0 "none"; VAL_ 1042 RIGHT_LINE 3 "orange" 2 "faded" 1 "solid" 0 "none"; +VAL_ 1042 LKAS_STATUS 1 "on" 0 "off"; VAL_ 1042 LEFT_LINE 3 "orange" 2 "faded" 1 "solid" 0 "none"; -VAL_ 1553 UNITS 1 "km" 2 "miles"; -VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left"; +VAL_ 1042 LDA_ON_MESSAGE 2 "Lane Departure Alert Turned ON, Steering Assist Inactive" 1 "Lane Departure Alert Turned ON, Steering Assist Active" 0 "clear"; +VAL_ 1042 LDA_SA_TOGGLE 2 "steering assist off" 1 "steering assist on"; +VAL_ 1042 LDA_SENSITIVITY 2 "standard" 1 "high" 0 "undefined"; +VAL_ 1042 LDA_SPEED_TOO_LOW 1 "lda unavailable, speed too low" 0 "ok"; +VAL_ 1042 LDA_FRONT_CAMERA_BLOCKED 1 "lda unavailable" 0 "ok"; +VAL_ 1042 TAKE_CONTROL 1 "take control" 0 "ok"; +VAL_ 1042 LANE_SWAY_WARNING 3 "ok" 2 "orange please take a break" 1 "prompt would you like to take a break" 0 "ok"; +VAL_ 1042 LANE_SWAY_BUZZER 3 "ok" 2 "beep twice" 1 "beep twice" 0 "ok"; VAL_ 1161 TSGN1 1 "speed sign" 0 "none"; VAL_ 1161 TSGN2 1 "speed sign" 0 "none"; VAL_ 1161 SPLSGN2 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none"; VAL_ 1162 TSGN3 0 "none" 1 "speed sign" 2 "0 unlimited" 7 "unlimited" 16 "highway" 17 "no highway" 18 "motorway" 19 "no motorway" 20 "in city" 21 "outside city" 22 "pedestrian area" 23 "no pedestrian area" 65 "no overtaking left" 66 "no overtaking right" 67 "overtaking allowed again" 81 "no right turn" 97 "stop" 105 "yield" 113 "stop" 114 "yield us" 129 "no entry" 138 "no entry tss2" 145 "do not enter"; VAL_ 1162 SPLSGN3 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none"; +VAL_ 1552 METER_SLIDER_LOW_BRIGHTNESS 1 "Low brightness mode, footwell lights off" 0 "Normal mode, footwell lights on"; +VAL_ 1552 METER_SLIDER_DIMMED 1 "Dimmed" 0 "Not Dimmed"; +VAL_ 1553 UNITS 1 "km" 2 "miles"; +VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left"; +VAL_ 1592 LOCK_STATUS 0 "locked" 1 "unlocked"; - - - -CM_ "Imported file _comma.dbc starts here"; -BO_ 359 STEERING_IPAS_COMMA: 8 IPAS - SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX - SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX - SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX - SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX - SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX - SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - -CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant"; - - BO_ 512 GAS_COMMAND: 6 EON - SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR - SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR - SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR - - BO_ 513 GAS_SENSOR: 6 INTERCEPTOR - SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON - SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON - SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON - SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON - SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON - - VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ; - -BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX - SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX - -CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss"; - -BO_ 767 SDSU: 8 XXX - SG_ FD_BUTTON : 7|1@0+ (1,0) [0|1] "" XXX - -CM_ "BO_ SDSU: The sDSU is a modified DSU for use in TSS1 Toyotas. Learn more: https://github.com/wocsor/panda/tree/smart_dsu"; - -CM_ SG_ 767 FD_BUTTON "The follow distance button signal as forwarded by the sdsu"; - -CM_ "toyota_rav4_hybrid_2017_pt.dbc starts here"; - - +CM_ "toyota_tnga_k_pt.dbc starts here"; BO_ 550 BRAKE_MODULE: 8 XXX SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|511] "" XXX SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|511] "" XXX SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|1] "" XXX -BO_ 581 GAS_PEDAL: 5 XXX - SG_ GAS_PEDAL : 23|8@0+ (0.005,0) [0|1] "" XXX - -BO_ 608 STEER_TORQUE_SENSOR: 8 XXX - SG_ STEER_TORQUE_EPS : 47|16@0- (0.73,0) [-20000|20000] "" XXX - SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX - SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX - SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX - SG_ STEER_ANGLE : 31|16@0- (0.0573,0) [-500|500] "" XXX - BO_ 610 EPS_STATUS: 5 EPS SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX -BO_ 956 GEAR_PACKET: 8 XXX - SG_ SPORT_ON : 2|1@0+ (1,0) [0|1] "" XXX - SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX - SG_ SPORT_GEAR_ON : 33|1@0+ (1,0) [0|1] "" XXX - SG_ SPORT_GEAR : 38|3@0+ (1,0) [0|7] "" XXX - SG_ ECON_ON : 40|1@0+ (1,0) [0|1] "" XXX - SG_ DRIVE_ENGAGED : 47|1@0+ (1,0) [0|1] "" XXX - - - CM_ SG_ 550 BRAKE_PRESSURE "seems prop to pedal force"; CM_ SG_ 550 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8"; -CM_ SG_ 581 GAS_PEDAL "it seems slightly filtered"; CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others"; + VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled"; VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby"; -VAL_ 956 SPORT_ON 0 "off" 1 "on"; -VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P"; -VAL_ 956 SPORT_GEAR_ON 0 "off" 1 "on"; -VAL_ 956 SPORT_GEAR 1 "S1" 2 "S2" 3 "S3" 4 "S4" 5 "S5" 6 "S6"; -VAL_ 956 ECON_ON 0 "off" 1 "on"; -VAL_ 956 DRIVE_ENGAGED 0 "off" 1 "on"; diff --git a/panda/__init__.py b/panda/__init__.py index a9bf38f48..f93f7314d 100644 --- a/panda/__init__.py +++ b/panda/__init__.py @@ -1,6 +1,6 @@ # flake8: noqa # pylint: skip-file -from .python import Panda, PandaWifiStreaming, PandaDFU, flash_release, \ +from .python import Panda, PandaDFU, flash_release, \ BASEDIR, ensure_st_up_to_date, PandaSerial, pack_can_buffer, unpack_can_buffer, \ DEFAULT_FW_FN, DEFAULT_H7_FW_FN, MCU_TYPE_H7, MCU_TYPE_F4, DLC_TO_LEN, LEN_TO_DLC diff --git a/panda/board/SConscript b/panda/board/SConscript index 4570bf1a5..2fcdfeeba 100644 --- a/panda/board/SConscript +++ b/panda/board/SConscript @@ -129,6 +129,9 @@ def objcopy(source, target, env, for_signature): with open("obj/gitversion.h", "w") as f: f.write(f'const uint8_t gitversion[] = "{get_version(BUILDER, BUILD_TYPE)}";\n') +with open("obj/version", "w") as f: + f.write(f'{get_version(BUILDER, BUILD_TYPE)}') + certs = [get_key_header(n) for n in ["debug", "release"]] with open("obj/cert.h", "w") as f: for cert in certs: diff --git a/panda/board/boards/black.h b/panda/board/boards/black.h index 5e86deecd..3cf58aef6 100644 --- a/panda/board/boards/black.h +++ b/panda/board/boards/black.h @@ -81,16 +81,16 @@ void black_set_gps_mode(uint8_t mode) { switch (mode) { case GPS_DISABLED: // GPS OFF - set_gpio_output(GPIOC, 14, 0); + set_gpio_output(GPIOC, 12, 0); set_gpio_output(GPIOC, 5, 0); break; case GPS_ENABLED: // GPS ON - set_gpio_output(GPIOC, 14, 1); + set_gpio_output(GPIOC, 12, 1); set_gpio_output(GPIOC, 5, 1); break; case GPS_BOOTMODE: - set_gpio_output(GPIOC, 14, 1); + set_gpio_output(GPIOC, 12, 1); set_gpio_output(GPIOC, 5, 0); break; default: @@ -168,6 +168,9 @@ void black_init(void) { // Initialize harness harness_init(); + // Initialize RTC + rtc_init(); + // Enable CAN transceivers black_enable_can_transceivers(true); @@ -206,7 +209,7 @@ const board board_black = { .has_hw_gmlan = false, .has_obd = true, .has_lin = false, - .has_rtc = false, + .has_rtc_battery = false, .init = black_init, .enable_can_transceiver = black_enable_can_transceiver, .enable_can_transceivers = black_enable_can_transceivers, diff --git a/panda/board/boards/board_declarations.h b/panda/board/boards/board_declarations.h index 0ec1a5f2a..eb9a33f19 100644 --- a/panda/board/boards/board_declarations.h +++ b/panda/board/boards/board_declarations.h @@ -22,7 +22,7 @@ struct board { const bool has_hw_gmlan; const bool has_obd; const bool has_lin; - const bool has_rtc; + const bool has_rtc_battery; board_init init; board_enable_can_transceiver enable_can_transceiver; board_enable_can_transceivers enable_can_transceivers; diff --git a/panda/board/boards/dos.h b/panda/board/boards/dos.h index 90f075e49..46354a544 100644 --- a/panda/board/boards/dos.h +++ b/panda/board/boards/dos.h @@ -208,7 +208,7 @@ const board board_dos = { .has_hw_gmlan = false, .has_obd = true, .has_lin = false, - .has_rtc = true, + .has_rtc_battery = true, .init = dos_init, .enable_can_transceiver = dos_enable_can_transceiver, .enable_can_transceivers = dos_enable_can_transceivers, diff --git a/panda/board/boards/grey.h b/panda/board/boards/grey.h index ad68787fa..6f0a55b2c 100644 --- a/panda/board/boards/grey.h +++ b/panda/board/boards/grey.h @@ -40,7 +40,7 @@ const board board_grey = { .has_hw_gmlan = true, .has_obd = false, .has_lin = true, - .has_rtc = false, + .has_rtc_battery = false, .init = grey_init, .enable_can_transceiver = white_enable_can_transceiver, .enable_can_transceivers = white_enable_can_transceivers, diff --git a/panda/board/boards/pedal.h b/panda/board/boards/pedal.h index f3922b164..1327c6454 100644 --- a/panda/board/boards/pedal.h +++ b/panda/board/boards/pedal.h @@ -83,7 +83,7 @@ const board board_pedal = { .has_hw_gmlan = false, .has_obd = false, .has_lin = false, - .has_rtc = false, + .has_rtc_battery = false, .init = pedal_init, .enable_can_transceiver = pedal_enable_can_transceiver, .enable_can_transceivers = pedal_enable_can_transceivers, diff --git a/panda/board/boards/red.h b/panda/board/boards/red.h index 17d4f0392..4499bea72 100644 --- a/panda/board/boards/red.h +++ b/panda/board/boards/red.h @@ -145,6 +145,9 @@ void red_init(void) { // Initialize harness harness_init(); + // Initialize RTC + rtc_init(); + // Enable CAN transceivers red_enable_can_transceivers(true); @@ -183,7 +186,7 @@ const board board_red = { .has_hw_gmlan = false, .has_obd = true, .has_lin = false, - .has_rtc = false, + .has_rtc_battery = false, .init = red_init, .enable_can_transceiver = red_enable_can_transceiver, .enable_can_transceivers = red_enable_can_transceivers, diff --git a/panda/board/boards/uno.h b/panda/board/boards/uno.h index d8f0e0c84..164b9a31e 100644 --- a/panda/board/boards/uno.h +++ b/panda/board/boards/uno.h @@ -269,7 +269,7 @@ const board board_uno = { .has_hw_gmlan = false, .has_obd = true, .has_lin = false, - .has_rtc = true, + .has_rtc_battery = true, .init = uno_init, .enable_can_transceiver = uno_enable_can_transceiver, .enable_can_transceivers = uno_enable_can_transceivers, diff --git a/panda/board/boards/white.h b/panda/board/boards/white.h index 560a3d4a5..6c88d621c 100644 --- a/panda/board/boards/white.h +++ b/panda/board/boards/white.h @@ -205,6 +205,9 @@ void white_grey_common_init(void) { set_gpio_alternate(GPIOC, 11, GPIO_AF7_USART3); set_gpio_pullup(GPIOC, 11, PULL_UP); + // Initialize RTC + rtc_init(); + // Enable CAN transceivers white_enable_can_transceivers(true); @@ -245,7 +248,7 @@ const board board_white = { .has_hw_gmlan = true, .has_obd = false, .has_lin = true, - .has_rtc = false, + .has_rtc_battery = false, .init = white_init, .enable_can_transceiver = white_enable_can_transceiver, .enable_can_transceivers = white_enable_can_transceivers, diff --git a/panda/board/can_definitions.h b/panda/board/can_definitions.h index 074f4e7a6..0de2da8a3 100644 --- a/panda/board/can_definitions.h +++ b/panda/board/can_definitions.h @@ -21,9 +21,5 @@ typedef struct { #define GET_MAILBOX_BYTES_04(msg) ((msg)->RDLR) #define GET_MAILBOX_BYTES_48(msg) ((msg)->RDHR) -#define CAN_INIT_TIMEOUT_MS 500U - -#define CANPACKET_HEAD_SIZE 5U - #define WORD_TO_BYTE_ARRAY(dst8, src32) 0[dst8] = ((src32) & 0xFFU); 1[dst8] = (((src32) >> 8U) & 0xFFU); 2[dst8] = (((src32) >> 16U) & 0xFFU); 3[dst8] = (((src32) >> 24U) & 0xFFU) #define BYTE_ARRAY_TO_WORD(dst32, src8) ((dst32) = 0[src8] | (1[src8] << 8U) | (2[src8] << 16U) | (3[src8] << 24U)) diff --git a/panda/board/config.h b/panda/board/config.h index 311a0a2e1..757c80e6c 100644 --- a/panda/board/config.h +++ b/panda/board/config.h @@ -7,14 +7,6 @@ //#define DEBUG_SPI //#define DEBUG_FAULTS -#define USB_VID 0xbbaaU - -#ifdef BOOTSTUB - #define USB_PID 0xddeeU -#else - #define USB_PID 0xddccU -#endif - #define NULL ((void*)0) #define COMPILE_TIME_ASSERT(pred) ((void)sizeof(char[1 - (2 * ((int)(!(pred))))])) @@ -32,9 +24,8 @@ ({ __typeof__ (a) _a = (a); \ (_a > 0) ? _a : (-_a); }) -#define MAX_RESP_LEN 0x40U - #include +#include "panda.h" #ifdef STM32H7 #include "stm32h7/stm32h7_config.h" #else diff --git a/panda/board/drivers/can_common.h b/panda/board/drivers/can_common.h index 5ec840568..273e305bc 100644 --- a/panda/board/drivers/can_common.h +++ b/panda/board/drivers/can_common.h @@ -14,14 +14,11 @@ typedef struct { bool brs_enabled; } bus_config_t; -#define CAN_BUS_NUM_MASK 0x3FU - -#define BUS_MAX 4U - uint32_t can_rx_errs = 0; uint32_t can_send_errs = 0; uint32_t can_fwd_errs = 0; uint32_t gmlan_send_errs = 0; +uint32_t blocked_msg_cnt = 0; extern int can_live; extern int pending_can_live; @@ -32,7 +29,6 @@ extern int can_silent; // Ignition detected from CAN meessages bool ignition_can = false; -bool ignition_cadillac = false; uint32_t ignition_can_cnt = 0U; #define ALL_CAN_SILENT 0xFF @@ -171,15 +167,13 @@ bus_config_t bus_config[] = { { .bus_lookup = 0xFFU, .can_num_lookup = 0xFFU, .can_speed = 333U, .can_data_speed = 333U, .canfd_enabled = false, .brs_enabled = false }, }; -#define CAN_MAX 3U - #define CANIF_FROM_CAN_NUM(num) (cans[num]) #define BUS_NUM_FROM_CAN_NUM(num) (bus_config[num].bus_lookup) #define CAN_NUM_FROM_BUS_NUM(num) (bus_config[num].can_num_lookup) void can_init_all(void) { bool ret = true; - for (uint8_t i=0U; i < CAN_MAX; i++) { + for (uint8_t i=0U; i < CAN_CNT; i++) { can_clear(can_queues[i]); ret &= can_init(i); } @@ -202,16 +196,9 @@ void ignition_can_hook(CANPacket_t *to_push) { if (bus == 0) { // GM exception - // TODO: verify on all supported GM models that we can reliably detect ignition using only this signal, - // since the 0x1F1 signal can briefly go low immediately after ignition if ((addr == 0x160) && (len == 5)) { // this message isn't all zeros when ignition is on - ignition_cadillac = GET_BYTES_04(to_push) != 0U; - } - if ((addr == 0x1F1) && (len == 8)) { - // Bit 5 is ignition "on" - bool ignition_gm = ((GET_BYTE(to_push, 0) & 0x20U) != 0U); - ignition_can = ignition_gm || ignition_cadillac; + ignition_can = GET_BYTES_04(to_push) != 0U; } // Tesla exception @@ -222,7 +209,7 @@ void ignition_can_hook(CANPacket_t *to_push) { // Mazda exception if ((addr == 0x9E) && (len == 8)) { - ignition_can = (GET_BYTE(to_push, 0) >> 4) == 0xDU; + ignition_can = (GET_BYTE(to_push, 0) >> 5) == 0x6U; } } @@ -238,7 +225,7 @@ bool can_tx_check_min_slots_free(uint32_t min) { void can_send(CANPacket_t *to_push, uint8_t bus_number, bool skip_tx_hook) { if (skip_tx_hook || safety_tx_hook(to_push) != 0) { - if (bus_number < BUS_MAX) { + if (bus_number < BUS_CNT) { // add CAN packet to send queue if ((bus_number == 3U) && (bus_config[3].can_num_lookup == 0xFFU)) { gmlan_send_errs += bitbang_gmlan(to_push) ? 0U : 1U; @@ -248,6 +235,7 @@ void can_send(CANPacket_t *to_push, uint8_t bus_number, bool skip_tx_hook) { } } } else { + blocked_msg_cnt += 1U; to_push->rejected = 1U; can_send_errs += can_push(&can_rx_q, to_push) ? 0U : 1U; } diff --git a/panda/board/drivers/rtc.h b/panda/board/drivers/rtc.h index e8d86fd5d..7f1854374 100644 --- a/panda/board/drivers/rtc.h +++ b/panda/board/drivers/rtc.h @@ -1,4 +1,5 @@ -#define RCC_BDCR_OPTIONS (RCC_BDCR_RTCEN | RCC_BDCR_RTCSEL_0 | RCC_BDCR_LSEON) +#define RCC_BDCR_OPTIONS_LSE (RCC_BDCR_RTCEN | RCC_BDCR_RTCSEL_0 | RCC_BDCR_LSEON) +#define RCC_BDCR_OPTIONS_LSI (RCC_BDCR_RTCEN | RCC_BDCR_RTCSEL_1) #define YEAR_OFFSET 2000U @@ -21,58 +22,66 @@ uint16_t from_bcd(uint8_t value){ } void rtc_init(void){ - if(current_board->has_rtc){ - // Initialize RTC module and clock if not done already. - if((RCC->BDCR & RCC_BDCR_MASK) != RCC_BDCR_OPTIONS){ - puts("Initializing RTC\n"); - // Reset backup domain - register_set_bits(&(RCC->BDCR), RCC_BDCR_BDRST); + uint32_t bdcr_opts = 0U; + uint32_t bdcr_mask = 0U; + if (current_board->has_rtc_battery) { + bdcr_opts = RCC_BDCR_OPTIONS_LSE; + bdcr_mask = RCC_BDCR_MASK_LSE; + } else { + bdcr_opts = RCC_BDCR_OPTIONS_LSI; + bdcr_mask = RCC_BDCR_MASK_LSI; + RCC->CSR |= RCC_CSR_LSION; + while((RCC->CSR & RCC_CSR_LSIRDY) == 0){} + } - // Disable write protection - disable_bdomain_protection(); + // Initialize RTC module and clock if not done already. + if((RCC->BDCR & bdcr_mask) != bdcr_opts){ + puts("Initializing RTC\n"); + // Reset backup domain + register_set_bits(&(RCC->BDCR), RCC_BDCR_BDRST); - // Clear backup domain reset - register_clear_bits(&(RCC->BDCR), RCC_BDCR_BDRST); + // Disable write protection + disable_bdomain_protection(); - // Set RTC options - register_set(&(RCC->BDCR), RCC_BDCR_OPTIONS, RCC_BDCR_MASK); + // Clear backup domain reset + register_clear_bits(&(RCC->BDCR), RCC_BDCR_BDRST); - // Enable write protection - enable_bdomain_protection(); - } + // Set RTC options + register_set(&(RCC->BDCR), bdcr_opts, bdcr_mask); + + // Enable write protection + enable_bdomain_protection(); } } void rtc_set_time(timestamp_t time){ - if(current_board->has_rtc){ - puts("Setting RTC time\n"); + puts("Setting RTC time\n"); - // Disable write protection - disable_bdomain_protection(); - RTC->WPR = 0xCA; - RTC->WPR = 0x53; + // Disable write protection + disable_bdomain_protection(); + RTC->WPR = 0xCA; + RTC->WPR = 0x53; - // Enable initialization mode - register_set_bits(&(RTC->ISR), RTC_ISR_INIT); - while((RTC->ISR & RTC_ISR_INITF) == 0){} + // Enable initialization mode + register_set_bits(&(RTC->ISR), RTC_ISR_INIT); + while((RTC->ISR & RTC_ISR_INITF) == 0){} - // Set time - RTC->TR = (to_bcd(time.hour) << RTC_TR_HU_Pos) | (to_bcd(time.minute) << RTC_TR_MNU_Pos) | (to_bcd(time.second) << RTC_TR_SU_Pos); - RTC->DR = (to_bcd(time.year - YEAR_OFFSET) << RTC_DR_YU_Pos) | (time.weekday << RTC_DR_WDU_Pos) | (to_bcd(time.month) << RTC_DR_MU_Pos) | (to_bcd(time.day) << RTC_DR_DU_Pos); + // Set time + RTC->TR = (to_bcd(time.hour) << RTC_TR_HU_Pos) | (to_bcd(time.minute) << RTC_TR_MNU_Pos) | (to_bcd(time.second) << RTC_TR_SU_Pos); + RTC->DR = (to_bcd(time.year - YEAR_OFFSET) << RTC_DR_YU_Pos) | (time.weekday << RTC_DR_WDU_Pos) | (to_bcd(time.month) << RTC_DR_MU_Pos) | (to_bcd(time.day) << RTC_DR_DU_Pos); - // Set options - register_set(&(RTC->CR), 0U, 0xFCFFFFU); + // Set options + register_set(&(RTC->CR), 0U, 0xFCFFFFU); - // Disable initalization mode - register_clear_bits(&(RTC->ISR), RTC_ISR_INIT); + // Disable initalization mode + register_clear_bits(&(RTC->ISR), RTC_ISR_INIT); - // Wait for synchronization - while((RTC->ISR & RTC_ISR_RSF) == 0){} + // Wait for synchronization + while((RTC->ISR & RTC_ISR_RSF) == 0){} - // Re-enable write protection - RTC->WPR = 0x00; - enable_bdomain_protection(); - } + // Re-enable write protection + RTC->WPR = 0x00; + enable_bdomain_protection(); } timestamp_t rtc_get_time(void){ @@ -86,22 +95,21 @@ timestamp_t rtc_get_time(void){ result.minute = 0U; result.second = 0U; - if(current_board->has_rtc){ - // Wait until the register sync flag is set - while((RTC->ISR & RTC_ISR_RSF) == 0){} + // Wait until the register sync flag is set + while((RTC->ISR & RTC_ISR_RSF) == 0){} - // Read time and date registers. Since our HSE > 7*LSE, this should be fine. - uint32_t time = RTC->TR; - uint32_t date = RTC->DR; + // Read time and date registers. Since our HSE > 7*LSE, this should be fine. + uint32_t time = RTC->TR; + uint32_t date = RTC->DR; + + // Parse values + result.year = from_bcd((date & (RTC_DR_YT | RTC_DR_YU)) >> RTC_DR_YU_Pos) + YEAR_OFFSET; + result.month = from_bcd((date & (RTC_DR_MT | RTC_DR_MU)) >> RTC_DR_MU_Pos); + result.day = from_bcd((date & (RTC_DR_DT | RTC_DR_DU)) >> RTC_DR_DU_Pos); + result.weekday = ((date & RTC_DR_WDU) >> RTC_DR_WDU_Pos); + result.hour = from_bcd((time & (RTC_TR_HT | RTC_TR_HU)) >> RTC_TR_HU_Pos); + result.minute = from_bcd((time & (RTC_TR_MNT | RTC_TR_MNU)) >> RTC_TR_MNU_Pos); + result.second = from_bcd((time & (RTC_TR_ST | RTC_TR_SU)) >> RTC_TR_SU_Pos); - // Parse values - result.year = from_bcd((date & (RTC_DR_YT | RTC_DR_YU)) >> RTC_DR_YU_Pos) + YEAR_OFFSET; - result.month = from_bcd((date & (RTC_DR_MT | RTC_DR_MU)) >> RTC_DR_MU_Pos); - result.day = from_bcd((date & (RTC_DR_DT | RTC_DR_DU)) >> RTC_DR_DU_Pos); - result.weekday = ((date & RTC_DR_WDU) >> RTC_DR_WDU_Pos); - result.hour = from_bcd((time & (RTC_TR_HT | RTC_TR_HU)) >> RTC_TR_HU_Pos); - result.minute = from_bcd((time & (RTC_TR_MNT | RTC_TR_MNU)) >> RTC_TR_MNU_Pos); - result.second = from_bcd((time & (RTC_TR_ST | RTC_TR_SU)) >> RTC_TR_SU_Pos); - } return result; } diff --git a/panda/board/drivers/usb.h b/panda/board/drivers/usb.h index 6b743bd19..f5903e95f 100644 --- a/panda/board/drivers/usb.h +++ b/panda/board/drivers/usb.h @@ -23,16 +23,13 @@ typedef union _USB_Setup { } USB_Setup_TypeDef; -#define MAX_CAN_MSGS_PER_BULK_TRANSFER 51U -#define MAX_EP1_CHUNK_PER_BULK_TRANSFER 16256 // max data stream chunk in bytes, shouldn't be higher than 16320 or counter will overflow - -bool usb_eopf_detected = false; +bool usb_enumerated = false; void usb_init(void); -int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired); -int usb_cb_ep1_in(void *usbdata, int len, bool hardwired); -void usb_cb_ep2_out(void *usbdata, int len, bool hardwired); -void usb_cb_ep3_out(void *usbdata, int len, bool hardwired); +int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp); +int usb_cb_ep1_in(void *usbdata, int len); +void usb_cb_ep2_out(void *usbdata, int len); +void usb_cb_ep3_out(void *usbdata, int len); void usb_cb_ep3_out_complete(void); void usb_cb_enumeration_complete(void); void usb_outep3_resume_if_paused(void); @@ -87,7 +84,7 @@ void usb_outep3_resume_if_paused(void); #define STS_SETUP_COMP 4 #define STS_SETUP_UPDT 6 -uint8_t resp[MAX_RESP_LEN]; +uint8_t resp[USBPACKET_MAX_SIZE]; // for the repeating interfaces #define DSCR_INTERFACE_LEN 9 @@ -387,7 +384,7 @@ void USB_WritePacket(const void *src, uint16_t len, uint32_t ep) { hexdump(src, len); #endif - uint32_t numpacket = (len + (MAX_RESP_LEN - 1U)) / MAX_RESP_LEN; + uint32_t numpacket = (len + (USBPACKET_MAX_SIZE - 1U)) / USBPACKET_MAX_SIZE; uint32_t count32b = 0; count32b = (len + 3U) / 4U; @@ -642,7 +639,7 @@ void usb_setup(void) { } break; default: - resp_len = usb_cb_control_msg(&setup, resp, 1); + resp_len = usb_cb_control_msg(&setup, resp); // response pending if -1 was returned if (resp_len != -1) { USB_WritePacket(resp, MIN(resp_len, setup.b.wLength.w), 0); @@ -683,14 +680,19 @@ void usb_irqhandler(void) { } if ((gintsts & USB_OTG_GINTSTS_EOPF) != 0) { - usb_eopf_detected = true; + usb_enumerated = true; } if ((gintsts & USB_OTG_GINTSTS_USBRST) != 0) { puts("USB reset\n"); + usb_enumerated = false; usb_reset(); } + if ((gintsts & USB_OTG_GINTSTS_USBSUSP) != 0) { + usb_enumerated = false; + } + if ((gintsts & USB_OTG_GINTSTS_ENUMDNE) != 0) { puts("enumeration done"); // Full speed, ENUMSPD @@ -735,12 +737,12 @@ void usb_irqhandler(void) { #endif if (endpoint == 2) { - usb_cb_ep2_out(usbdata, len, 1); + usb_cb_ep2_out(usbdata, len); } if (endpoint == 3) { outep3_processing = true; - usb_cb_ep3_out(usbdata, len, 1); + usb_cb_ep3_out(usbdata, len); } } else if (status == STS_SETUP_UPDT) { (void)USB_ReadPacket(&setup, 8); @@ -879,7 +881,7 @@ void usb_irqhandler(void) { puts(" IN PACKET QUEUE\n"); #endif // TODO: always assuming max len, can we get the length? - USB_WritePacket((void *)resp, usb_cb_ep1_in(resp, 0x40, 1), 1); + USB_WritePacket((void *)resp, usb_cb_ep1_in(resp, 0x40), 1); } break; @@ -890,7 +892,7 @@ void usb_irqhandler(void) { puts(" IN PACKET QUEUE\n"); #endif // TODO: always assuming max len, can we get the length? - int len = usb_cb_ep1_in(resp, 0x40, 1); + int len = usb_cb_ep1_in(resp, 0x40); if (len > 0) { USB_WritePacket((void *)resp, len, 1); } @@ -940,15 +942,3 @@ void usb_outep3_resume_if_paused(void) { } EXIT_CRITICAL(); } - -bool usb_enumerated(void) { - // This relies on the USB being suspended after no activity for 3ms. - // Seems pretty stable in combination with the EOPF to reject noise. - bool ret = false; - if(!(USBx_DEVICE->DSTS & USB_OTG_DSTS_SUSPSTS)){ - // Check to see if an end of periodic frame is detected - ret = usb_eopf_detected; - } - usb_eopf_detected = false; - return ret; -} diff --git a/panda/board/flasher.h b/panda/board/flasher.h index 534b65e78..1176bdba2 100644 --- a/panda/board/flasher.h +++ b/panda/board/flasher.h @@ -6,7 +6,7 @@ bool unlocked = false; void debug_ring_callback(uart_ring *ring) {} #endif -int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired) { +int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp) { int resp_len = 0; // flasher machine @@ -57,21 +57,11 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired) // **** 0xd1: enter bootloader mode case 0xd1: // this allows reflashing of the bootstub - // so it's blocked over wifi switch (setup->b.wValue.w) { case 0: - // TODO: put this back when it's no longer a "devkit" - //#ifdef ALLOW_DEBUG - #if 1 - if (hardwired) { - #else - // no more bootstub on UNO once OTP block is flashed - if (hardwired && ((hw_type != HW_TYPE_UNO) || (!is_provisioned()))) { - #endif - puts("-> entering bootloader\n"); - enter_bootloader_mode = ENTER_BOOTLOADER_MAGIC; - NVIC_SystemReset(); - } + puts("-> entering bootloader\n"); + enter_bootloader_mode = ENTER_BOOTLOADER_MAGIC; + NVIC_SystemReset(); break; case 1: puts("-> entering softloader\n"); @@ -82,7 +72,7 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired) break; // **** 0xd6: get version case 0xd6: - COMPILE_TIME_ASSERT(sizeof(gitversion) <= MAX_RESP_LEN); + COMPILE_TIME_ASSERT(sizeof(gitversion) <= USBPACKET_MAX_SIZE); memcpy(resp, gitversion, sizeof(gitversion)); resp_len = sizeof(gitversion); break; @@ -95,16 +85,14 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired) return resp_len; } -int usb_cb_ep1_in(void *usbdata, int len, bool hardwired) { +int usb_cb_ep1_in(void *usbdata, int len) { UNUSED(usbdata); UNUSED(len); - UNUSED(hardwired); return 0; } -void usb_cb_ep3_out(void *usbdata, int len, bool hardwired) { +void usb_cb_ep3_out(void *usbdata, int len) { UNUSED(usbdata); UNUSED(len); - UNUSED(hardwired); } void usb_cb_ep3_out_complete(void) {} @@ -114,8 +102,7 @@ void usb_cb_enumeration_complete(void) { is_enumerated = 1; } -void usb_cb_ep2_out(void *usbdata, int len, bool hardwired) { - UNUSED(hardwired); +void usb_cb_ep2_out(void *usbdata, int len) { current_board->set_led(LED_RED, 0); for (int i = 0; i < len/4; i++) { flash_write_word(prog_ptr, *(uint32_t*)(usbdata+(i*4))); @@ -133,11 +120,11 @@ int spi_cb_rx(uint8_t *data, int len, uint8_t *data_out) { switch (data[0]) { case 0: // control transfer - resp_len = usb_cb_control_msg((USB_Setup_TypeDef *)(data+4), data_out, 0); + resp_len = usb_cb_control_msg((USB_Setup_TypeDef *)(data+4), data_out); break; case 2: // ep 2, flash! - usb_cb_ep2_out(data+4, data[2], 0); + usb_cb_ep2_out(data+4, data[2]); break; } return resp_len; diff --git a/panda/board/health.h b/panda/board/health.h new file mode 100644 index 000000000..7a727d601 --- /dev/null +++ b/panda/board/health.h @@ -0,0 +1,25 @@ +// When changing this struct, boardd and python/__init__.py needs to be kept up to date! +#define HEALTH_PACKET_VERSION 3 +struct __attribute__((packed)) health_t { + uint32_t uptime_pkt; + uint32_t voltage_pkt; + uint32_t current_pkt; + uint32_t can_rx_errs_pkt; + uint32_t can_send_errs_pkt; + uint32_t can_fwd_errs_pkt; + uint32_t gmlan_send_errs_pkt; + uint32_t faults_pkt; + uint8_t ignition_line_pkt; + uint8_t ignition_can_pkt; + uint8_t controls_allowed_pkt; + uint8_t gas_interceptor_detected_pkt; + uint8_t car_harness_status_pkt; + uint8_t usb_power_mode_pkt; + uint8_t safety_mode_pkt; + int16_t safety_param_pkt; + uint8_t fault_status_pkt; + uint8_t power_save_enabled_pkt; + uint8_t heartbeat_lost_pkt; + uint16_t unsafe_mode_pkt; + uint32_t blocked_msg_cnt_pkt; +}; diff --git a/panda/board/main.c b/panda/board/main.c index ac7a75a5e..3682d1b76 100644 --- a/panda/board/main.c +++ b/panda/board/main.c @@ -20,35 +20,9 @@ #include "drivers/bxcan.h" #endif -#include "usb_protocol.h" - #include "obj/gitversion.h" -extern int _app_start[0xc000]; // Only first 3 sectors of size 0x4000 are used - -// When changing this struct, boardd and python/__init__.py needs to be kept up to date! -#define HEALTH_PACKET_VERSION 1 -struct __attribute__((packed)) health_t { - uint32_t uptime_pkt; - uint32_t voltage_pkt; - uint32_t current_pkt; - uint32_t can_rx_errs_pkt; - uint32_t can_send_errs_pkt; - uint32_t can_fwd_errs_pkt; - uint32_t gmlan_send_errs_pkt; - uint32_t faults_pkt; - uint8_t ignition_line_pkt; - uint8_t ignition_can_pkt; - uint8_t controls_allowed_pkt; - uint8_t gas_interceptor_detected_pkt; - uint8_t car_harness_status_pkt; - uint8_t usb_power_mode_pkt; - uint8_t safety_mode_pkt; - int16_t safety_param_pkt; - uint8_t fault_status_pkt; - uint8_t power_save_enabled_pkt; - uint8_t heartbeat_lost_pkt; -}; +#include "usb_comms.h" // ********************* Serial debugging ********************* @@ -109,6 +83,8 @@ void set_safety_mode(uint16_t mode, int16_t param) { } } } + blocked_msg_cnt = 0; + switch (mode_copy) { case SAFETY_SILENT: set_intercept_relay(false); @@ -156,473 +132,6 @@ bool is_car_safety_mode(uint16_t mode) { (mode != SAFETY_ELM327); } -// ***************************** USB port ***************************** - -int get_health_pkt(void *dat) { - COMPILE_TIME_ASSERT(sizeof(struct health_t) <= MAX_RESP_LEN); - struct health_t * health = (struct health_t*)dat; - - health->uptime_pkt = uptime_cnt; - health->voltage_pkt = adc_get_voltage(); - health->current_pkt = current_board->read_current(); - - //Use the GPIO pin to determine ignition or use a CAN based logic - health->ignition_line_pkt = (uint8_t)(current_board->check_ignition()); - health->ignition_can_pkt = (uint8_t)(ignition_can); - - health->controls_allowed_pkt = controls_allowed; - health->gas_interceptor_detected_pkt = gas_interceptor_detected; - health->can_rx_errs_pkt = can_rx_errs; - health->can_send_errs_pkt = can_send_errs; - health->can_fwd_errs_pkt = can_fwd_errs; - health->gmlan_send_errs_pkt = gmlan_send_errs; - health->car_harness_status_pkt = car_harness_status; - health->usb_power_mode_pkt = usb_power_mode; - health->safety_mode_pkt = (uint8_t)(current_safety_mode); - health->safety_param_pkt = current_safety_param; - health->power_save_enabled_pkt = (uint8_t)(power_save_status == POWER_SAVE_STATUS_ENABLED); - health->heartbeat_lost_pkt = (uint8_t)(heartbeat_lost); - - health->fault_status_pkt = fault_status; - health->faults_pkt = faults; - - return sizeof(*health); -} - -int get_rtc_pkt(void *dat) { - timestamp_t t = rtc_get_time(); - (void)memcpy(dat, &t, sizeof(t)); - return sizeof(t); -} - - - -// send on serial, first byte to select the ring -void usb_cb_ep2_out(void *usbdata, int len, bool hardwired) { - UNUSED(hardwired); - uint8_t *usbdata8 = (uint8_t *)usbdata; - uart_ring *ur = get_ring_by_number(usbdata8[0]); - if ((len != 0) && (ur != NULL)) { - if ((usbdata8[0] < 2U) || safety_tx_lin_hook(usbdata8[0] - 2U, &usbdata8[1], len - 1)) { - for (int i = 1; i < len; i++) { - while (!putc(ur, usbdata8[i])) { - // wait - } - } - } - } -} - -void usb_cb_ep3_out_complete(void) { - if (can_tx_check_min_slots_free(MAX_CAN_MSGS_PER_BULK_TRANSFER)) { - usb_outep3_resume_if_paused(); - } -} - -void usb_cb_enumeration_complete(void) { - puts("USB enumeration complete\n"); - is_enumerated = 1; -} - -int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired) { - unsigned int resp_len = 0; - uart_ring *ur = NULL; - timestamp_t t; - switch (setup->b.bRequest) { - // **** 0xa0: get rtc time - case 0xa0: - resp_len = get_rtc_pkt(resp); - break; - // **** 0xa1: set rtc year - case 0xa1: - t = rtc_get_time(); - t.year = setup->b.wValue.w; - rtc_set_time(t); - break; - // **** 0xa2: set rtc month - case 0xa2: - t = rtc_get_time(); - t.month = setup->b.wValue.w; - rtc_set_time(t); - break; - // **** 0xa3: set rtc day - case 0xa3: - t = rtc_get_time(); - t.day = setup->b.wValue.w; - rtc_set_time(t); - break; - // **** 0xa4: set rtc weekday - case 0xa4: - t = rtc_get_time(); - t.weekday = setup->b.wValue.w; - rtc_set_time(t); - break; - // **** 0xa5: set rtc hour - case 0xa5: - t = rtc_get_time(); - t.hour = setup->b.wValue.w; - rtc_set_time(t); - break; - // **** 0xa6: set rtc minute - case 0xa6: - t = rtc_get_time(); - t.minute = setup->b.wValue.w; - rtc_set_time(t); - break; - // **** 0xa7: set rtc second - case 0xa7: - t = rtc_get_time(); - t.second = setup->b.wValue.w; - rtc_set_time(t); - break; - // **** 0xb0: set IR power - case 0xb0: - current_board->set_ir_power(setup->b.wValue.w); - break; - // **** 0xb1: set fan power - case 0xb1: - current_board->set_fan_power(setup->b.wValue.w); - break; - // **** 0xb2: get fan rpm - case 0xb2: - resp[0] = (fan_rpm & 0x00FFU); - resp[1] = ((fan_rpm & 0xFF00U) >> 8U); - resp_len = 2; - break; - // **** 0xb3: set phone power - case 0xb3: - current_board->set_phone_power(setup->b.wValue.w > 0U); - break; - // **** 0xc0: get CAN debug info - case 0xc0: - puts("can tx: "); puth(can_tx_cnt); - puts(" txd: "); puth(can_txd_cnt); - puts(" rx: "); puth(can_rx_cnt); - puts(" err: "); puth(can_err_cnt); - puts("\n"); - break; - // **** 0xc1: get hardware type - case 0xc1: - resp[0] = hw_type; - resp_len = 1; - break; - // **** 0xd0: fetch serial number - case 0xd0: - // addresses are OTP - if (setup->b.wValue.w == 1U) { - (void)memcpy(resp, (uint8_t *)DEVICE_SERIAL_NUMBER_ADDRESS, 0x10); - resp_len = 0x10; - } else { - get_provision_chunk(resp); - resp_len = PROVISION_CHUNK_LEN; - } - break; - // **** 0xd1: enter bootloader mode - case 0xd1: - // this allows reflashing of the bootstub - // so it's blocked over wifi - switch (setup->b.wValue.w) { - case 0: - // only allow bootloader entry on debug builds - #ifdef ALLOW_DEBUG - if (hardwired) { - puts("-> entering bootloader\n"); - enter_bootloader_mode = ENTER_BOOTLOADER_MAGIC; - NVIC_SystemReset(); - } - #endif - break; - case 1: - puts("-> entering softloader\n"); - enter_bootloader_mode = ENTER_SOFTLOADER_MAGIC; - NVIC_SystemReset(); - break; - default: - puts("Bootloader mode invalid\n"); - break; - } - break; - // **** 0xd2: get health packet - case 0xd2: - resp_len = get_health_pkt(resp); - break; - // **** 0xd3: get first 64 bytes of signature - case 0xd3: - { - resp_len = 64; - char * code = (char*)_app_start; - int code_len = _app_start[0]; - (void)memcpy(resp, &code[code_len], resp_len); - } - break; - // **** 0xd4: get second 64 bytes of signature - case 0xd4: - { - resp_len = 64; - char * code = (char*)_app_start; - int code_len = _app_start[0]; - (void)memcpy(resp, &code[code_len + 64], resp_len); - } - break; - // **** 0xd6: get version - case 0xd6: - COMPILE_TIME_ASSERT(sizeof(gitversion) <= MAX_RESP_LEN); - (void)memcpy(resp, gitversion, sizeof(gitversion)); - resp_len = sizeof(gitversion) - 1U; - break; - // **** 0xd8: reset ST - case 0xd8: - NVIC_SystemReset(); - break; - // **** 0xd9: set ESP power - case 0xd9: - if (setup->b.wValue.w == 1U) { - current_board->set_gps_mode(GPS_ENABLED); - } else if (setup->b.wValue.w == 2U) { - current_board->set_gps_mode(GPS_BOOTMODE); - } else { - current_board->set_gps_mode(GPS_DISABLED); - } - break; - // **** 0xda: reset ESP, with optional boot mode - case 0xda: - current_board->set_gps_mode(GPS_DISABLED); - delay(1000000); - if (setup->b.wValue.w == 1U) { - current_board->set_gps_mode(GPS_BOOTMODE); - } else { - current_board->set_gps_mode(GPS_ENABLED); - } - delay(1000000); - current_board->set_gps_mode(GPS_ENABLED); - break; - // **** 0xdb: set GMLAN (white/grey) or OBD CAN (black) multiplexing mode - case 0xdb: - if(current_board->has_obd){ - if (setup->b.wValue.w == 1U) { - // Enable OBD CAN - current_board->set_can_mode(CAN_MODE_OBD_CAN2); - } else { - // Disable OBD CAN - current_board->set_can_mode(CAN_MODE_NORMAL); - } - } else { - if (setup->b.wValue.w == 1U) { - // GMLAN ON - if (setup->b.wIndex.w == 1U) { - can_set_gmlan(1); - } else if (setup->b.wIndex.w == 2U) { - can_set_gmlan(2); - } else { - puts("Invalid bus num for GMLAN CAN set\n"); - } - } else { - can_set_gmlan(-1); - } - } - break; - - // **** 0xdc: set safety mode - case 0xdc: - // Blocked over WiFi. - // Allow SILENT, NOOUTPUT and ELM security mode to be set over wifi. - if (hardwired || (setup->b.wValue.w == SAFETY_SILENT) || - (setup->b.wValue.w == SAFETY_NOOUTPUT) || - (setup->b.wValue.w == SAFETY_ELM327)) { - set_safety_mode(setup->b.wValue.w, (uint16_t) setup->b.wIndex.w); - } - break; - // **** 0xdd: get healthpacket and CANPacket versions - case 0xdd: - resp[0] = HEALTH_PACKET_VERSION; - resp[1] = CAN_PACKET_VERSION; - resp_len = 2; - break; - // **** 0xde: set can bitrate - case 0xde: - if (setup->b.wValue.w < BUS_MAX) { - // TODO: add sanity check, ideally check if value is correct(from array of correct values) - bus_config[setup->b.wValue.w].can_speed = setup->b.wIndex.w; - bool ret = can_init(CAN_NUM_FROM_BUS_NUM(setup->b.wValue.w)); - UNUSED(ret); - } - break; - // **** 0xdf: set unsafe mode - case 0xdf: - // you can only set this if you are in a non car safety mode - if (!is_car_safety_mode(current_safety_mode)) { - unsafe_mode = setup->b.wValue.w; - } - break; - // **** 0xe0: uart read - case 0xe0: - ur = get_ring_by_number(setup->b.wValue.w); - if (!ur) { - break; - } - - // TODO: Remove this again and fix boardd code to hande the message bursts instead of single chars - if (ur == &uart_ring_gps) { - dma_pointer_handler(ur, DMA2_Stream5->NDTR); - } - - // read - while ((resp_len < MIN(setup->b.wLength.w, MAX_RESP_LEN)) && - getc(ur, (char*)&resp[resp_len])) { - ++resp_len; - } - break; - // **** 0xe1: uart set baud rate - case 0xe1: - ur = get_ring_by_number(setup->b.wValue.w); - if (!ur) { - break; - } - uart_set_baud(ur->uart, setup->b.wIndex.w); - break; - // **** 0xe2: uart set parity - case 0xe2: - ur = get_ring_by_number(setup->b.wValue.w); - if (!ur) { - break; - } - switch (setup->b.wIndex.w) { - case 0: - // disable parity, 8-bit - ur->uart->CR1 &= ~(USART_CR1_PCE | USART_CR1_M); - break; - case 1: - // even parity, 9-bit - ur->uart->CR1 &= ~USART_CR1_PS; - ur->uart->CR1 |= USART_CR1_PCE | USART_CR1_M; - break; - case 2: - // odd parity, 9-bit - ur->uart->CR1 |= USART_CR1_PS; - ur->uart->CR1 |= USART_CR1_PCE | USART_CR1_M; - break; - default: - break; - } - break; - // **** 0xe4: uart set baud rate extended - case 0xe4: - ur = get_ring_by_number(setup->b.wValue.w); - if (!ur) { - break; - } - uart_set_baud(ur->uart, (int)setup->b.wIndex.w*300); - break; - // **** 0xe5: set CAN loopback (for testing) - case 0xe5: - can_loopback = (setup->b.wValue.w > 0U); - can_init_all(); - break; - // **** 0xe6: set USB power - case 0xe6: - current_board->set_usb_power_mode(setup->b.wValue.w); - break; - // **** 0xe7: set power save state - case 0xe7: - set_power_save_state(setup->b.wValue.w); - break; - // **** 0xf0: k-line/l-line wake-up pulse for KWP2000 fast initialization - case 0xf0: - if(current_board->has_lin) { - bool k = (setup->b.wValue.w == 0U) || (setup->b.wValue.w == 2U); - bool l = (setup->b.wValue.w == 1U) || (setup->b.wValue.w == 2U); - if (bitbang_wakeup(k, l)) { - resp_len = -1; // do not clear NAK yet (wait for bit banging to finish) - } - } - break; - // **** 0xf1: Clear CAN ring buffer. - case 0xf1: - if (setup->b.wValue.w == 0xFFFFU) { - puts("Clearing CAN Rx queue\n"); - can_clear(&can_rx_q); - } else if (setup->b.wValue.w < BUS_MAX) { - puts("Clearing CAN Tx queue\n"); - can_clear(can_queues[setup->b.wValue.w]); - } else { - puts("Clearing CAN CAN ring buffer failed: wrong bus number\n"); - } - break; - // **** 0xf2: Clear UART ring buffer. - case 0xf2: - { - uart_ring * rb = get_ring_by_number(setup->b.wValue.w); - if (rb != NULL) { - puts("Clearing UART queue.\n"); - clear_uart_buff(rb); - } - break; - } - // **** 0xf3: Heartbeat. Resets heartbeat counter. - case 0xf3: - { - heartbeat_counter = 0U; - heartbeat_lost = false; - heartbeat_disabled = false; - break; - } - // **** 0xf4: k-line/l-line 5 baud initialization - case 0xf4: - if(current_board->has_lin) { - bool k = (setup->b.wValue.w == 0U) || (setup->b.wValue.w == 2U); - bool l = (setup->b.wValue.w == 1U) || (setup->b.wValue.w == 2U); - uint8_t five_baud_addr = (setup->b.wIndex.w & 0xFFU); - if (bitbang_five_baud_addr(k, l, five_baud_addr)) { - resp_len = -1; // do not clear NAK yet (wait for bit banging to finish) - } - } - break; - // **** 0xf5: set clock source mode - case 0xf5: - current_board->set_clock_source_mode(setup->b.wValue.w); - break; - // **** 0xf6: set siren enabled - case 0xf6: - siren_enabled = (setup->b.wValue.w != 0U); - break; - // **** 0xf7: set green led enabled - case 0xf7: - green_led_enabled = (setup->b.wValue.w != 0U); - break; -#ifdef ALLOW_DEBUG - // **** 0xf8: disable heartbeat checks - case 0xf8: - heartbeat_disabled = true; - break; -#endif - // **** 0xde: set CAN FD data bitrate - case 0xf9: - if (setup->b.wValue.w < CAN_MAX) { - // TODO: add sanity check, ideally check if value is correct(from array of correct values) - bus_config[setup->b.wValue.w].can_data_speed = setup->b.wIndex.w; - bus_config[setup->b.wValue.w].canfd_enabled = (setup->b.wIndex.w >= bus_config[setup->b.wValue.w].can_speed) ? true : false; - bus_config[setup->b.wValue.w].brs_enabled = (setup->b.wIndex.w > bus_config[setup->b.wValue.w].can_speed) ? true : false; - bool ret = can_init(CAN_NUM_FROM_BUS_NUM(setup->b.wValue.w)); - UNUSED(ret); - } - break; - // **** 0xfa: check if CAN FD and BRS are enabled - case 0xfa: - if (setup->b.wValue.w < CAN_MAX) { - resp[0] = bus_config[setup->b.wValue.w].canfd_enabled; - resp[1] = bus_config[setup->b.wValue.w].brs_enabled; - resp_len = 2; - } - break; - default: - puts("NO HANDLER "); - puth(setup->b.bRequest); - puts("\n"); - break; - } - return resp_len; -} - // ***************************** main code ***************************** // cppcheck-suppress unusedFunction ; used in headers not included in cppcheck @@ -693,6 +202,16 @@ void tick_handler(void) { } + // exit controls allowed if unused by openpilot for a few seconds + if (controls_allowed && !heartbeat_engaged) { + heartbeat_engaged_mismatches += 1U; + if (heartbeat_engaged_mismatches >= 3U) { + controls_allowed = 0U; + } + } else { + heartbeat_engaged_mismatches = 0U; + } + if (!heartbeat_disabled) { // if the heartbeat has been gone for a while, go to SILENT safety mode and enter power save if (heartbeat_counter >= (check_started() ? HEARTBEAT_IGNITION_CNT_ON : HEARTBEAT_IGNITION_CNT_OFF)) { @@ -721,7 +240,7 @@ void tick_handler(void) { current_board->set_ir_power(0U); // If enumerated but no heartbeat (phone up, boardd not running), turn the fan on to cool the device - if(usb_enumerated()){ + if(usb_enumerated){ current_board->set_fan_power(50U); } else { current_board->set_fan_power(0U); diff --git a/panda/board/main_declarations.h b/panda/board/main_declarations.h index c211e5988..1a8be2e95 100644 --- a/panda/board/main_declarations.h +++ b/panda/board/main_declarations.h @@ -19,7 +19,9 @@ bool green_led_enabled = false; // heartbeat state uint32_t heartbeat_counter = 0; bool heartbeat_lost = false; -bool heartbeat_disabled = false; // set over USB +bool heartbeat_disabled = false; // set over USB +bool heartbeat_engaged = false; // openpilot enabled, passed in heartbeat USB command +uint32_t heartbeat_engaged_mismatches = 0; // count of mismatches between heartbeat_engaged and controls_allowed // siren state bool siren_enabled = false; diff --git a/panda/board/panda.h b/panda/board/panda.h new file mode 100644 index 000000000..2dbd2493b --- /dev/null +++ b/panda/board/panda.h @@ -0,0 +1,26 @@ +// USB definitions +#define USB_VID 0xBBAAU + +#ifdef BOOTSTUB + #define USB_PID 0xDDEEU +#else + #define USB_PID 0xDDCCU +#endif + +#define USBPACKET_MAX_SIZE 0x40U + +#define MAX_CAN_MSGS_PER_BULK_TRANSFER 51U +#define MAX_EP1_CHUNK_PER_BULK_TRANSFER 16256 // max data stream chunk in bytes, shouldn't be higher than 16320 or counter will overflow + +// CAN definitions +#define CANPACKET_HEAD_SIZE 5U + +#if !defined(STM32F4) && !defined(STM32F2) + #define CANPACKET_DATA_SIZE_MAX 64U +#else + #define CANPACKET_DATA_SIZE_MAX 8U +#endif + +#define CAN_CNT 3U +#define BUS_CNT 4U +#define CAN_INIT_TIMEOUT_MS 500U diff --git a/panda/board/pedal/main.c b/panda/board/pedal/main.c index 7553b3e50..c21c89f4a 100644 --- a/panda/board/pedal/main.c +++ b/panda/board/pedal/main.c @@ -41,27 +41,23 @@ void debug_ring_callback(uart_ring *ring) { } } -int usb_cb_ep1_in(void *usbdata, int len, bool hardwired) { +int usb_cb_ep1_in(void *usbdata, int len) { UNUSED(usbdata); UNUSED(len); - UNUSED(hardwired); return 0; } -void usb_cb_ep2_out(void *usbdata, int len, bool hardwired) { +void usb_cb_ep2_out(void *usbdata, int len) { UNUSED(usbdata); UNUSED(len); - UNUSED(hardwired); } -void usb_cb_ep3_out(void *usbdata, int len, bool hardwired) { +void usb_cb_ep3_out(void *usbdata, int len) { UNUSED(usbdata); UNUSED(len); - UNUSED(hardwired); } void usb_cb_ep3_out_complete(void) {} void usb_cb_enumeration_complete(void) {} -int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired) { - UNUSED(hardwired); +int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp) { unsigned int resp_len = 0; uart_ring *ur = NULL; switch (setup->b.bRequest) { @@ -77,7 +73,7 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired) break; } // read - while ((resp_len < MIN(setup->b.wLength.w, MAX_RESP_LEN)) && + while ((resp_len < MIN(setup->b.wLength.w, USBPACKET_MAX_SIZE)) && getc(ur, (char*)&resp[resp_len])) { ++resp_len; } diff --git a/panda/board/provision.h b/panda/board/provision.h index ed670a6db..842179442 100644 --- a/panda/board/provision.h +++ b/panda/board/provision.h @@ -1,9 +1,5 @@ #define PROVISION_CHUNK_LEN 0x20 -// WiFi SSID = 0x0 - 0x10 -// WiFi password = 0x10 - 0x1C -// SHA1 checksum = 0x1C - 0x20 - void get_provision_chunk(uint8_t *resp) { (void)memcpy(resp, (uint8_t *)PROVISION_CHUNK_ADDRESS, PROVISION_CHUNK_LEN); if (memcmp(resp, "\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff", 0x20) == 0) { diff --git a/panda/board/safety.h b/panda/board/safety.h index 1f1bcba72..b53f39587 100644 --- a/panda/board/safety.h +++ b/panda/board/safety.h @@ -1,6 +1,6 @@ -// include first, needed by safety policies #include "safety_declarations.h" -// Include the actual safety policies. + +// include the safety policies. #include "safety/safety_defaults.h" #include "safety/safety_honda.h" #include "safety/safety_toyota.h" @@ -12,7 +12,8 @@ #include "safety/safety_subaru.h" #include "safety/safety_mazda.h" #include "safety/safety_nissan.h" -#include "safety/safety_volkswagen.h" +#include "safety/safety_volkswagen_mqb.h" +#include "safety/safety_volkswagen_pq.h" #include "safety/safety_elm327.h" // from cereal.car.CarParams.SafetyModel diff --git a/panda/board/safety/safety_chrysler.h b/panda/board/safety/safety_chrysler.h index f94f75e7b..677d28be3 100644 --- a/panda/board/safety/safety_chrysler.h +++ b/panda/board/safety/safety_chrysler.h @@ -4,7 +4,6 @@ const uint32_t CHRYSLER_RT_INTERVAL = 250000; // 250ms between real time checks const int CHRYSLER_MAX_RATE_UP = 3; const int CHRYSLER_MAX_RATE_DOWN = 3; const int CHRYSLER_MAX_TORQUE_ERROR = 80; // max torque cmd in excess of torque motor -const int CHRYSLER_GAS_THRSLD = 30; // 7% more than 2m/s const int CHRYSLER_STANDSTILL_THRSLD = 10; // about 1m/s const CanMsg CHRYSLER_TX_MSGS[] = {{571, 0, 3}, {658, 0, 6}, {678, 0, 8}}; @@ -100,16 +99,12 @@ static int chrysler_rx_hook(CANPacket_t *to_push) { // exit controls on rising edge of gas press if (addr == 308) { - gas_pressed = ((GET_BYTE(to_push, 5) & 0x7FU) != 0U) && ((int)vehicle_speed > CHRYSLER_GAS_THRSLD); + gas_pressed = ((GET_BYTE(to_push, 5) & 0x7FU) != 0U); } // exit controls on rising edge of brake press if (addr == 320) { brake_pressed = (GET_BYTE(to_push, 0) & 0x7U) == 5U; - if (brake_pressed && (!brake_pressed_prev || vehicle_moving)) { - controls_allowed = 0; - } - brake_pressed_prev = brake_pressed; } generic_rx_checks((addr == 0x292)); diff --git a/panda/board/safety/safety_gm.h b/panda/board/safety/safety_gm.h index 9a9fef611..c2152ac6b 100644 --- a/panda/board/safety/safety_gm.h +++ b/panda/board/safety/safety_gm.h @@ -28,8 +28,8 @@ AddrCheckStruct gm_addr_checks[] = { {.msg = {{388, 0, 8, .expected_timestep = 100000U}, { 0 }, { 0 }}}, {.msg = {{842, 0, 5, .expected_timestep = 100000U}, { 0 }, { 0 }}}, {.msg = {{481, 0, 7, .expected_timestep = 100000U}, { 0 }, { 0 }}}, - {.msg = {{241, 0, 6, .expected_timestep = 100000U}, { 0 }, { 0 }}}, - {.msg = {{417, 0, 7, .expected_timestep = 100000U}, { 0 }, { 0 }}}, + {.msg = {{201, 0, 8, .expected_timestep = 100000U}, { 0 }, { 0 }}}, + {.msg = {{452, 0, 8, .expected_timestep = 100000U}, { 0 }, { 0 }}}, }; #define GM_RX_CHECK_LEN (sizeof(gm_addr_checks) / sizeof(gm_addr_checks[0])) addr_checks gm_rx_checks = {gm_addr_checks, GM_RX_CHECK_LEN}; @@ -70,15 +70,12 @@ static int gm_rx_hook(CANPacket_t *to_push) { } } - // speed > 0 - if (addr == 241) { - // Brake pedal's potentiometer returns near-zero reading - // even when pedal is not pressed - brake_pressed = GET_BYTE(to_push, 1) >= 10U; + if (addr == 201) { + brake_pressed = GET_BIT(to_push, 40U) != 0U; } - if (addr == 417) { - gas_pressed = GET_BYTE(to_push, 6) != 0U; + if (addr == 452) { + gas_pressed = GET_BYTE(to_push, 5) != 0U; } // exit controls on regen paddle diff --git a/panda/board/safety/safety_honda.h b/panda/board/safety/safety_honda.h index ed19fb8a6..eb09b628e 100644 --- a/panda/board/safety/safety_honda.h +++ b/panda/board/safety/safety_honda.h @@ -56,6 +56,7 @@ const uint16_t HONDA_PARAM_BOSCH_LONG = 2; const uint16_t HONDA_PARAM_NIDEC_ALT = 4; int honda_brake = 0; +bool honda_brake_switch_prev = false; bool honda_alt_brake_msg = false; bool honda_fwd_brake = false; bool honda_bosch_long = false; @@ -95,6 +96,8 @@ static int honda_rx_hook(CANPacket_t *to_push) { bool valid = addr_safety_check(to_push, &honda_rx_checks, honda_get_checksum, honda_compute_checksum, honda_get_counter); + const bool pcm_cruise = ((honda_hw == HONDA_BOSCH) && !honda_bosch_long) || ((honda_hw == HONDA_NIDEC) && !gas_interceptor_detected); + if (valid) { int addr = GET_ADDR(to_push); int len = GET_LEN(to_push); @@ -115,9 +118,21 @@ static int honda_rx_hook(CANPacket_t *to_push) { } } - // state machine to enter and exit controls + // enter controls when PCM enters cruise state + if (pcm_cruise && (addr == 0x17C)) { + const bool cruise_engaged = GET_BIT(to_push, 38U) != 0U; + if (!cruise_engaged) { + controls_allowed = 0; + } + if (cruise_engaged && !cruise_engaged_prev) { + controls_allowed = 1; + } + cruise_engaged_prev = cruise_engaged; + } + + // state machine to enter and exit controls for button enabling // 0x1A6 for the ILX, 0x296 for the Civic Touring - if ((addr == 0x1A6) || (addr == 0x296)) { + if (!pcm_cruise && ((addr == 0x1A6) || (addr == 0x296))) { // check for button presses int button = (GET_BYTE(to_push, 0) & 0xE0U) >> 5; switch (button) { @@ -140,11 +155,19 @@ static int honda_rx_hook(CANPacket_t *to_push) { // and crv, which prevents the usual brake safety from working correctly. these // cars have a signal on 0x1BE which only detects user's brake being applied so // in these cases, this is used instead. - // most hondas: 0x17C bit 53 - // accord, crv: 0x1BE bit 4 - bool is_user_brake_msg = honda_alt_brake_msg ? ((addr) == 0x1BE) : ((addr) == 0x17C); - if (is_user_brake_msg) { - brake_pressed = honda_alt_brake_msg ? (GET_BYTE((to_push), 0) & 0x10U) : (GET_BYTE((to_push), 6) & 0x20U); + // most hondas: 0x17C + // accord, crv: 0x1BE + if (honda_alt_brake_msg) { + if (addr == 0x1BE) { + brake_pressed = GET_BIT(to_push, 4U) != 0U; + } + } else { + if (addr == 0x17C) { + // also if brake switch is 1 for two CAN frames, as brake pressed is delayed + const bool brake_switch = GET_BIT(to_push, 32U) != 0U; + brake_pressed = (GET_BIT(to_push, 53U) != 0U) || (brake_switch && honda_brake_switch_prev); + honda_brake_switch_prev = brake_switch; + } } // length check because bosch hardware also uses this id (0x201 w/ len = 8) @@ -162,7 +185,7 @@ static int honda_rx_hook(CANPacket_t *to_push) { } // disable stock Honda AEB in unsafe mode - if ( !(unsafe_mode & UNSAFE_DISABLE_STOCK_AEB) ) { + if (!(unsafe_mode & UNSAFE_DISABLE_STOCK_AEB)) { if ((bus == 2) && (addr == 0x1FA)) { bool honda_stock_aeb = GET_BYTE(to_push, 3) & 0x20U; int honda_stock_brake = (GET_BYTE(to_push, 0) << 2) + ((GET_BYTE(to_push, 1) >> 6) & 0x3U); @@ -228,7 +251,7 @@ static int honda_tx_hook(CANPacket_t *to_send) { int pedal_pressed = brake_pressed_prev && vehicle_moving; bool unsafe_allow_gas = unsafe_mode & UNSAFE_DISABLE_DISENGAGE_ON_GAS; if (!unsafe_allow_gas) { - pedal_pressed = pedal_pressed || gas_pressed_prev || (gas_interceptor_prev > HONDA_GAS_INTERCEPTOR_THRESHOLD); + pedal_pressed = pedal_pressed || gas_pressed_prev; } bool current_controls_allowed = controls_allowed && !(pedal_pressed); int bus_pt = (honda_hw == HONDA_BOSCH) ? 1 : 0; diff --git a/panda/board/safety/safety_toyota.h b/panda/board/safety/safety_toyota.h index f3d5eff7e..648d10d76 100644 --- a/panda/board/safety/safety_toyota.h +++ b/panda/board/safety/safety_toyota.h @@ -172,6 +172,15 @@ static int toyota_tx_hook(CANPacket_t *to_send) { } } + // AEB: block all actuation. only used when DSU is unplugged + if (addr == 0x283) { + // only allow the checksum, which is the last byte + bool block = (GET_BYTES_04(to_send) != 0U) || (GET_BYTE(to_send, 4) != 0U) || (GET_BYTE(to_send, 5) != 0U); + if (block) { + tx = 0; + } + } + // LTA steering check // only sent to prevent dash errors, no actuation is accepted if (addr == 0x191) { diff --git a/panda/board/safety/safety_volkswagen.h b/panda/board/safety/safety_volkswagen.h deleted file mode 100644 index 8666c8807..000000000 --- a/panda/board/safety/safety_volkswagen.h +++ /dev/null @@ -1,416 +0,0 @@ -// Safety-relevant steering constants for Volkswagen -const int VOLKSWAGEN_MAX_STEER = 300; // 3.0 Nm (EPS side max of 3.0Nm with fault if violated) -const int VOLKSWAGEN_MAX_RT_DELTA = 75; // 4 max rate up * 50Hz send rate * 250000 RT interval / 1000000 = 50 ; 50 * 1.5 for safety pad = 75 -const uint32_t VOLKSWAGEN_RT_INTERVAL = 250000; // 250ms between real time checks -const int VOLKSWAGEN_MAX_RATE_UP = 4; // 2.0 Nm/s RoC limit (EPS rack has own soft-limit of 5.0 Nm/s) -const int VOLKSWAGEN_MAX_RATE_DOWN = 10; // 5.0 Nm/s RoC limit (EPS rack has own soft-limit of 5.0 Nm/s) -const int VOLKSWAGEN_DRIVER_TORQUE_ALLOWANCE = 80; -const int VOLKSWAGEN_DRIVER_TORQUE_FACTOR = 3; - -// Safety-relevant CAN messages for the Volkswagen MQB platform -#define MSG_ESP_19 0x0B2 // RX from ABS, for wheel speeds -#define MSG_LH_EPS_03 0x09F // RX from EPS, for driver steering torque -#define MSG_ESP_05 0x106 // RX from ABS, for brake switch state -#define MSG_TSK_06 0x120 // RX from ECU, for ACC status from drivetrain coordinator -#define MSG_MOTOR_20 0x121 // RX from ECU, for driver throttle input -#define MSG_HCA_01 0x126 // TX by OP, Heading Control Assist steering torque -#define MSG_GRA_ACC_01 0x12B // TX by OP, ACC control buttons for cancel/resume -#define MSG_LDW_02 0x397 // TX by OP, Lane line recognition and text alerts - -// Transmit of GRA_ACC_01 is allowed on bus 0 and 2 to keep compatibility with gateway and camera integration -const CanMsg VOLKSWAGEN_MQB_TX_MSGS[] = {{MSG_HCA_01, 0, 8}, {MSG_GRA_ACC_01, 0, 8}, {MSG_GRA_ACC_01, 2, 8}, {MSG_LDW_02, 0, 8}}; -#define VOLKSWAGEN_MQB_TX_MSGS_LEN (sizeof(VOLKSWAGEN_MQB_TX_MSGS) / sizeof(VOLKSWAGEN_MQB_TX_MSGS[0])) - -AddrCheckStruct volkswagen_mqb_addr_checks[] = { - {.msg = {{MSG_ESP_19, 0, 8, .check_checksum = false, .max_counter = 0U, .expected_timestep = 10000U}, { 0 }, { 0 }}}, - {.msg = {{MSG_LH_EPS_03, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 10000U}, { 0 }, { 0 }}}, - {.msg = {{MSG_ESP_05, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}, { 0 }, { 0 }}}, - {.msg = {{MSG_TSK_06, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}, { 0 }, { 0 }}}, - {.msg = {{MSG_MOTOR_20, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}, { 0 }, { 0 }}}, -}; -#define VOLKSWAGEN_MQB_ADDR_CHECKS_LEN (sizeof(volkswagen_mqb_addr_checks) / sizeof(volkswagen_mqb_addr_checks[0])) -addr_checks volkswagen_mqb_rx_checks = {volkswagen_mqb_addr_checks, VOLKSWAGEN_MQB_ADDR_CHECKS_LEN}; - -// Safety-relevant CAN messages for the Volkswagen PQ35/PQ46/NMS platforms -#define MSG_LENKHILFE_3 0x0D0 // RX from EPS, for steering angle and driver steering torque -#define MSG_HCA_1 0x0D2 // TX by OP, Heading Control Assist steering torque -#define MSG_MOTOR_2 0x288 // RX from ECU, for CC state and brake switch state -#define MSG_MOTOR_3 0x380 // RX from ECU, for driver throttle input -#define MSG_GRA_NEU 0x38A // TX by OP, ACC control buttons for cancel/resume -#define MSG_BREMSE_1 0x1A0 // RX from ABS, for ego speed -#define MSG_LDW_1 0x5BE // TX by OP, Lane line recognition and text alerts - -// Transmit of GRA_Neu is allowed on bus 0 and 2 to keep compatibility with gateway and camera integration -const CanMsg VOLKSWAGEN_PQ_TX_MSGS[] = {{MSG_HCA_1, 0, 5}, {MSG_GRA_NEU, 0, 4}, {MSG_GRA_NEU, 2, 4}, {MSG_LDW_1, 0, 8}}; -#define VOLKSWAGEN_PQ_TX_MSGS_LEN (sizeof(VOLKSWAGEN_PQ_TX_MSGS) / sizeof(VOLKSWAGEN_PQ_TX_MSGS[0])) - -AddrCheckStruct volkswagen_pq_addr_checks[] = { - {.msg = {{MSG_LENKHILFE_3, 0, 6, .check_checksum = true, .max_counter = 15U, .expected_timestep = 10000U}, { 0 }, { 0 }}}, - {.msg = {{MSG_MOTOR_2, 0, 8, .check_checksum = false, .max_counter = 0U, .expected_timestep = 20000U}, { 0 }, { 0 }}}, - {.msg = {{MSG_MOTOR_3, 0, 8, .check_checksum = false, .max_counter = 0U, .expected_timestep = 10000U}, { 0 }, { 0 }}}, - {.msg = {{MSG_BREMSE_1, 0, 8, .check_checksum = false, .max_counter = 0U, .expected_timestep = 10000U}, { 0 }, { 0 }}}, -}; -#define VOLKSWAGEN_PQ_ADDR_CHECKS_LEN (sizeof(volkswagen_pq_addr_checks) / sizeof(volkswagen_pq_addr_checks[0])) -addr_checks volkswagen_pq_rx_checks = {volkswagen_pq_addr_checks, VOLKSWAGEN_PQ_ADDR_CHECKS_LEN}; - -int volkswagen_torque_msg = 0; -int volkswagen_lane_msg = 0; -uint8_t volkswagen_crc8_lut_8h2f[256]; // Static lookup table for CRC8 poly 0x2F, aka 8H2F/AUTOSAR - - -static uint8_t volkswagen_get_checksum(CANPacket_t *to_push) { - return (uint8_t)GET_BYTE(to_push, 0); -} - -static uint8_t volkswagen_mqb_get_counter(CANPacket_t *to_push) { - // MQB message counters are consistently found at LSB 8. - return (uint8_t)GET_BYTE(to_push, 1) & 0xFU; -} - -static uint8_t volkswagen_pq_get_counter(CANPacket_t *to_push) { - // Few PQ messages have counters, and their offsets are inconsistent. This - // function works only for Lenkhilfe_3 at this time. - return (uint8_t)(GET_BYTE(to_push, 1) & 0xF0U) >> 4; -} - -static uint8_t volkswagen_mqb_compute_crc(CANPacket_t *to_push) { - int addr = GET_ADDR(to_push); - int len = GET_LEN(to_push); - - // This is CRC-8H2F/AUTOSAR with a twist. See the OpenDBC implementation - // of this algorithm for a version with explanatory comments. - - uint8_t crc = 0xFFU; - for (int i = 1; i < len; i++) { - crc ^= (uint8_t)GET_BYTE(to_push, i); - crc = volkswagen_crc8_lut_8h2f[crc]; - } - - uint8_t counter = volkswagen_mqb_get_counter(to_push); - switch(addr) { - case MSG_LH_EPS_03: - crc ^= (uint8_t[]){0xF5,0xF5,0xF5,0xF5,0xF5,0xF5,0xF5,0xF5,0xF5,0xF5,0xF5,0xF5,0xF5,0xF5,0xF5,0xF5}[counter]; - break; - case MSG_ESP_05: - crc ^= (uint8_t[]){0x07,0x07,0x07,0x07,0x07,0x07,0x07,0x07,0x07,0x07,0x07,0x07,0x07,0x07,0x07,0x07}[counter]; - break; - case MSG_TSK_06: - crc ^= (uint8_t[]){0xC4,0xE2,0x4F,0xE4,0xF8,0x2F,0x56,0x81,0x9F,0xE5,0x83,0x44,0x05,0x3F,0x97,0xDF}[counter]; - break; - case MSG_MOTOR_20: - crc ^= (uint8_t[]){0xE9,0x65,0xAE,0x6B,0x7B,0x35,0xE5,0x5F,0x4E,0xC7,0x86,0xA2,0xBB,0xDD,0xEB,0xB4}[counter]; - break; - default: // Undefined CAN message, CRC check expected to fail - break; - } - crc = volkswagen_crc8_lut_8h2f[crc]; - - return crc ^ 0xFFU; -} - -static uint8_t volkswagen_pq_compute_checksum(CANPacket_t *to_push) { - int len = GET_LEN(to_push); - uint8_t checksum = 0U; - - for (int i = 1; i < len; i++) { - checksum ^= (uint8_t)GET_BYTE(to_push, i); - } - - return checksum; -} - -static const addr_checks* volkswagen_mqb_init(int16_t param) { - UNUSED(param); - - controls_allowed = false; - relay_malfunction_reset(); - volkswagen_torque_msg = MSG_HCA_01; - volkswagen_lane_msg = MSG_LDW_02; - gen_crc_lookup_table(0x2F, volkswagen_crc8_lut_8h2f); - return &volkswagen_mqb_rx_checks; -} - -static const addr_checks* volkswagen_pq_init(int16_t param) { - UNUSED(param); - - controls_allowed = false; - relay_malfunction_reset(); - volkswagen_torque_msg = MSG_HCA_1; - volkswagen_lane_msg = MSG_LDW_1; - return &volkswagen_pq_rx_checks; -} - -static int volkswagen_mqb_rx_hook(CANPacket_t *to_push) { - - bool valid = addr_safety_check(to_push, &volkswagen_mqb_rx_checks, - volkswagen_get_checksum, volkswagen_mqb_compute_crc, volkswagen_mqb_get_counter); - - if (valid && (GET_BUS(to_push) == 0U)) { - int addr = GET_ADDR(to_push); - - // Update in-motion state by sampling front wheel speeds - // Signal: ESP_19.ESP_VL_Radgeschw_02 (front left) in scaled km/h - // Signal: ESP_19.ESP_VR_Radgeschw_02 (front right) in scaled km/h - if (addr == MSG_ESP_19) { - int wheel_speed_fl = GET_BYTE(to_push, 4) | (GET_BYTE(to_push, 5) << 8); - int wheel_speed_fr = GET_BYTE(to_push, 6) | (GET_BYTE(to_push, 7) << 8); - // Check for average front speed in excess of 0.3m/s, 1.08km/h - // DBC speed scale 0.0075: 0.3m/s = 144, sum both wheels to compare - vehicle_moving = (wheel_speed_fl + wheel_speed_fr) > 288; - } - - // Update driver input torque samples - // Signal: LH_EPS_03.EPS_Lenkmoment (absolute torque) - // Signal: LH_EPS_03.EPS_VZ_Lenkmoment (direction) - if (addr == MSG_LH_EPS_03) { - int torque_driver_new = GET_BYTE(to_push, 5) | ((GET_BYTE(to_push, 6) & 0x1FU) << 8); - int sign = (GET_BYTE(to_push, 6) & 0x80U) >> 7; - if (sign == 1) { - torque_driver_new *= -1; - } - update_sample(&torque_driver, torque_driver_new); - } - - // Enter controls on rising edge of stock ACC, exit controls if stock ACC disengages - // Signal: TSK_06.TSK_Status - if (addr == MSG_TSK_06) { - int acc_status = (GET_BYTE(to_push, 3) & 0x7U); - int cruise_engaged = ((acc_status == 3) || (acc_status == 4) || (acc_status == 5)) ? 1 : 0; - if (cruise_engaged && !cruise_engaged_prev) { - controls_allowed = 1; - } - if (!cruise_engaged) { - controls_allowed = 0; - } - cruise_engaged_prev = cruise_engaged; - } - - // Signal: Motor_20.MO_Fahrpedalrohwert_01 - if (addr == MSG_MOTOR_20) { - gas_pressed = ((GET_BYTES_04(to_push) >> 12) & 0xFFU) != 0U; - } - - // Signal: ESP_05.ESP_Fahrer_bremst - if (addr == MSG_ESP_05) { - brake_pressed = (GET_BYTE(to_push, 3) & 0x4U) >> 2; - } - - generic_rx_checks((addr == MSG_HCA_01)); - } - return valid; -} - -static int volkswagen_pq_rx_hook(CANPacket_t *to_push) { - - bool valid = addr_safety_check(to_push, &volkswagen_pq_rx_checks, - volkswagen_get_checksum, volkswagen_pq_compute_checksum, volkswagen_pq_get_counter); - - if (valid && (GET_BUS(to_push) == 0U)) { - int addr = GET_ADDR(to_push); - - // Update in-motion state from speed value. - // Signal: Bremse_1.Geschwindigkeit_neu__Bremse_1_ - if (addr == MSG_BREMSE_1) { - int speed = ((GET_BYTE(to_push, 2) & 0xFEU) >> 1) | (GET_BYTE(to_push, 3) << 7); - // DBC speed scale 0.01: 0.3m/s = 108. - vehicle_moving = speed > 108; - } - - // Update driver input torque samples - // Signal: Lenkhilfe_3.LH3_LM (absolute torque) - // Signal: Lenkhilfe_3.LH3_LMSign (direction) - if (addr == MSG_LENKHILFE_3) { - int torque_driver_new = GET_BYTE(to_push, 2) | ((GET_BYTE(to_push, 3) & 0x3U) << 8); - int sign = (GET_BYTE(to_push, 3) & 0x4U) >> 2; - if (sign == 1) { - torque_driver_new *= -1; - } - update_sample(&torque_driver, torque_driver_new); - } - - // Enter controls on rising edge of stock ACC, exit controls if stock ACC disengages - // Signal: Motor_2.GRA_Status - if (addr == MSG_MOTOR_2) { - int acc_status = (GET_BYTE(to_push, 2) & 0xC0U) >> 6; - int cruise_engaged = ((acc_status == 1) || (acc_status == 2)) ? 1 : 0; - if (cruise_engaged && !cruise_engaged_prev) { - controls_allowed = 1; - } - if (!cruise_engaged) { - controls_allowed = 0; - } - cruise_engaged_prev = cruise_engaged; - } - - // Signal: Motor_3.Fahrpedal_Rohsignal - if (addr == MSG_MOTOR_3) { - gas_pressed = (GET_BYTE(to_push, 2)); - } - - // Signal: Motor_2.Bremslichtschalter - if (addr == MSG_MOTOR_2) { - brake_pressed = (GET_BYTE(to_push, 2) & 0x1U); - } - - generic_rx_checks((addr == MSG_HCA_1)); - } - return valid; -} - -static bool volkswagen_steering_check(int desired_torque) { - bool violation = false; - uint32_t ts = microsecond_timer_get(); - - if (controls_allowed) { - // *** global torque limit check *** - violation |= max_limit_check(desired_torque, VOLKSWAGEN_MAX_STEER, -VOLKSWAGEN_MAX_STEER); - - // *** torque rate limit check *** - violation |= driver_limit_check(desired_torque, desired_torque_last, &torque_driver, - VOLKSWAGEN_MAX_STEER, VOLKSWAGEN_MAX_RATE_UP, VOLKSWAGEN_MAX_RATE_DOWN, - VOLKSWAGEN_DRIVER_TORQUE_ALLOWANCE, VOLKSWAGEN_DRIVER_TORQUE_FACTOR); - desired_torque_last = desired_torque; - - // *** torque real time rate limit check *** - violation |= rt_rate_limit_check(desired_torque, rt_torque_last, VOLKSWAGEN_MAX_RT_DELTA); - - // every RT_INTERVAL set the new limits - uint32_t ts_elapsed = get_ts_elapsed(ts, ts_last); - if (ts_elapsed > VOLKSWAGEN_RT_INTERVAL) { - rt_torque_last = desired_torque; - ts_last = ts; - } - } - - // no torque if controls is not allowed - if (!controls_allowed && (desired_torque != 0)) { - violation = true; - } - - // reset to 0 if either controls is not allowed or there's a violation - if (violation || !controls_allowed) { - desired_torque_last = 0; - rt_torque_last = 0; - ts_last = ts; - } - - return violation; -} - -static int volkswagen_mqb_tx_hook(CANPacket_t *to_send) { - int addr = GET_ADDR(to_send); - int tx = 1; - - if (!msg_allowed(to_send, VOLKSWAGEN_MQB_TX_MSGS, VOLKSWAGEN_MQB_TX_MSGS_LEN)) { - tx = 0; - } - - // Safety check for HCA_01 Heading Control Assist torque - // Signal: HCA_01.Assist_Torque (absolute torque) - // Signal: HCA_01.Assist_VZ (direction) - if (addr == MSG_HCA_01) { - int desired_torque = GET_BYTE(to_send, 2) | ((GET_BYTE(to_send, 3) & 0x3FU) << 8); - int sign = (GET_BYTE(to_send, 3) & 0x80U) >> 7; - if (sign == 1) { - desired_torque *= -1; - } - - if (volkswagen_steering_check(desired_torque)) { - tx = 0; - } - } - - // FORCE CANCEL: ensuring that only the cancel button press is sent when controls are off. - // This avoids unintended engagements while still allowing resume spam - if ((addr == MSG_GRA_ACC_01) && !controls_allowed) { - // disallow resume and set: bits 16 and 19 - if ((GET_BYTE(to_send, 2) & 0x9U) != 0U) { - tx = 0; - } - } - - // 1 allows the message through - return tx; -} - -static int volkswagen_pq_tx_hook(CANPacket_t *to_send) { - int addr = GET_ADDR(to_send); - int tx = 1; - - if (!msg_allowed(to_send, VOLKSWAGEN_PQ_TX_MSGS, VOLKSWAGEN_PQ_TX_MSGS_LEN)) { - tx = 0; - } - - // Safety check for HCA_1 Heading Control Assist torque - // Signal: HCA_1.LM_Offset (absolute torque) - // Signal: HCA_1.LM_Offsign (direction) - if (addr == MSG_HCA_1) { - int desired_torque = GET_BYTE(to_send, 2) | ((GET_BYTE(to_send, 3) & 0x7FU) << 8); - desired_torque = desired_torque / 32; // DBC scale from PQ network to centi-Nm - int sign = (GET_BYTE(to_send, 3) & 0x80U) >> 7; - if (sign == 1) { - desired_torque *= -1; - } - - if (volkswagen_steering_check(desired_torque)) { - tx = 0; - } - } - - // FORCE CANCEL: ensuring that only the cancel button press is sent when controls are off. - // This avoids unintended engagements while still allowing resume spam - if ((addr == MSG_GRA_NEU) && !controls_allowed) { - // disallow resume and set: bits 16 and 17 - if ((GET_BYTE(to_send, 2) & 0x3U) != 0U) { - tx = 0; - } - } - - // 1 allows the message through - return tx; -} - -static int volkswagen_fwd_hook(int bus_num, CANPacket_t *to_fwd) { - int addr = GET_ADDR(to_fwd); - int bus_fwd = -1; - - switch (bus_num) { - case 0: - // Forward all traffic from the Extended CAN onward - bus_fwd = 2; - break; - case 2: - if ((addr == volkswagen_torque_msg) || (addr == volkswagen_lane_msg)) { - // OP takes control of the Heading Control Assist and Lane Departure Warning messages from the camera - bus_fwd = -1; - } else { - // Forward all remaining traffic from Extended CAN devices to J533 gateway - bus_fwd = 0; - } - break; - default: - // No other buses should be in use; fallback to do-not-forward - bus_fwd = -1; - break; - } - - return bus_fwd; -} - -// Volkswagen MQB platform -const safety_hooks volkswagen_mqb_hooks = { - .init = volkswagen_mqb_init, - .rx = volkswagen_mqb_rx_hook, - .tx = volkswagen_mqb_tx_hook, - .tx_lin = nooutput_tx_lin_hook, - .fwd = volkswagen_fwd_hook, -}; - -// Volkswagen PQ35/PQ46/NMS platforms -const safety_hooks volkswagen_pq_hooks = { - .init = volkswagen_pq_init, - .rx = volkswagen_pq_rx_hook, - .tx = volkswagen_pq_tx_hook, - .tx_lin = nooutput_tx_lin_hook, - .fwd = volkswagen_fwd_hook, -}; diff --git a/panda/board/safety/safety_volkswagen_mqb.h b/panda/board/safety/safety_volkswagen_mqb.h new file mode 100644 index 000000000..2da2a3b62 --- /dev/null +++ b/panda/board/safety/safety_volkswagen_mqb.h @@ -0,0 +1,253 @@ +const int VOLKSWAGEN_MQB_MAX_STEER = 300; // 3.0 Nm (EPS side max of 3.0Nm with fault if violated) +const int VOLKSWAGEN_MQB_MAX_RT_DELTA = 75; // 4 max rate up * 50Hz send rate * 250000 RT interval / 1000000 = 50 ; 50 * 1.5 for safety pad = 75 +const uint32_t VOLKSWAGEN_MQB_RT_INTERVAL = 250000; // 250ms between real time checks +const int VOLKSWAGEN_MQB_MAX_RATE_UP = 4; // 2.0 Nm/s RoC limit (EPS rack has own soft-limit of 5.0 Nm/s) +const int VOLKSWAGEN_MQB_MAX_RATE_DOWN = 10; // 5.0 Nm/s RoC limit (EPS rack has own soft-limit of 5.0 Nm/s) +const int VOLKSWAGEN_MQB_DRIVER_TORQUE_ALLOWANCE = 80; +const int VOLKSWAGEN_MQB_DRIVER_TORQUE_FACTOR = 3; + +#define MSG_ESP_19 0x0B2 // RX from ABS, for wheel speeds +#define MSG_LH_EPS_03 0x09F // RX from EPS, for driver steering torque +#define MSG_ESP_05 0x106 // RX from ABS, for brake switch state +#define MSG_TSK_06 0x120 // RX from ECU, for ACC status from drivetrain coordinator +#define MSG_MOTOR_20 0x121 // RX from ECU, for driver throttle input +#define MSG_HCA_01 0x126 // TX by OP, Heading Control Assist steering torque +#define MSG_GRA_ACC_01 0x12B // TX by OP, ACC control buttons for cancel/resume +#define MSG_LDW_02 0x397 // TX by OP, Lane line recognition and text alerts + +// Transmit of GRA_ACC_01 is allowed on bus 0 and 2 to keep compatibility with gateway and camera integration +const CanMsg VOLKSWAGEN_MQB_TX_MSGS[] = {{MSG_HCA_01, 0, 8}, {MSG_GRA_ACC_01, 0, 8}, {MSG_GRA_ACC_01, 2, 8}, {MSG_LDW_02, 0, 8}}; +#define VOLKSWAGEN_MQB_TX_MSGS_LEN (sizeof(VOLKSWAGEN_MQB_TX_MSGS) / sizeof(VOLKSWAGEN_MQB_TX_MSGS[0])) + +AddrCheckStruct volkswagen_mqb_addr_checks[] = { + {.msg = {{MSG_ESP_19, 0, 8, .check_checksum = false, .max_counter = 0U, .expected_timestep = 10000U}, { 0 }, { 0 }}}, + {.msg = {{MSG_LH_EPS_03, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 10000U}, { 0 }, { 0 }}}, + {.msg = {{MSG_ESP_05, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}, { 0 }, { 0 }}}, + {.msg = {{MSG_TSK_06, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}, { 0 }, { 0 }}}, + {.msg = {{MSG_MOTOR_20, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}, { 0 }, { 0 }}}, +}; +#define VOLKSWAGEN_MQB_ADDR_CHECKS_LEN (sizeof(volkswagen_mqb_addr_checks) / sizeof(volkswagen_mqb_addr_checks[0])) +addr_checks volkswagen_mqb_rx_checks = {volkswagen_mqb_addr_checks, VOLKSWAGEN_MQB_ADDR_CHECKS_LEN}; + +uint8_t volkswagen_crc8_lut_8h2f[256]; // Static lookup table for CRC8 poly 0x2F, aka 8H2F/AUTOSAR + + +static uint8_t volkswagen_mqb_get_checksum(CANPacket_t *to_push) { + return (uint8_t)GET_BYTE(to_push, 0); +} + +static uint8_t volkswagen_mqb_get_counter(CANPacket_t *to_push) { + // MQB message counters are consistently found at LSB 8. + return (uint8_t)GET_BYTE(to_push, 1) & 0xFU; +} + +static uint8_t volkswagen_mqb_compute_crc(CANPacket_t *to_push) { + int addr = GET_ADDR(to_push); + int len = GET_LEN(to_push); + + // This is CRC-8H2F/AUTOSAR with a twist. See the OpenDBC implementation + // of this algorithm for a version with explanatory comments. + + uint8_t crc = 0xFFU; + for (int i = 1; i < len; i++) { + crc ^= (uint8_t)GET_BYTE(to_push, i); + crc = volkswagen_crc8_lut_8h2f[crc]; + } + + uint8_t counter = volkswagen_mqb_get_counter(to_push); + switch(addr) { + case MSG_LH_EPS_03: + crc ^= (uint8_t[]){0xF5,0xF5,0xF5,0xF5,0xF5,0xF5,0xF5,0xF5,0xF5,0xF5,0xF5,0xF5,0xF5,0xF5,0xF5,0xF5}[counter]; + break; + case MSG_ESP_05: + crc ^= (uint8_t[]){0x07,0x07,0x07,0x07,0x07,0x07,0x07,0x07,0x07,0x07,0x07,0x07,0x07,0x07,0x07,0x07}[counter]; + break; + case MSG_TSK_06: + crc ^= (uint8_t[]){0xC4,0xE2,0x4F,0xE4,0xF8,0x2F,0x56,0x81,0x9F,0xE5,0x83,0x44,0x05,0x3F,0x97,0xDF}[counter]; + break; + case MSG_MOTOR_20: + crc ^= (uint8_t[]){0xE9,0x65,0xAE,0x6B,0x7B,0x35,0xE5,0x5F,0x4E,0xC7,0x86,0xA2,0xBB,0xDD,0xEB,0xB4}[counter]; + break; + default: // Undefined CAN message, CRC check expected to fail + break; + } + crc = volkswagen_crc8_lut_8h2f[crc]; + + return crc ^ 0xFFU; +} + +static const addr_checks* volkswagen_mqb_init(int16_t param) { + UNUSED(param); + + controls_allowed = false; + relay_malfunction_reset(); + gen_crc_lookup_table(0x2F, volkswagen_crc8_lut_8h2f); + return &volkswagen_mqb_rx_checks; +} + +static int volkswagen_mqb_rx_hook(CANPacket_t *to_push) { + + bool valid = addr_safety_check(to_push, &volkswagen_mqb_rx_checks, + volkswagen_mqb_get_checksum, volkswagen_mqb_compute_crc, volkswagen_mqb_get_counter); + + if (valid && (GET_BUS(to_push) == 0U)) { + int addr = GET_ADDR(to_push); + + // Update in-motion state by sampling front wheel speeds + // Signal: ESP_19.ESP_VL_Radgeschw_02 (front left) in scaled km/h + // Signal: ESP_19.ESP_VR_Radgeschw_02 (front right) in scaled km/h + if (addr == MSG_ESP_19) { + int wheel_speed_fl = GET_BYTE(to_push, 4) | (GET_BYTE(to_push, 5) << 8); + int wheel_speed_fr = GET_BYTE(to_push, 6) | (GET_BYTE(to_push, 7) << 8); + // Check for average front speed in excess of 0.3m/s, 1.08km/h + // DBC speed scale 0.0075: 0.3m/s = 144, sum both wheels to compare + vehicle_moving = (wheel_speed_fl + wheel_speed_fr) > 288; + } + + // Update driver input torque samples + // Signal: LH_EPS_03.EPS_Lenkmoment (absolute torque) + // Signal: LH_EPS_03.EPS_VZ_Lenkmoment (direction) + if (addr == MSG_LH_EPS_03) { + int torque_driver_new = GET_BYTE(to_push, 5) | ((GET_BYTE(to_push, 6) & 0x1FU) << 8); + int sign = (GET_BYTE(to_push, 6) & 0x80U) >> 7; + if (sign == 1) { + torque_driver_new *= -1; + } + update_sample(&torque_driver, torque_driver_new); + } + + // Enter controls on rising edge of stock ACC, exit controls if stock ACC disengages + // Signal: TSK_06.TSK_Status + if (addr == MSG_TSK_06) { + int acc_status = (GET_BYTE(to_push, 3) & 0x7U); + int cruise_engaged = ((acc_status == 3) || (acc_status == 4) || (acc_status == 5)) ? 1 : 0; + if (cruise_engaged && !cruise_engaged_prev) { + controls_allowed = 1; + } + if (!cruise_engaged) { + controls_allowed = 0; + } + cruise_engaged_prev = cruise_engaged; + } + + // Signal: Motor_20.MO_Fahrpedalrohwert_01 + if (addr == MSG_MOTOR_20) { + gas_pressed = ((GET_BYTES_04(to_push) >> 12) & 0xFFU) != 0U; + } + + // Signal: ESP_05.ESP_Fahrer_bremst + if (addr == MSG_ESP_05) { + brake_pressed = (GET_BYTE(to_push, 3) & 0x4U) >> 2; + } + + generic_rx_checks((addr == MSG_HCA_01)); + } + return valid; +} + +static int volkswagen_mqb_tx_hook(CANPacket_t *to_send) { + int addr = GET_ADDR(to_send); + int tx = 1; + + if (!msg_allowed(to_send, VOLKSWAGEN_MQB_TX_MSGS, VOLKSWAGEN_MQB_TX_MSGS_LEN)) { + tx = 0; + } + + // Safety check for HCA_01 Heading Control Assist torque + // Signal: HCA_01.Assist_Torque (absolute torque) + // Signal: HCA_01.Assist_VZ (direction) + if (addr == MSG_HCA_01) { + int desired_torque = GET_BYTE(to_send, 2) | ((GET_BYTE(to_send, 3) & 0x3FU) << 8); + int sign = (GET_BYTE(to_send, 3) & 0x80U) >> 7; + if (sign == 1) { + desired_torque *= -1; + } + + bool violation = false; + uint32_t ts = microsecond_timer_get(); + + if (controls_allowed) { + // *** global torque limit check *** + violation |= max_limit_check(desired_torque, VOLKSWAGEN_MQB_MAX_STEER, -VOLKSWAGEN_MQB_MAX_STEER); + + // *** torque rate limit check *** + violation |= driver_limit_check(desired_torque, desired_torque_last, &torque_driver, + VOLKSWAGEN_MQB_MAX_STEER, VOLKSWAGEN_MQB_MAX_RATE_UP, VOLKSWAGEN_MQB_MAX_RATE_DOWN, + VOLKSWAGEN_MQB_DRIVER_TORQUE_ALLOWANCE, VOLKSWAGEN_MQB_DRIVER_TORQUE_FACTOR); + desired_torque_last = desired_torque; + + // *** torque real time rate limit check *** + violation |= rt_rate_limit_check(desired_torque, rt_torque_last, VOLKSWAGEN_MQB_MAX_RT_DELTA); + + // every RT_INTERVAL set the new limits + uint32_t ts_elapsed = get_ts_elapsed(ts, ts_last); + if (ts_elapsed > VOLKSWAGEN_MQB_RT_INTERVAL) { + rt_torque_last = desired_torque; + ts_last = ts; + } + } + + // no torque if controls is not allowed + if (!controls_allowed && (desired_torque != 0)) { + violation = true; + } + + // reset to 0 if either controls is not allowed or there's a violation + if (violation || !controls_allowed) { + desired_torque_last = 0; + rt_torque_last = 0; + ts_last = ts; + } + + if (violation) { + tx = 0; + } + } + + // FORCE CANCEL: ensuring that only the cancel button press is sent when controls are off. + // This avoids unintended engagements while still allowing resume spam + if ((addr == MSG_GRA_ACC_01) && !controls_allowed) { + // disallow resume and set: bits 16 and 19 + if ((GET_BYTE(to_send, 2) & 0x9U) != 0U) { + tx = 0; + } + } + + // 1 allows the message through + return tx; +} + +static int volkswagen_mqb_fwd_hook(int bus_num, CANPacket_t *to_fwd) { + int addr = GET_ADDR(to_fwd); + int bus_fwd = -1; + + switch (bus_num) { + case 0: + // Forward all traffic from the Extended CAN onward + bus_fwd = 2; + break; + case 2: + if ((addr == MSG_HCA_01) || (addr == MSG_LDW_02)) { + // OP takes control of the Heading Control Assist and Lane Departure Warning messages from the camera + bus_fwd = -1; + } else { + // Forward all remaining traffic from Extended CAN devices to J533 gateway + bus_fwd = 0; + } + break; + default: + // No other buses should be in use; fallback to do-not-forward + bus_fwd = -1; + break; + } + + return bus_fwd; +} + +const safety_hooks volkswagen_mqb_hooks = { + .init = volkswagen_mqb_init, + .rx = volkswagen_mqb_rx_hook, + .tx = volkswagen_mqb_tx_hook, + .tx_lin = nooutput_tx_lin_hook, + .fwd = volkswagen_mqb_fwd_hook, +}; diff --git a/panda/board/safety/safety_volkswagen_pq.h b/panda/board/safety/safety_volkswagen_pq.h new file mode 100644 index 000000000..d4fc8202c --- /dev/null +++ b/panda/board/safety/safety_volkswagen_pq.h @@ -0,0 +1,223 @@ +const int VOLKSWAGEN_PQ_MAX_STEER = 300; // 3.0 Nm (EPS side max of 3.0Nm with fault if violated) +const int VOLKSWAGEN_PQ_MAX_RT_DELTA = 75; // 4 max rate up * 50Hz send rate * 250000 RT interval / 1000000 = 50 ; 50 * 1.5 for safety pad = 75 +const uint32_t VOLKSWAGEN_PQ_RT_INTERVAL = 250000; // 250ms between real time checks +const int VOLKSWAGEN_PQ_MAX_RATE_UP = 4; // 2.0 Nm/s RoC limit (EPS rack has own soft-limit of 5.0 Nm/s) +const int VOLKSWAGEN_PQ_MAX_RATE_DOWN = 10; // 5.0 Nm/s RoC limit (EPS rack has own soft-limit of 5.0 Nm/s) +const int VOLKSWAGEN_PQ_DRIVER_TORQUE_ALLOWANCE = 80; +const int VOLKSWAGEN_PQ_DRIVER_TORQUE_FACTOR = 3; + +#define MSG_LENKHILFE_3 0x0D0 // RX from EPS, for steering angle and driver steering torque +#define MSG_HCA_1 0x0D2 // TX by OP, Heading Control Assist steering torque +#define MSG_MOTOR_2 0x288 // RX from ECU, for CC state and brake switch state +#define MSG_MOTOR_3 0x380 // RX from ECU, for driver throttle input +#define MSG_GRA_NEU 0x38A // TX by OP, ACC control buttons for cancel/resume +#define MSG_BREMSE_1 0x1A0 // RX from ABS, for ego speed +#define MSG_LDW_1 0x5BE // TX by OP, Lane line recognition and text alerts + +// Transmit of GRA_Neu is allowed on bus 0 and 2 to keep compatibility with gateway and camera integration +const CanMsg VOLKSWAGEN_PQ_TX_MSGS[] = {{MSG_HCA_1, 0, 5}, {MSG_GRA_NEU, 0, 4}, {MSG_GRA_NEU, 2, 4}, {MSG_LDW_1, 0, 8}}; +#define VOLKSWAGEN_PQ_TX_MSGS_LEN (sizeof(VOLKSWAGEN_PQ_TX_MSGS) / sizeof(VOLKSWAGEN_PQ_TX_MSGS[0])) + +AddrCheckStruct volkswagen_pq_addr_checks[] = { + {.msg = {{MSG_LENKHILFE_3, 0, 6, .check_checksum = true, .max_counter = 15U, .expected_timestep = 10000U}, { 0 }, { 0 }}}, + {.msg = {{MSG_MOTOR_2, 0, 8, .check_checksum = false, .max_counter = 0U, .expected_timestep = 20000U}, { 0 }, { 0 }}}, + {.msg = {{MSG_MOTOR_3, 0, 8, .check_checksum = false, .max_counter = 0U, .expected_timestep = 10000U}, { 0 }, { 0 }}}, + {.msg = {{MSG_BREMSE_1, 0, 8, .check_checksum = false, .max_counter = 0U, .expected_timestep = 10000U}, { 0 }, { 0 }}}, +}; +#define VOLKSWAGEN_PQ_ADDR_CHECKS_LEN (sizeof(volkswagen_pq_addr_checks) / sizeof(volkswagen_pq_addr_checks[0])) +addr_checks volkswagen_pq_rx_checks = {volkswagen_pq_addr_checks, VOLKSWAGEN_PQ_ADDR_CHECKS_LEN}; + + +static uint8_t volkswagen_pq_get_checksum(CANPacket_t *to_push) { + return (uint8_t)GET_BYTE(to_push, 0); +} + +static uint8_t volkswagen_pq_get_counter(CANPacket_t *to_push) { + // Few PQ messages have counters, and their offsets are inconsistent. This + // function works only for Lenkhilfe_3 at this time. + return (uint8_t)(GET_BYTE(to_push, 1) & 0xF0U) >> 4; +} + +static uint8_t volkswagen_pq_compute_checksum(CANPacket_t *to_push) { + int len = GET_LEN(to_push); + uint8_t checksum = 0U; + + for (int i = 1; i < len; i++) { + checksum ^= (uint8_t)GET_BYTE(to_push, i); + } + + return checksum; +} + +static const addr_checks* volkswagen_pq_init(int16_t param) { + UNUSED(param); + + controls_allowed = false; + relay_malfunction_reset(); + return &volkswagen_pq_rx_checks; +} + +static int volkswagen_pq_rx_hook(CANPacket_t *to_push) { + + bool valid = addr_safety_check(to_push, &volkswagen_pq_rx_checks, + volkswagen_pq_get_checksum, volkswagen_pq_compute_checksum, volkswagen_pq_get_counter); + + if (valid && (GET_BUS(to_push) == 0U)) { + int addr = GET_ADDR(to_push); + + // Update in-motion state from speed value. + // Signal: Bremse_1.Geschwindigkeit_neu__Bremse_1_ + if (addr == MSG_BREMSE_1) { + int speed = ((GET_BYTE(to_push, 2) & 0xFEU) >> 1) | (GET_BYTE(to_push, 3) << 7); + // DBC speed scale 0.01: 0.3m/s = 108. + vehicle_moving = speed > 108; + } + + // Update driver input torque samples + // Signal: Lenkhilfe_3.LH3_LM (absolute torque) + // Signal: Lenkhilfe_3.LH3_LMSign (direction) + if (addr == MSG_LENKHILFE_3) { + int torque_driver_new = GET_BYTE(to_push, 2) | ((GET_BYTE(to_push, 3) & 0x3U) << 8); + int sign = (GET_BYTE(to_push, 3) & 0x4U) >> 2; + if (sign == 1) { + torque_driver_new *= -1; + } + update_sample(&torque_driver, torque_driver_new); + } + + // Enter controls on rising edge of stock ACC, exit controls if stock ACC disengages + // Signal: Motor_2.GRA_Status + if (addr == MSG_MOTOR_2) { + int acc_status = (GET_BYTE(to_push, 2) & 0xC0U) >> 6; + int cruise_engaged = ((acc_status == 1) || (acc_status == 2)) ? 1 : 0; + if (cruise_engaged && !cruise_engaged_prev) { + controls_allowed = 1; + } + if (!cruise_engaged) { + controls_allowed = 0; + } + cruise_engaged_prev = cruise_engaged; + } + + // Signal: Motor_3.Fahrpedal_Rohsignal + if (addr == MSG_MOTOR_3) { + gas_pressed = (GET_BYTE(to_push, 2)); + } + + // Signal: Motor_2.Bremslichtschalter + if (addr == MSG_MOTOR_2) { + brake_pressed = (GET_BYTE(to_push, 2) & 0x1U); + } + + generic_rx_checks((addr == MSG_HCA_1)); + } + return valid; +} + +static int volkswagen_pq_tx_hook(CANPacket_t *to_send) { + int addr = GET_ADDR(to_send); + int tx = 1; + + if (!msg_allowed(to_send, VOLKSWAGEN_PQ_TX_MSGS, VOLKSWAGEN_PQ_TX_MSGS_LEN)) { + tx = 0; + } + + // Safety check for HCA_1 Heading Control Assist torque + // Signal: HCA_1.LM_Offset (absolute torque) + // Signal: HCA_1.LM_Offsign (direction) + if (addr == MSG_HCA_1) { + int desired_torque = GET_BYTE(to_send, 2) | ((GET_BYTE(to_send, 3) & 0x7FU) << 8); + desired_torque = desired_torque / 32; // DBC scale from PQ network to centi-Nm + int sign = (GET_BYTE(to_send, 3) & 0x80U) >> 7; + if (sign == 1) { + desired_torque *= -1; + } + + bool violation = false; + uint32_t ts = microsecond_timer_get(); + + if (controls_allowed) { + // *** global torque limit check *** + violation |= max_limit_check(desired_torque, VOLKSWAGEN_PQ_MAX_STEER, -VOLKSWAGEN_PQ_MAX_STEER); + + // *** torque rate limit check *** + violation |= driver_limit_check(desired_torque, desired_torque_last, &torque_driver, + VOLKSWAGEN_PQ_MAX_STEER, VOLKSWAGEN_PQ_MAX_RATE_UP, VOLKSWAGEN_PQ_MAX_RATE_DOWN, + VOLKSWAGEN_PQ_DRIVER_TORQUE_ALLOWANCE, VOLKSWAGEN_PQ_DRIVER_TORQUE_FACTOR); + desired_torque_last = desired_torque; + + // *** torque real time rate limit check *** + violation |= rt_rate_limit_check(desired_torque, rt_torque_last, VOLKSWAGEN_PQ_MAX_RT_DELTA); + + // every RT_INTERVAL set the new limits + uint32_t ts_elapsed = get_ts_elapsed(ts, ts_last); + if (ts_elapsed > VOLKSWAGEN_PQ_RT_INTERVAL) { + rt_torque_last = desired_torque; + ts_last = ts; + } + } + + // no torque if controls is not allowed + if (!controls_allowed && (desired_torque != 0)) { + violation = true; + } + + // reset to 0 if either controls is not allowed or there's a violation + if (violation || !controls_allowed) { + desired_torque_last = 0; + rt_torque_last = 0; + ts_last = ts; + } + + if (violation) { + tx = 0; + } + } + + // FORCE CANCEL: ensuring that only the cancel button press is sent when controls are off. + // This avoids unintended engagements while still allowing resume spam + if ((addr == MSG_GRA_NEU) && !controls_allowed) { + // disallow resume and set: bits 16 and 17 + if ((GET_BYTE(to_send, 2) & 0x3U) != 0U) { + tx = 0; + } + } + + // 1 allows the message through + return tx; +} + +static int volkswagen_pq_fwd_hook(int bus_num, CANPacket_t *to_fwd) { + int addr = GET_ADDR(to_fwd); + int bus_fwd = -1; + + switch (bus_num) { + case 0: + // Forward all traffic from the Extended CAN onward + bus_fwd = 2; + break; + case 2: + if ((addr == MSG_HCA_1) || (addr == MSG_LDW_1)) { + // OP takes control of the Heading Control Assist and Lane Departure Warning messages from the camera + bus_fwd = -1; + } else { + // Forward all remaining traffic from Extended CAN devices to J533 gateway + bus_fwd = 0; + } + break; + default: + // No other buses should be in use; fallback to do-not-forward + bus_fwd = -1; + break; + } + + return bus_fwd; +} + +const safety_hooks volkswagen_pq_hooks = { + .init = volkswagen_pq_init, + .rx = volkswagen_pq_rx_hook, + .tx = volkswagen_pq_tx_hook, + .tx_lin = nooutput_tx_lin_hook, + .fwd = volkswagen_pq_fwd_hook, +}; diff --git a/panda/board/stm32fx/clock_source.h b/panda/board/stm32fx/clock_source.h index 691010bd3..26c1cfa80 100644 --- a/panda/board/stm32fx/clock_source.h +++ b/panda/board/stm32fx/clock_source.h @@ -1,23 +1,12 @@ #define CLOCK_SOURCE_MODE_DISABLED 0U #define CLOCK_SOURCE_MODE_FREE_RUNNING 1U -#define CLOCK_SOURCE_MODE_EXTERNAL_SYNC 2U #define CLOCK_SOURCE_PERIOD_MS 50U #define CLOCK_SOURCE_PULSE_LEN_MS 2U uint8_t clock_source_mode = CLOCK_SOURCE_MODE_DISABLED; -void EXTI0_IRQ_Handler(void) { - volatile unsigned int pr = EXTI->PR & (1U << 0); - if (pr != 0U) { - if(clock_source_mode == CLOCK_SOURCE_MODE_EXTERNAL_SYNC){ - // TODO: Implement! - } - } - EXTI->PR = (1U << 0); -} - void TIM1_UP_TIM10_IRQ_Handler(void) { if((TIM1->SR & TIM_SR_UIF) != 0) { if(clock_source_mode != CLOCK_SOURCE_MODE_DISABLED) { @@ -47,13 +36,6 @@ void TIM1_CC_IRQ_Handler(void) { } void clock_source_init(uint8_t mode){ - // Setup external clock signal interrupt - REGISTER_INTERRUPT(EXTI0_IRQn, EXTI0_IRQ_Handler, 110U, FAULT_INTERRUPT_RATE_CLOCK_SOURCE) - register_set(&(SYSCFG->EXTICR[0]), SYSCFG_EXTICR1_EXTI0_PB, 0xFU); - register_set_bits(&(EXTI->IMR), (1U << 0)); - register_set_bits(&(EXTI->RTSR), (1U << 0)); - register_clear_bits(&(EXTI->FTSR), (1U << 0)); - // Setup timer REGISTER_INTERRUPT(TIM1_UP_TIM10_IRQn, TIM1_UP_TIM10_IRQ_Handler, (1200U / CLOCK_SOURCE_PERIOD_MS) , FAULT_INTERRUPT_RATE_TIM1) REGISTER_INTERRUPT(TIM1_CC_IRQn, TIM1_CC_IRQ_Handler, (1200U / CLOCK_SOURCE_PERIOD_MS) , FAULT_INTERRUPT_RATE_TIM1) @@ -69,7 +51,6 @@ void clock_source_init(uint8_t mode){ switch(mode) { case CLOCK_SOURCE_MODE_DISABLED: // No clock signal - NVIC_DisableIRQ(EXTI0_IRQn); NVIC_DisableIRQ(TIM1_UP_TIM10_IRQn); NVIC_DisableIRQ(TIM1_CC_IRQn); @@ -81,20 +62,11 @@ void clock_source_init(uint8_t mode){ break; case CLOCK_SOURCE_MODE_FREE_RUNNING: // Clock signal is based on internal timer - NVIC_DisableIRQ(EXTI0_IRQn); NVIC_EnableIRQ(TIM1_UP_TIM10_IRQn); NVIC_EnableIRQ(TIM1_CC_IRQn); clock_source_mode = CLOCK_SOURCE_MODE_FREE_RUNNING; break; - case CLOCK_SOURCE_MODE_EXTERNAL_SYNC: - // Clock signal is based on external timer - NVIC_EnableIRQ(EXTI0_IRQn); - NVIC_EnableIRQ(TIM1_UP_TIM10_IRQn); - NVIC_EnableIRQ(TIM1_CC_IRQn); - - clock_source_mode = CLOCK_SOURCE_MODE_EXTERNAL_SYNC; - break; default: puts("Unknown clock source mode: "); puth(mode); puts("\n"); break; diff --git a/panda/board/stm32fx/llrtc.h b/panda/board/stm32fx/llrtc.h index 1dc137369..39a0aef3d 100644 --- a/panda/board/stm32fx/llrtc.h +++ b/panda/board/stm32fx/llrtc.h @@ -1,4 +1,5 @@ -#define RCC_BDCR_MASK (RCC_BDCR_RTCEN | RCC_BDCR_RTCSEL | RCC_BDCR_LSEMOD | RCC_BDCR_LSEBYP | RCC_BDCR_LSEON) +#define RCC_BDCR_MASK_LSE (RCC_BDCR_RTCEN | RCC_BDCR_RTCSEL | RCC_BDCR_LSEMOD | RCC_BDCR_LSEBYP | RCC_BDCR_LSEON) +#define RCC_BDCR_MASK_LSI (RCC_BDCR_RTCEN | RCC_BDCR_RTCSEL) void enable_bdomain_protection(void) { register_clear_bits(&(PWR->CR), PWR_CR_DBP); diff --git a/panda/board/stm32fx/stm32fx_config.h b/panda/board/stm32fx/stm32fx_config.h index 8c5ca1c71..fb1934926 100644 --- a/panda/board/stm32fx/stm32fx_config.h +++ b/panda/board/stm32fx/stm32fx_config.h @@ -38,8 +38,6 @@ #define PROVISION_CHUNK_ADDRESS 0x1FFF79E0U #define DEVICE_SERIAL_NUMBER_ADDRESS 0x1FFF79C0U -#define CANPACKET_DATA_SIZE_MAX 8U - #include "can_definitions.h" #ifndef BOOTSTUB @@ -66,7 +64,7 @@ #include "stm32fx/board.h" #include "stm32fx/clock.h" -#if !defined (BOOTSTUB) && (defined(PANDA) || defined(PEDAL_USB)) +#if !defined(BOOTSTUB) && (defined(PANDA) || defined(PEDAL_USB)) #include "drivers/uart.h" #include "stm32fx/lluart.h" #endif diff --git a/panda/board/stm32h7/llrtc.h b/panda/board/stm32h7/llrtc.h index 8689f8952..54ef3017e 100644 --- a/panda/board/stm32h7/llrtc.h +++ b/panda/board/stm32h7/llrtc.h @@ -1,4 +1,5 @@ -#define RCC_BDCR_MASK (RCC_BDCR_RTCEN | RCC_BDCR_RTCSEL | RCC_BDCR_LSEDRV | RCC_BDCR_LSEBYP | RCC_BDCR_LSEON) +#define RCC_BDCR_MASK_LSE (RCC_BDCR_RTCEN | RCC_BDCR_RTCSEL | RCC_BDCR_LSEDRV | RCC_BDCR_LSEBYP | RCC_BDCR_LSEON) +#define RCC_BDCR_MASK_LSI (RCC_BDCR_RTCEN | RCC_BDCR_RTCSEL) void enable_bdomain_protection(void) { register_clear_bits(&(PWR->CR1), PWR_CR1_DBP); diff --git a/panda/board/stm32h7/peripherals.h b/panda/board/stm32h7/peripherals.h index b50516f79..e43c59396 100644 --- a/panda/board/stm32h7/peripherals.h +++ b/panda/board/stm32h7/peripherals.h @@ -112,6 +112,8 @@ void peripherals_init(void) { RCC->APB1HENR |= RCC_APB1HENR_FDCANEN; // FDCAN core enable RCC->AHB1ENR |= RCC_AHB1ENR_ADC12EN; // Enable ADC clocks + RCC->APB4ENR |= RCC_APB4ENR_SYSCFGEN; + // HS USB enable, also LP is needed for CSleep state(__WFI()) RCC->AHB1ENR |= RCC_AHB1ENR_USB1OTGHSEN; RCC->AHB1LPENR |= RCC_AHB1LPENR_USB1OTGHSLPEN; diff --git a/panda/board/stm32h7/stm32h7_config.h b/panda/board/stm32h7/stm32h7_config.h index cdc2a9dcc..61e96e3c7 100644 --- a/panda/board/stm32h7/stm32h7_config.h +++ b/panda/board/stm32h7/stm32h7_config.h @@ -34,8 +34,6 @@ #define PROVISION_CHUNK_ADDRESS 0x080FFFE0U #define DEVICE_SERIAL_NUMBER_ADDRESS 0x080FFFC0U -#define CANPACKET_DATA_SIZE_MAX 64U - #include "can_definitions.h" #ifndef BOOTSTUB @@ -58,7 +56,7 @@ #include "stm32h7/board.h" #include "stm32h7/clock.h" -#if !defined (BOOTSTUB) && defined(PANDA) +#if !defined(BOOTSTUB) && defined(PANDA) #include "drivers/uart.h" #include "stm32h7/lluart.h" #endif diff --git a/panda/board/usb_comms.h b/panda/board/usb_comms.h new file mode 100644 index 000000000..c1bd2d544 --- /dev/null +++ b/panda/board/usb_comms.h @@ -0,0 +1,466 @@ +#include "usb_protocol.h" +#include "health.h" + +extern int _app_start[0xc000]; // Only first 3 sectors of size 0x4000 are used + +// Prototypes +void set_safety_mode(uint16_t mode, int16_t param); +bool is_car_safety_mode(uint16_t mode); + +int get_health_pkt(void *dat) { + COMPILE_TIME_ASSERT(sizeof(struct health_t) <= USBPACKET_MAX_SIZE); + struct health_t * health = (struct health_t*)dat; + + health->uptime_pkt = uptime_cnt; + health->voltage_pkt = adc_get_voltage(); + health->current_pkt = current_board->read_current(); + + //Use the GPIO pin to determine ignition or use a CAN based logic + health->ignition_line_pkt = (uint8_t)(current_board->check_ignition()); + health->ignition_can_pkt = (uint8_t)(ignition_can); + + health->controls_allowed_pkt = controls_allowed; + health->gas_interceptor_detected_pkt = gas_interceptor_detected; + health->can_rx_errs_pkt = can_rx_errs; + health->can_send_errs_pkt = can_send_errs; + health->can_fwd_errs_pkt = can_fwd_errs; + health->gmlan_send_errs_pkt = gmlan_send_errs; + health->car_harness_status_pkt = car_harness_status; + health->usb_power_mode_pkt = usb_power_mode; + health->safety_mode_pkt = (uint8_t)(current_safety_mode); + health->safety_param_pkt = current_safety_param; + health->unsafe_mode_pkt = unsafe_mode; + health->power_save_enabled_pkt = (uint8_t)(power_save_status == POWER_SAVE_STATUS_ENABLED); + health->heartbeat_lost_pkt = (uint8_t)(heartbeat_lost); + health->blocked_msg_cnt_pkt = blocked_msg_cnt; + + health->fault_status_pkt = fault_status; + health->faults_pkt = faults; + + return sizeof(*health); +} + +int get_rtc_pkt(void *dat) { + timestamp_t t = rtc_get_time(); + (void)memcpy(dat, &t, sizeof(t)); + return sizeof(t); +} + + + +// send on serial, first byte to select the ring +void usb_cb_ep2_out(void *usbdata, int len) { + uint8_t *usbdata8 = (uint8_t *)usbdata; + uart_ring *ur = get_ring_by_number(usbdata8[0]); + if ((len != 0) && (ur != NULL)) { + if ((usbdata8[0] < 2U) || safety_tx_lin_hook(usbdata8[0] - 2U, &usbdata8[1], len - 1)) { + for (int i = 1; i < len; i++) { + while (!putc(ur, usbdata8[i])) { + // wait + } + } + } + } +} + +void usb_cb_ep3_out_complete(void) { + if (can_tx_check_min_slots_free(MAX_CAN_MSGS_PER_BULK_TRANSFER)) { + usb_outep3_resume_if_paused(); + } +} + +void usb_cb_enumeration_complete(void) { + puts("USB enumeration complete\n"); + is_enumerated = 1; +} + +int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp) { + unsigned int resp_len = 0; + uart_ring *ur = NULL; + timestamp_t t; + switch (setup->b.bRequest) { + // **** 0xa0: get rtc time + case 0xa0: + resp_len = get_rtc_pkt(resp); + break; + // **** 0xa1: set rtc year + case 0xa1: + t = rtc_get_time(); + t.year = setup->b.wValue.w; + rtc_set_time(t); + break; + // **** 0xa2: set rtc month + case 0xa2: + t = rtc_get_time(); + t.month = setup->b.wValue.w; + rtc_set_time(t); + break; + // **** 0xa3: set rtc day + case 0xa3: + t = rtc_get_time(); + t.day = setup->b.wValue.w; + rtc_set_time(t); + break; + // **** 0xa4: set rtc weekday + case 0xa4: + t = rtc_get_time(); + t.weekday = setup->b.wValue.w; + rtc_set_time(t); + break; + // **** 0xa5: set rtc hour + case 0xa5: + t = rtc_get_time(); + t.hour = setup->b.wValue.w; + rtc_set_time(t); + break; + // **** 0xa6: set rtc minute + case 0xa6: + t = rtc_get_time(); + t.minute = setup->b.wValue.w; + rtc_set_time(t); + break; + // **** 0xa7: set rtc second + case 0xa7: + t = rtc_get_time(); + t.second = setup->b.wValue.w; + rtc_set_time(t); + break; + // **** 0xb0: set IR power + case 0xb0: + current_board->set_ir_power(setup->b.wValue.w); + break; + // **** 0xb1: set fan power + case 0xb1: + current_board->set_fan_power(setup->b.wValue.w); + break; + // **** 0xb2: get fan rpm + case 0xb2: + resp[0] = (fan_rpm & 0x00FFU); + resp[1] = ((fan_rpm & 0xFF00U) >> 8U); + resp_len = 2; + break; + // **** 0xb3: set phone power + case 0xb3: + current_board->set_phone_power(setup->b.wValue.w > 0U); + break; + // **** 0xc0: get CAN debug info + case 0xc0: + puts("can tx: "); puth(can_tx_cnt); + puts(" txd: "); puth(can_txd_cnt); + puts(" rx: "); puth(can_rx_cnt); + puts(" err: "); puth(can_err_cnt); + puts("\n"); + break; + // **** 0xc1: get hardware type + case 0xc1: + resp[0] = hw_type; + resp_len = 1; + break; + // **** 0xd0: fetch serial number + case 0xd0: + // addresses are OTP + if (setup->b.wValue.w == 1U) { + (void)memcpy(resp, (uint8_t *)DEVICE_SERIAL_NUMBER_ADDRESS, 0x10); + resp_len = 0x10; + } else { + get_provision_chunk(resp); + resp_len = PROVISION_CHUNK_LEN; + } + break; + // **** 0xd1: enter bootloader mode + case 0xd1: + // this allows reflashing of the bootstub + switch (setup->b.wValue.w) { + case 0: + // only allow bootloader entry on debug builds + #ifdef ALLOW_DEBUG + puts("-> entering bootloader\n"); + enter_bootloader_mode = ENTER_BOOTLOADER_MAGIC; + NVIC_SystemReset(); + #endif + break; + case 1: + puts("-> entering softloader\n"); + enter_bootloader_mode = ENTER_SOFTLOADER_MAGIC; + NVIC_SystemReset(); + break; + default: + puts("Bootloader mode invalid\n"); + break; + } + break; + // **** 0xd2: get health packet + case 0xd2: + resp_len = get_health_pkt(resp); + break; + // **** 0xd3: get first 64 bytes of signature + case 0xd3: + { + resp_len = 64; + char * code = (char*)_app_start; + int code_len = _app_start[0]; + (void)memcpy(resp, &code[code_len], resp_len); + } + break; + // **** 0xd4: get second 64 bytes of signature + case 0xd4: + { + resp_len = 64; + char * code = (char*)_app_start; + int code_len = _app_start[0]; + (void)memcpy(resp, &code[code_len + 64], resp_len); + } + break; + // **** 0xd6: get version + case 0xd6: + COMPILE_TIME_ASSERT(sizeof(gitversion) <= USBPACKET_MAX_SIZE); + (void)memcpy(resp, gitversion, sizeof(gitversion)); + resp_len = sizeof(gitversion) - 1U; + break; + // **** 0xd8: reset ST + case 0xd8: + NVIC_SystemReset(); + break; + // **** 0xd9: set ESP power + case 0xd9: + if (setup->b.wValue.w == 1U) { + current_board->set_gps_mode(GPS_ENABLED); + } else if (setup->b.wValue.w == 2U) { + current_board->set_gps_mode(GPS_BOOTMODE); + } else { + current_board->set_gps_mode(GPS_DISABLED); + } + break; + // **** 0xda: reset ESP, with optional boot mode + case 0xda: + current_board->set_gps_mode(GPS_DISABLED); + delay(1000000); + if (setup->b.wValue.w == 1U) { + current_board->set_gps_mode(GPS_BOOTMODE); + } else { + current_board->set_gps_mode(GPS_ENABLED); + } + delay(1000000); + current_board->set_gps_mode(GPS_ENABLED); + break; + // **** 0xdb: set GMLAN (white/grey) or OBD CAN (black) multiplexing mode + case 0xdb: + if(current_board->has_obd){ + if (setup->b.wValue.w == 1U) { + // Enable OBD CAN + current_board->set_can_mode(CAN_MODE_OBD_CAN2); + } else { + // Disable OBD CAN + current_board->set_can_mode(CAN_MODE_NORMAL); + } + } else { + if (setup->b.wValue.w == 1U) { + // GMLAN ON + if (setup->b.wIndex.w == 1U) { + can_set_gmlan(1); + } else if (setup->b.wIndex.w == 2U) { + can_set_gmlan(2); + } else { + puts("Invalid bus num for GMLAN CAN set\n"); + } + } else { + can_set_gmlan(-1); + } + } + break; + + // **** 0xdc: set safety mode + case 0xdc: + set_safety_mode(setup->b.wValue.w, (uint16_t) setup->b.wIndex.w); + break; + // **** 0xdd: get healthpacket and CANPacket versions + case 0xdd: + resp[0] = HEALTH_PACKET_VERSION; + resp[1] = CAN_PACKET_VERSION; + resp_len = 2; + break; + // **** 0xde: set can bitrate + case 0xde: + if (setup->b.wValue.w < BUS_CNT) { + // TODO: add sanity check, ideally check if value is correct(from array of correct values) + bus_config[setup->b.wValue.w].can_speed = setup->b.wIndex.w; + bool ret = can_init(CAN_NUM_FROM_BUS_NUM(setup->b.wValue.w)); + UNUSED(ret); + } + break; + // **** 0xdf: set unsafe mode + case 0xdf: + // you can only set this if you are in a non car safety mode + if (!is_car_safety_mode(current_safety_mode)) { + unsafe_mode = setup->b.wValue.w; + } + break; + // **** 0xe0: uart read + case 0xe0: + ur = get_ring_by_number(setup->b.wValue.w); + if (!ur) { + break; + } + + // TODO: Remove this again and fix boardd code to hande the message bursts instead of single chars + if (ur == &uart_ring_gps) { + dma_pointer_handler(ur, DMA2_Stream5->NDTR); + } + + // read + while ((resp_len < MIN(setup->b.wLength.w, USBPACKET_MAX_SIZE)) && + getc(ur, (char*)&resp[resp_len])) { + ++resp_len; + } + break; + // **** 0xe1: uart set baud rate + case 0xe1: + ur = get_ring_by_number(setup->b.wValue.w); + if (!ur) { + break; + } + uart_set_baud(ur->uart, setup->b.wIndex.w); + break; + // **** 0xe2: uart set parity + case 0xe2: + ur = get_ring_by_number(setup->b.wValue.w); + if (!ur) { + break; + } + switch (setup->b.wIndex.w) { + case 0: + // disable parity, 8-bit + ur->uart->CR1 &= ~(USART_CR1_PCE | USART_CR1_M); + break; + case 1: + // even parity, 9-bit + ur->uart->CR1 &= ~USART_CR1_PS; + ur->uart->CR1 |= USART_CR1_PCE | USART_CR1_M; + break; + case 2: + // odd parity, 9-bit + ur->uart->CR1 |= USART_CR1_PS; + ur->uart->CR1 |= USART_CR1_PCE | USART_CR1_M; + break; + default: + break; + } + break; + // **** 0xe4: uart set baud rate extended + case 0xe4: + ur = get_ring_by_number(setup->b.wValue.w); + if (!ur) { + break; + } + uart_set_baud(ur->uart, (int)setup->b.wIndex.w*300); + break; + // **** 0xe5: set CAN loopback (for testing) + case 0xe5: + can_loopback = (setup->b.wValue.w > 0U); + can_init_all(); + break; + // **** 0xe6: set USB power + case 0xe6: + current_board->set_usb_power_mode(setup->b.wValue.w); + break; + // **** 0xe7: set power save state + case 0xe7: + set_power_save_state(setup->b.wValue.w); + break; + // **** 0xf0: k-line/l-line wake-up pulse for KWP2000 fast initialization + case 0xf0: + if(current_board->has_lin) { + bool k = (setup->b.wValue.w == 0U) || (setup->b.wValue.w == 2U); + bool l = (setup->b.wValue.w == 1U) || (setup->b.wValue.w == 2U); + if (bitbang_wakeup(k, l)) { + resp_len = -1; // do not clear NAK yet (wait for bit banging to finish) + } + } + break; + // **** 0xf1: Clear CAN ring buffer. + case 0xf1: + if (setup->b.wValue.w == 0xFFFFU) { + puts("Clearing CAN Rx queue\n"); + can_clear(&can_rx_q); + } else if (setup->b.wValue.w < BUS_CNT) { + puts("Clearing CAN Tx queue\n"); + can_clear(can_queues[setup->b.wValue.w]); + } else { + puts("Clearing CAN CAN ring buffer failed: wrong bus number\n"); + } + break; + // **** 0xf2: Clear UART ring buffer. + case 0xf2: + { + uart_ring * rb = get_ring_by_number(setup->b.wValue.w); + if (rb != NULL) { + puts("Clearing UART queue.\n"); + clear_uart_buff(rb); + } + break; + } + // **** 0xf3: Heartbeat. Resets heartbeat counter. + case 0xf3: + { + heartbeat_counter = 0U; + heartbeat_lost = false; + heartbeat_disabled = false; + heartbeat_engaged = (setup->b.wValue.w == 1U); + break; + } + // **** 0xf4: k-line/l-line 5 baud initialization + case 0xf4: + if(current_board->has_lin) { + bool k = (setup->b.wValue.w == 0U) || (setup->b.wValue.w == 2U); + bool l = (setup->b.wValue.w == 1U) || (setup->b.wValue.w == 2U); + uint8_t five_baud_addr = (setup->b.wIndex.w & 0xFFU); + if (bitbang_five_baud_addr(k, l, five_baud_addr)) { + resp_len = -1; // do not clear NAK yet (wait for bit banging to finish) + } + } + break; + // **** 0xf5: set clock source mode + case 0xf5: + current_board->set_clock_source_mode(setup->b.wValue.w); + break; + // **** 0xf6: set siren enabled + case 0xf6: + siren_enabled = (setup->b.wValue.w != 0U); + break; + // **** 0xf7: set green led enabled + case 0xf7: + green_led_enabled = (setup->b.wValue.w != 0U); + break; +#ifdef ALLOW_DEBUG + // **** 0xf8: disable heartbeat checks + case 0xf8: + heartbeat_disabled = true; + break; +#endif + // **** 0xde: set CAN FD data bitrate + case 0xf9: + if (setup->b.wValue.w < CAN_CNT) { + // TODO: add sanity check, ideally check if value is correct(from array of correct values) + bus_config[setup->b.wValue.w].can_data_speed = setup->b.wIndex.w; + bus_config[setup->b.wValue.w].canfd_enabled = (setup->b.wIndex.w >= bus_config[setup->b.wValue.w].can_speed) ? true : false; + bus_config[setup->b.wValue.w].brs_enabled = (setup->b.wIndex.w > bus_config[setup->b.wValue.w].can_speed) ? true : false; + bool ret = can_init(CAN_NUM_FROM_BUS_NUM(setup->b.wValue.w)); + UNUSED(ret); + } + break; + // **** 0xfa: check if CAN FD and BRS are enabled + case 0xfa: + if (setup->b.wValue.w < CAN_CNT) { + resp[0] = bus_config[setup->b.wValue.w].canfd_enabled; + resp[1] = bus_config[setup->b.wValue.w].brs_enabled; + resp_len = 2; + } + break; + default: + puts("NO HANDLER "); + puth(setup->b.bRequest); + puts("\n"); + break; + } + return resp_len; +} diff --git a/panda/board/usb_protocol.h b/panda/board/usb_protocol.h index a20b6c1b4..932d1ddd4 100644 --- a/panda/board/usb_protocol.h +++ b/panda/board/usb_protocol.h @@ -8,8 +8,7 @@ typedef struct { usb_asm_buffer ep1_buffer = {.ptr = 0, .tail_size = 0, .counter = 0}; int total_rx_size = 0; -int usb_cb_ep1_in(void *usbdata, int len, bool hardwired) { - UNUSED(hardwired); +int usb_cb_ep1_in(void *usbdata, int len) { int pos = 1; uint8_t *usbdata8 = (uint8_t *)usbdata; usbdata8[0] = ep1_buffer.counter; @@ -60,8 +59,7 @@ int usb_cb_ep1_in(void *usbdata, int len, bool hardwired) { usb_asm_buffer ep3_buffer = {.ptr = 0, .tail_size = 0, .counter = 0}; // send on CAN -void usb_cb_ep3_out(void *usbdata, int len, bool hardwired) { - UNUSED(hardwired); +void usb_cb_ep3_out(void *usbdata, int len) { uint8_t *usbdata8 = (uint8_t *)usbdata; // Got first packet from a stream, resetting buffer and counter if (usbdata8[0] == 0U) { diff --git a/panda/python/__init__.py b/panda/python/__init__.py index 87c811fea..7ebb26d90 100644 --- a/panda/python/__init__.py +++ b/panda/python/__init__.py @@ -2,7 +2,6 @@ import datetime import struct import hashlib -import socket import usb1 import os import time @@ -115,64 +114,6 @@ def ensure_can_packet_version(fn): return fn(self, *args, **kwargs) return wrapper -class PandaWifiStreaming(object): - def __init__(self, ip="192.168.0.10", port=1338): - self.sock = socket.socket(socket.AF_INET, socket.SOCK_DGRAM) - self.sock.setblocking(0) - self.ip = ip - self.port = port - self.kick() - - def kick(self): - # must be called at least every 5 seconds - self.sock.sendto("hello", (self.ip, self.port)) - - def can_recv(self): - ret = [] - while True: - try: - dat, addr = self.sock.recvfrom(0x200 * 0x10) - if addr == (self.ip, self.port): - ret += unpack_can_buffer(dat) - except socket.error as e: - if e.errno != 35 and e.errno != 11: - traceback.print_exc() - break - return ret - -# stupid tunneling of USB over wifi and SPI -class WifiHandle(object): - def __init__(self, ip="192.168.0.10", port=1337): - self.sock = socket.create_connection((ip, port)) - - def __recv(self): - ret = self.sock.recv(0x44) - length = struct.unpack("I", ret[0:4])[0] - return ret[4:4 + length] - - def controlWrite(self, request_type, request, value, index, data, timeout=0): - # ignore data in reply, panda doesn't use it - return self.controlRead(request_type, request, value, index, 0, timeout) - - def controlRead(self, request_type, request, value, index, length, timeout=0): - self.sock.send(struct.pack("HHBBHHH", 0, 0, request_type, request, value, index, length)) - return self.__recv() - - def bulkWrite(self, endpoint, data, timeout=0): - if len(data) > 0x10: - raise ValueError("Data must not be longer than 0x10") - self.sock.send(struct.pack("HH", endpoint, len(data)) + data) - self.__recv() # to /dev/null - - def bulkRead(self, endpoint, length, timeout=0): - self.sock.send(struct.pack("HH", endpoint, 0)) - return self.__recv() - - def close(self): - self.sock.close() - -# *** normal mode *** - class Panda(object): # matches cereal.car.CarParams.SafetyModel @@ -219,7 +160,8 @@ class Panda(object): HW_TYPE_RED_PANDA = b'\x07' CAN_PACKET_VERSION = 2 - HEALTH_PACKET_VERSION = 1 + HEALTH_PACKET_VERSION = 3 + HEALTH_STRUCT = struct.Struct(" &string_value[0]) - raise Exception('AcadosOcpSolver.options_set() does not support field {}.'\ - '\n Possible values are {}.'.format(field_, ', '.join(int_fields + double_fields + string_fields))) + else: + raise Exception('AcadosOcpSolver.options_set() does not support field {}.'\ + '\n Possible values are {}.'.format(field_, ', '.join(int_fields + double_fields + string_fields))) def __del__(self): diff --git a/release/files_common b/release/files_common index 3fc354396..67e4c0e31 100644 --- a/release/files_common +++ b/release/files_common @@ -70,13 +70,14 @@ selfdrive/version.py selfdrive/__init__.py selfdrive/config.py -selfdrive/crash.py +selfdrive/sentry.py selfdrive/swaglog.py selfdrive/logmessaged.py selfdrive/tombstoned.py selfdrive/pandad.py selfdrive/updated.py selfdrive/rtshield.py +selfdrive/statsd.py selfdrive/athena/__init__.py selfdrive/athena/athenad.py @@ -87,6 +88,8 @@ selfdrive/boardd/.gitignore selfdrive/boardd/SConscript selfdrive/boardd/__init__.py selfdrive/boardd/boardd.cc +selfdrive/boardd/boardd.h +selfdrive/boardd/main.cc selfdrive/boardd/boardd.py selfdrive/boardd/boardd_api_impl.pyx selfdrive/boardd/can_list_to_can_capnp.cc @@ -197,6 +200,8 @@ selfdrive/common/version.h selfdrive/common/swaglog.h selfdrive/common/swaglog.cc +selfdrive/common/statlog.h +selfdrive/common/statlog.cc selfdrive/common/util.cc selfdrive/common/util.h selfdrive/common/queue.h @@ -227,17 +232,19 @@ selfdrive/controls/radard.py selfdrive/controls/lib/__init__.py selfdrive/controls/lib/alertmanager.py selfdrive/controls/lib/alerts_offroad.json -selfdrive/controls/lib/events.py +selfdrive/controls/lib/desire_helper.py selfdrive/controls/lib/drive_helpers.py -selfdrive/controls/lib/latcontrol_pid.py +selfdrive/controls/lib/events.py +selfdrive/controls/lib/lane_planner.py +selfdrive/controls/lib/latcontrol_angle.py selfdrive/controls/lib/latcontrol_indi.py selfdrive/controls/lib/latcontrol_lqr.py -selfdrive/controls/lib/latcontrol_angle.py -selfdrive/controls/lib/longcontrol.py +selfdrive/controls/lib/latcontrol_pid.py +selfdrive/controls/lib/latcontrol.py selfdrive/controls/lib/lateral_planner.py -selfdrive/controls/lib/lane_planner.py -selfdrive/controls/lib/pid.py +selfdrive/controls/lib/longcontrol.py selfdrive/controls/lib/longitudinal_planner.py +selfdrive/controls/lib/pid.py selfdrive/controls/lib/radar_helpers.py selfdrive/controls/lib/vehicle_model.py @@ -254,6 +261,7 @@ selfdrive/hardware/base.py selfdrive/hardware/hw.h selfdrive/hardware/eon/__init__.py selfdrive/hardware/eon/androidd.py +selfdrive/hardware/eon/shutdownd.py selfdrive/hardware/eon/hardware.h selfdrive/hardware/eon/hardware.py selfdrive/hardware/eon/neos.py @@ -548,7 +556,7 @@ opendbc/can/dbc_out/.gitignore opendbc/chrysler_pacifica_2017_hybrid.dbc opendbc/chrysler_pacifica_2017_hybrid_private_fusion.dbc -opendbc/gm_global_a_powertrain.dbc +opendbc/gm_global_a_powertrain_generated.dbc opendbc/gm_global_a_object.dbc opendbc/gm_global_a_chassis.dbc @@ -561,17 +569,13 @@ opendbc/acura_rdx_2018_can_generated.dbc opendbc/acura_rdx_2020_can_generated.dbc opendbc/honda_civic_touring_2016_can_generated.dbc opendbc/honda_civic_hatchback_ex_2017_can_generated.dbc -opendbc/honda_civic_sedan_16_diesel_2019_can_generated.dbc opendbc/honda_crv_touring_2016_can_generated.dbc opendbc/honda_crv_ex_2017_can_generated.dbc opendbc/honda_crv_ex_2017_body_generated.dbc opendbc/honda_crv_executive_2016_can_generated.dbc -opendbc/honda_crv_hybrid_2019_can_generated.dbc opendbc/honda_fit_ex_2018_can_generated.dbc opendbc/honda_odyssey_exl_2018_generated.dbc opendbc/honda_odyssey_extreme_edition_2018_china_can_generated.dbc -opendbc/honda_pilot_touring_2017_can_generated.dbc -opendbc/honda_ridgeline_black_edition_2017_can_generated.dbc opendbc/honda_insight_ex_2019_can_generated.dbc opendbc/acura_ilx_2016_nidec.dbc @@ -588,23 +592,9 @@ opendbc/subaru_outback_2015_generated.dbc opendbc/subaru_outback_2019_generated.dbc opendbc/subaru_forester_2017_generated.dbc -opendbc/toyota_rav4_hybrid_2017_pt_generated.dbc -opendbc/toyota_rav4_2017_pt_generated.dbc -opendbc/toyota_prius_2017_pt_generated.dbc -opendbc/toyota_corolla_2017_pt_generated.dbc -opendbc/lexus_rx_350_2016_pt_generated.dbc -opendbc/lexus_rx_hybrid_2017_pt_generated.dbc +opendbc/toyota_tnga_k_pt_generated.dbc +opendbc/toyota_new_mc_pt_generated.dbc opendbc/toyota_nodsu_pt_generated.dbc -opendbc/toyota_nodsu_hybrid_pt_generated.dbc -opendbc/toyota_camry_hybrid_2018_pt_generated.dbc -opendbc/toyota_highlander_2017_pt_generated.dbc -opendbc/toyota_highlander_hybrid_2018_pt_generated.dbc -opendbc/toyota_avalon_2017_pt_generated.dbc -opendbc/toyota_sienna_xle_2018_pt_generated.dbc -opendbc/lexus_is_2018_pt_generated.dbc -opendbc/lexus_ct200h_2018_pt_generated.dbc -opendbc/lexus_nx300h_2018_pt_generated.dbc -opendbc/lexus_nx300_2018_pt_generated.dbc opendbc/toyota_adas.dbc opendbc/toyota_tss2_adas.dbc diff --git a/selfdrive/athena/athenad.py b/selfdrive/athena/athenad.py index d19692661..cc7cdd87a 100755 --- a/selfdrive/athena/athenad.py +++ b/selfdrive/athena/athenad.py @@ -4,37 +4,43 @@ import hashlib import io import json import os -import sys import queue import random import select import socket +import subprocess +import sys +import tempfile import threading import time from collections import namedtuple +from datetime import datetime from functools import partial -from typing import Any +from typing import Any, Dict import requests from jsonrpc import JSONRPCResponseManager, dispatcher -from websocket import ABNF, WebSocketTimeoutException, WebSocketException, create_connection +from websocket import (ABNF, WebSocketException, WebSocketTimeoutException, + create_connection) import cereal.messaging as messaging +from cereal import log from cereal.services import service_list from common.api import Api -from common.file_helpers import CallbackReader from common.basedir import PERSIST +from common.file_helpers import CallbackReader from common.params import Params from common.realtime import sec_since_boot -from selfdrive.hardware import HARDWARE, PC +from selfdrive.hardware import HARDWARE, PC, TICI from selfdrive.loggerd.config import ROOT from selfdrive.loggerd.xattr_cache import getxattr, setxattr -from selfdrive.swaglog import cloudlog, SWAGLOG_DIR -from selfdrive.version import get_version, get_origin, get_short_branch, get_commit +from selfdrive.statsd import STATS_DIR +from selfdrive.swaglog import SWAGLOG_DIR, cloudlog +from selfdrive.version import get_commit, get_origin, get_short_branch, get_version ATHENA_HOST = os.getenv('ATHENA_HOST', 'wss://athena.comma.ai') HANDLER_THREADS = int(os.getenv('HANDLER_THREADS', "4")) -LOCAL_PORT_WHITELIST = set([8022]) +LOCAL_PORT_WHITELIST = {8022} LOG_ATTR_NAME = 'user.upload' LOG_ATTR_VALUE_MAX_UNIX_TIME = int.to_bytes(2147483647, 4, sys.byteorder) @@ -42,18 +48,46 @@ RECONNECT_TIMEOUT_S = 70 RETRY_DELAY = 10 # seconds MAX_RETRY_COUNT = 30 # Try for at most 5 minutes if upload fails immediately +MAX_AGE = 31 * 24 * 3600 # seconds WS_FRAME_SIZE = 4096 +NetworkType = log.DeviceState.NetworkType + dispatcher["echo"] = lambda s: s recv_queue: Any = queue.Queue() send_queue: Any = queue.Queue() upload_queue: Any = queue.Queue() -log_send_queue: Any = queue.Queue() +low_priority_send_queue: Any = queue.Queue() log_recv_queue: Any = queue.Queue() cancelled_uploads: Any = set() -UploadItem = namedtuple('UploadItem', ['path', 'url', 'headers', 'created_at', 'id', 'retry_count', 'current', 'progress'], defaults=(0, False, 0)) +UploadItem = namedtuple('UploadItem', ['path', 'url', 'headers', 'created_at', 'id', 'retry_count', 'current', 'progress', 'allow_cellular'], defaults=(0, False, 0, False)) -cur_upload_items = {} +cur_upload_items: Dict[int, Any] = {} + +class AbortTransferException(Exception): + pass + + +class UploadQueueCache(): + params = Params() + + @staticmethod + def initialize(upload_queue): + try: + upload_queue_json = UploadQueueCache.params.get("AthenadUploadQueue") + if upload_queue_json is not None: + for item in json.loads(upload_queue_json): + upload_queue.put(UploadItem(**item)) + except Exception: + cloudlog.exception("athena.UploadQueueCache.initialize.exception") + + @staticmethod + def cache(upload_queue): + try: + items = [i._asdict() for i in upload_queue.queue if i.id not in cancelled_uploads] + UploadQueueCache.params.put("AthenadUploadQueue", json.dumps(items)) + except Exception: + cloudlog.exception("athena.UploadQueueCache.cache.exception") def handle_long_poll(ws): @@ -64,6 +98,7 @@ def handle_long_poll(ws): threading.Thread(target=ws_send, args=(ws, end_event), name='ws_send'), threading.Thread(target=upload_handler, args=(end_event,), name='upload_handler'), threading.Thread(target=log_handler, args=(end_event,), name='log_handler'), + threading.Thread(target=stat_handler, args=(end_event,), name='stat_handler'), ] + [ threading.Thread(target=jsonrpc_handler, args=(end_event,), name=f'worker_{x}') for x in range(HANDLER_THREADS) @@ -103,7 +138,29 @@ def jsonrpc_handler(end_event): send_queue.put_nowait(json.dumps({"error": str(e)})) -def upload_handler(end_event): +def retry_upload(tid: int, end_event: threading.Event, increase_count: bool = True) -> None: + if cur_upload_items[tid].retry_count < MAX_RETRY_COUNT: + item = cur_upload_items[tid] + new_retry_count = item.retry_count + 1 if increase_count else item.retry_count + + item = item._replace( + retry_count=new_retry_count, + progress=0, + current=False + ) + upload_queue.put_nowait(item) + UploadQueueCache.cache(upload_queue) + + cur_upload_items[tid] = None + + for _ in range(RETRY_DELAY): + time.sleep(1) + if end_event.is_set(): + break + + +def upload_handler(end_event: threading.Event) -> None: + sm = messaging.SubMaster(['deviceState']) tid = threading.get_ident() while not end_event.is_set(): @@ -111,32 +168,58 @@ def upload_handler(end_event): try: cur_upload_items[tid] = upload_queue.get(timeout=1)._replace(current=True) + if cur_upload_items[tid].id in cancelled_uploads: cancelled_uploads.remove(cur_upload_items[tid].id) continue + # Remove item if too old + age = datetime.now() - datetime.fromtimestamp(cur_upload_items[tid].created_at / 1000) + if age.total_seconds() > MAX_AGE: + cloudlog.event("athena.upload_handler.expired", item=cur_upload_items[tid], error=True) + continue + + # Check if uploading over cell is allowed + sm.update(0) + cell = sm['deviceState'].networkType not in [NetworkType.wifi, NetworkType.ethernet] + if cell and (not cur_upload_items[tid].allow_cellular): + retry_upload(tid, end_event, False) + continue + try: def cb(sz, cur): + # Abort transfer if connection changed to cell after starting upload + sm.update(0) + cell = sm['deviceState'].networkType not in [NetworkType.wifi, NetworkType.ethernet] + if cell and (not cur_upload_items[tid].allow_cellular): + raise AbortTransferException + cur_upload_items[tid] = cur_upload_items[tid]._replace(progress=cur / sz if sz else 1) - _do_upload(cur_upload_items[tid], cb) - except (requests.exceptions.Timeout, requests.exceptions.ConnectionError, requests.exceptions.SSLError) as e: - cloudlog.warning(f"athena.upload_handler.retry {e} {cur_upload_items[tid]}") - if cur_upload_items[tid].retry_count < MAX_RETRY_COUNT: - item = cur_upload_items[tid] - item = item._replace( - retry_count=item.retry_count + 1, - progress=0, - current=False - ) - upload_queue.put_nowait(item) - cur_upload_items[tid] = None + network_type = sm['deviceState'].networkType.raw + fn = cur_upload_items[tid].path + try: + sz = os.path.getsize(fn) + except OSError: + sz = -1 - for _ in range(RETRY_DELAY): - time.sleep(1) - if end_event.is_set(): - break + cloudlog.event("athena.upload_handler.upload_start", fn=fn, sz=sz, network_type=network_type) + response = _do_upload(cur_upload_items[tid], cb) + + if response.status_code not in (200, 201, 403, 412): + cloudlog.event("athena.upload_handler.retry", status_code=response.status_code, fn=fn, sz=sz, network_type=network_type) + retry_upload(tid, end_event) + else: + cloudlog.event("athena.upload_handler.success", fn=fn, sz=sz, network_type=network_type) + + UploadQueueCache.cache(upload_queue) + except (requests.exceptions.Timeout, requests.exceptions.ConnectionError, requests.exceptions.SSLError): + cloudlog.event("athena.upload_handler.timeout", fn=fn, sz=sz, network_type=network_type) + retry_upload(tid, end_event) + except AbortTransferException: + cloudlog.event("athena.upload_handler.abort", fn=fn, sz=sz, network_type=network_type) + retry_upload(tid, end_event, False) except queue.Empty: pass @@ -237,19 +320,47 @@ def reboot(): @dispatcher.add_method def uploadFileToUrl(fn, url, headers): - if len(fn) == 0 or fn[0] == '/' or '..' in fn: - return 500 - path = os.path.join(ROOT, fn) - if not os.path.exists(path): - return 404 + return uploadFilesToUrls([{ + "fn": fn, + "url": url, + "headers": headers, + }]) - item = UploadItem(path=path, url=url, headers=headers, created_at=int(time.time() * 1000), id=None) - upload_id = hashlib.sha1(str(item).encode()).hexdigest() - item = item._replace(id=upload_id) - upload_queue.put_nowait(item) +@dispatcher.add_method +def uploadFilesToUrls(files_data): + items = [] + failed = [] + for file in files_data: + fn = file.get('fn', '') + if len(fn) == 0 or fn[0] == '/' or '..' in fn or 'url' not in file: + failed.append(fn) + continue + path = os.path.join(ROOT, fn) + if not os.path.exists(path): + failed.append(fn) + continue - return {"enqueued": 1, "item": item._asdict()} + item = UploadItem( + path=path, + url=file['url'], + headers=file.get('headers', {}), + created_at=int(time.time() * 1000), + id=None, + allow_cellular=file.get('allow_cellular', False), + ) + upload_id = hashlib.sha1(str(item).encode()).hexdigest() + item = item._replace(id=upload_id) + upload_queue.put_nowait(item) + items.append(item._asdict()) + + UploadQueueCache.cache(upload_queue) + + resp = {"enqueued": len(items), "items": items} + if failed: + resp["failed"] = failed + + return resp @dispatcher.add_method @@ -260,11 +371,15 @@ def listUploadQueue(): @dispatcher.add_method def cancelUpload(upload_id): - upload_ids = set(item.id for item in list(upload_queue.queue)) - if upload_id not in upload_ids: + if not isinstance(upload_id, list): + upload_id = [upload_id] + + uploading_ids = {item.id for item in list(upload_queue.queue)} + cancelled_ids = uploading_ids.intersection(upload_id) + if len(cancelled_ids) == 0: return 404 - cancelled_uploads.add(upload_id) + cancelled_uploads.update(cancelled_ids) return {"success": 1} @@ -273,6 +388,18 @@ def primeActivated(activated): return {"success": 1} +@dispatcher.add_method +def setBandwithLimit(upload_speed_kbps, download_speed_kbps): + if not TICI: + return {"success": 0, "error": "only supported on comma three"} + + try: + HARDWARE.set_bandwidth_limit(upload_speed_kbps, download_speed_kbps) + return {"success": 1} + except subprocess.CalledProcessError as e: + return {"success": 0, "error": "failed to set limit", "stdout": e.stdout, "stderr": e.stderr} + + def startLocalProxy(global_end_event, remote_ws_uri, local_port): try: if local_port not in LOCAL_PORT_WHITELIST: @@ -280,8 +407,7 @@ def startLocalProxy(global_end_event, remote_ws_uri, local_port): cloudlog.debug("athena.startLocalProxy.starting") - params = Params() - dongle_id = params.get("DongleId").decode('utf8') + dongle_id = Params().get("DongleId").decode('utf8') identity_token = Api(dongle_id).get_token() ws = create_connection(remote_ws_uri, cookie="jwt=" + identity_token, @@ -312,7 +438,7 @@ def getPublicKey(): if not os.path.isfile(PERSIST + '/comma/id_rsa.pub'): return None - with open(PERSIST + '/comma/id_rsa.pub', 'r') as f: + with open(PERSIST + '/comma/id_rsa.pub') as f: return f.read() @@ -338,7 +464,7 @@ def getNetworks(): @dispatcher.add_method def takeSnapshot(): - from selfdrive.camerad.snapshot.snapshot import snapshot, jpeg_write + from selfdrive.camerad.snapshot.snapshot import jpeg_write, snapshot ret = snapshot() if ret is not None: def b64jpeg(x): @@ -393,7 +519,7 @@ def log_handler(end_event): curr_time = int(time.time()) log_path = os.path.join(SWAGLOG_DIR, log_entry) setxattr(log_path, LOG_ATTR_NAME, int.to_bytes(curr_time, 4, sys.byteorder)) - with open(log_path, "r") as f: + with open(log_path) as f: jsonrpc = { "method": "forwardLogs", "params": { @@ -402,7 +528,7 @@ def log_handler(end_event): "jsonrpc": "2.0", "id": log_entry } - log_send_queue.put_nowait(json.dumps(jsonrpc)) + low_priority_send_queue.put_nowait(json.dumps(jsonrpc)) curr_log = log_entry except OSError: pass # file could be deleted by log rotation @@ -433,6 +559,32 @@ def log_handler(end_event): cloudlog.exception("athena.log_handler.exception") +def stat_handler(end_event): + while not end_event.is_set(): + last_scan = 0 + curr_scan = sec_since_boot() + try: + if curr_scan - last_scan > 10: + stat_filenames = list(filter(lambda name: not name.startswith(tempfile.gettempprefix()), os.listdir(STATS_DIR))) + if len(stat_filenames) > 0: + stat_path = os.path.join(STATS_DIR, stat_filenames[0]) + with open(stat_path) as f: + jsonrpc = { + "method": "storeStats", + "params": { + "stats": f.read() + }, + "jsonrpc": "2.0", + "id": stat_filenames[0] + } + low_priority_send_queue.put_nowait(json.dumps(jsonrpc)) + os.remove(stat_path) + last_scan = curr_scan + except Exception: + cloudlog.exception("athena.stat_handler.exception") + time.sleep(0.1) + + def ws_proxy_recv(ws, local_sock, ssock, end_event, global_end_event): while not (end_event.is_set() or global_end_event.is_set()): try: @@ -505,7 +657,7 @@ def ws_send(ws, end_event): try: data = send_queue.get_nowait() except queue.Empty: - data = log_send_queue.get(timeout=1) + data = low_priority_send_queue.get(timeout=1) for i in range(0, len(data), WS_FRAME_SIZE): frame = data[i:i+WS_FRAME_SIZE] last = i + WS_FRAME_SIZE >= len(data) @@ -525,6 +677,7 @@ def backoff(retries): def main(): params = Params() dongle_id = params.get("DongleId", encoding='utf-8') + UploadQueueCache.initialize(upload_queue) ws_uri = ATHENA_HOST + "/ws/v2/" + dongle_id api = Api(dongle_id) diff --git a/selfdrive/athena/manage_athenad.py b/selfdrive/athena/manage_athenad.py index fa95eacd8..58ad58310 100755 --- a/selfdrive/athena/manage_athenad.py +++ b/selfdrive/athena/manage_athenad.py @@ -6,7 +6,7 @@ from multiprocessing import Process from common.params import Params from selfdrive.manager.process import launcher from selfdrive.swaglog import cloudlog -from selfdrive.version import get_version, get_dirty +from selfdrive.version import get_version, is_dirty ATHENA_MGR_PID_PARAM = "AthenadPid" @@ -14,12 +14,12 @@ ATHENA_MGR_PID_PARAM = "AthenadPid" def main(): params = Params() dongle_id = params.get("DongleId").decode('utf-8') - cloudlog.bind_global(dongle_id=dongle_id, version=get_version(), dirty=get_dirty()) + cloudlog.bind_global(dongle_id=dongle_id, version=get_version(), dirty=is_dirty()) try: while 1: cloudlog.info("starting athena daemon") - proc = Process(name='athenad', target=launcher, args=('selfdrive.athena.athenad',)) + proc = Process(name='athenad', target=launcher, args=('selfdrive.athena.athenad', 'athenad')) proc.start() proc.join() cloudlog.event("athenad exited", exitcode=proc.exitcode) diff --git a/selfdrive/athena/registration.py b/selfdrive/athena/registration.py index e06bae506..10f5d46f7 100755 --- a/selfdrive/athena/registration.py +++ b/selfdrive/athena/registration.py @@ -1,4 +1,4 @@ -#/!/usr/bin/env python3 +#!/usr/bin/env python3 import time import json import jwt @@ -10,13 +10,18 @@ from common.params import Params from common.spinner import Spinner from common.basedir import PERSIST from selfdrive.controls.lib.alertmanager import set_offroad_alert -from selfdrive.hardware import HARDWARE +from selfdrive.hardware import HARDWARE, PC from selfdrive.swaglog import cloudlog UNREGISTERED_DONGLE_ID = "UnregisteredDevice" +def is_registered_device() -> bool: + dongle = Params().get("DongleId", encoding='utf-8') + return dongle not in (None, UNREGISTERED_DONGLE_ID) + + def register(show_spinner=False) -> str: params = Params() params.put("SubscriberInfo", HARDWARE.get_subscriber_info()) @@ -86,7 +91,7 @@ def register(show_spinner=False) -> str: if dongle_id: params.put("DongleId", dongle_id) - set_offroad_alert("Offroad_UnofficialHardware", dongle_id == UNREGISTERED_DONGLE_ID) + set_offroad_alert("Offroad_UnofficialHardware", (dongle_id == UNREGISTERED_DONGLE_ID) and not PC) return dongle_id diff --git a/selfdrive/boardd/SConscript b/selfdrive/boardd/SConscript index 07ded56e1..922107509 100644 --- a/selfdrive/boardd/SConscript +++ b/selfdrive/boardd/SConscript @@ -1,7 +1,7 @@ Import('env', 'envCython', 'common', 'cereal', 'messaging') libs = ['usb-1.0', common, cereal, messaging, 'pthread', 'zmq', 'capnp', 'kj'] -env.Program('boardd', ['boardd.cc', 'panda.cc', 'pigeon.cc'], LIBS=libs) +env.Program('boardd', ['main.cc', 'boardd.cc', 'panda.cc', 'pigeon.cc'], LIBS=libs) env.Library('libcan_list_to_can_capnp', ['can_list_to_can_capnp.cc']) envCython.Program('boardd_api_impl.so', 'boardd_api_impl.pyx', LIBS=["can_list_to_can_capnp", 'capnp', 'kj'] + envCython["LIBS"]) diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc index d09738a70..c5310f879 100644 --- a/selfdrive/boardd/boardd.cc +++ b/selfdrive/boardd/boardd.cc @@ -1,3 +1,5 @@ +#include "selfdrive/boardd/boardd.h" + #include #include #include @@ -10,12 +12,12 @@ #include #include #include +#include #include #include #include #include #include -#include #include @@ -26,9 +28,7 @@ #include "selfdrive/common/timing.h" #include "selfdrive/common/util.h" #include "selfdrive/hardware/hw.h" -#include "selfdrive/locationd/ublox_msg.h" -#include "selfdrive/boardd/panda.h" #include "selfdrive/boardd/pigeon.h" // -- Multi-panda conventions -- @@ -161,7 +161,8 @@ bool safety_setter_thread(std::vector pandas) { int safety_param; auto safety_configs = car_params.getSafetyConfigs(); - for (uint32_t i=0; i i) { @@ -173,9 +174,8 @@ bool safety_setter_thread(std::vector pandas) { safety_param = 0; } - LOGW("panda %d: setting safety model: %d with param %d", i, (int)safety_model, safety_param); - - panda->set_unsafe_mode(0); // see safety_declarations.h for allowed values + LOGW("panda %d: setting safety model: %d, param: %d, unsafe mode: %d", i, (int)safety_model, safety_param, unsafe_mode); + panda->set_unsafe_mode(unsafe_mode); panda->set_safety_model(safety_model, safety_param); } @@ -294,7 +294,7 @@ void send_empty_panda_state(PubMaster *pm) { pm->send("pandaStates", msg); } -bool send_panda_states(PubMaster *pm, const std::vector &pandas, bool spoofing_started) { +std::optional send_panda_states(PubMaster *pm, const std::vector &pandas, bool spoofing_started) { bool ignition_local = false; // build msg @@ -304,34 +304,39 @@ bool send_panda_states(PubMaster *pm, const std::vector &pandas, bool s std::vector pandaStates; for (const auto& panda : pandas){ - health_t pandaState = panda->get_state(); - - if (spoofing_started) { - pandaState.ignition_line = 1; + auto health_opt = panda->get_state(); + if (!health_opt) { + return std::nullopt; } - ignition_local |= ((pandaState.ignition_line != 0) || (pandaState.ignition_can != 0)); + health_t health = *health_opt; - pandaStates.push_back(pandaState); + if (spoofing_started) { + health.ignition_line_pkt = 1; + } + + ignition_local |= ((health.ignition_line_pkt != 0) || (health.ignition_can_pkt != 0)); + + pandaStates.push_back(health); } - for (uint32_t i=0; iset_safety_model(cereal::CarParams::SafetyModel::NO_OUTPUT); } #ifndef __x86_64__ bool power_save_desired = !ignition_local && !pigeon_active; - if (pandaState.power_save_enabled != power_save_desired) { + if (health.power_save_enabled_pkt != power_save_desired) { panda->set_power_saving(power_save_desired); } // set safety mode to NO_OUTPUT when car is off. ELM327 is an alternative if we want to leverage athenad/connect - if (!ignition_local && (pandaState.safety_model != (uint8_t)(cereal::CarParams::SafetyModel::NO_OUTPUT))) { + if (!ignition_local && (health.safety_mode_pkt != (uint8_t)(cereal::CarParams::SafetyModel::NO_OUTPUT))) { panda->set_safety_model(cereal::CarParams::SafetyModel::NO_OUTPUT); } #endif @@ -341,25 +346,27 @@ bool send_panda_states(PubMaster *pm, const std::vector &pandas, bool s } auto ps = pss[i]; - ps.setUptime(pandaState.uptime); - ps.setIgnitionLine(pandaState.ignition_line); - ps.setIgnitionCan(pandaState.ignition_can); - ps.setControlsAllowed(pandaState.controls_allowed); - ps.setGasInterceptorDetected(pandaState.gas_interceptor_detected); - ps.setCanRxErrs(pandaState.can_rx_errs); - ps.setCanSendErrs(pandaState.can_send_errs); - ps.setCanFwdErrs(pandaState.can_fwd_errs); - ps.setGmlanSendErrs(pandaState.gmlan_send_errs); + ps.setUptime(health.uptime_pkt); + ps.setBlockedCnt(health.blocked_msg_cnt_pkt); + ps.setIgnitionLine(health.ignition_line_pkt); + ps.setIgnitionCan(health.ignition_can_pkt); + ps.setControlsAllowed(health.controls_allowed_pkt); + ps.setGasInterceptorDetected(health.gas_interceptor_detected_pkt); + ps.setCanRxErrs(health.can_rx_errs_pkt); + ps.setCanSendErrs(health.can_send_errs_pkt); + ps.setCanFwdErrs(health.can_fwd_errs_pkt); + ps.setGmlanSendErrs(health.gmlan_send_errs_pkt); ps.setPandaType(panda->hw_type); - ps.setSafetyModel(cereal::CarParams::SafetyModel(pandaState.safety_model)); - ps.setSafetyParam(pandaState.safety_param); - ps.setFaultStatus(cereal::PandaState::FaultStatus(pandaState.fault_status)); - ps.setPowerSaveEnabled((bool)(pandaState.power_save_enabled)); - ps.setHeartbeatLost((bool)(pandaState.heartbeat_lost)); - ps.setHarnessStatus(cereal::PandaState::HarnessStatus(pandaState.car_harness_status)); + ps.setSafetyModel(cereal::CarParams::SafetyModel(health.safety_mode_pkt)); + ps.setSafetyParam(health.safety_param_pkt); + ps.setFaultStatus(cereal::PandaState::FaultStatus(health.fault_status_pkt)); + ps.setPowerSaveEnabled((bool)(health.power_save_enabled_pkt)); + ps.setHeartbeatLost((bool)(health.heartbeat_lost_pkt)); + ps.setUnsafeMode(health.unsafe_mode_pkt); + ps.setHarnessStatus(cereal::PandaState::HarnessStatus(health.car_harness_status_pkt)); // Convert faults bitset to capnp list - std::bitset fault_bits(pandaState.faults); + std::bitset fault_bits(health.faults_pkt); auto faults = ps.initFaults(fault_bits.count()); size_t j = 0; @@ -377,7 +384,12 @@ bool send_panda_states(PubMaster *pm, const std::vector &pandas, bool s } void send_peripheral_state(PubMaster *pm, Panda *panda) { - health_t pandaState = panda->get_state(); + auto pandaState_opt = panda->get_state(); + if (!pandaState_opt) { + return; + } + + health_t pandaState = *pandaState_opt; // build msg MessageBuilder msg; @@ -396,12 +408,12 @@ void send_peripheral_state(PubMaster *pm, Panda *panda) { LOGW("reading hwmon took %lfms", read_time); } } else { - ps.setVoltage(pandaState.voltage); - ps.setCurrent(pandaState.current); + ps.setVoltage(pandaState.voltage_pkt); + ps.setCurrent(pandaState.current_pkt); } uint16_t fan_speed_rpm = panda->get_fan_speed(); - ps.setUsbPowerMode(cereal::PeripheralState::UsbPowerMode(pandaState.usb_power_mode)); + ps.setUsbPowerMode(cereal::PeripheralState::UsbPowerMode(pandaState.usb_power_mode_pkt)); ps.setFanSpeedRpm(fan_speed_rpm); pm->send("peripheralState", msg); @@ -411,6 +423,8 @@ void panda_state_thread(PubMaster *pm, std::vector pandas, bool spoofin util::set_thread_name("boardd_panda_state"); Params params; + SubMaster sm({"controlsState"}); + Panda *peripheral_panda = pandas[0]; bool ignition_last = false; std::future safety_future; @@ -419,9 +433,17 @@ void panda_state_thread(PubMaster *pm, std::vector pandas, bool spoofin // run at 2hz while (!do_exit && check_all_connected(pandas)) { + uint64_t start_time = nanos_since_boot(); + // send out peripheralState send_peripheral_state(pm, peripheral_panda); - ignition = send_panda_states(pm, pandas, spoofing_started); + auto ignition_opt = send_panda_states(pm, pandas, spoofing_started); + + if (!ignition_opt) { + continue; + } + + ignition = *ignition_opt; // TODO: make this check fast, currently takes 16ms // check if we have new pandas and are offroad @@ -445,10 +467,15 @@ void panda_state_thread(PubMaster *pm, std::vector pandas, bool spoofin ignition_last = ignition; + sm.update(0); + const bool engaged = sm.allAliveAndValid({"controlsState"}) && sm["controlsState"].getControlsState().getEnabled(); + for (const auto &panda : pandas) { - panda->send_heartbeat(); + panda->send_heartbeat(engaged); } - util::sleep_for(500); + + uint64_t dt = nanos_since_boot() - start_time; + util::sleep_for(500 - dt / 1000000ULL); } } @@ -547,38 +574,11 @@ void pigeon_thread(Panda *panda) { std::unique_ptr pigeon(Hardware::TICI() ? Pigeon::connect("/dev/ttyHS0") : Pigeon::connect(panda)); - std::unordered_map last_recv_time; - std::unordered_map cls_max_dt = { - {(char)ublox::CLASS_NAV, int64_t(900000000ULL)}, // 0.9s - {(char)ublox::CLASS_RXM, int64_t(900000000ULL)}, // 0.9s - }; - while (!do_exit && panda->connected) { bool need_reset = false; bool ignition_local = ignition; std::string recv = pigeon->receive(); - // Parse message header - if (ignition_local && recv.length() >= 3) { - if (recv[0] == (char)ublox::PREAMBLE1 && recv[1] == (char)ublox::PREAMBLE2) { - const char msg_cls = recv[2]; - uint64_t t = nanos_since_boot(); - if (t > last_recv_time[msg_cls]) { - last_recv_time[msg_cls] = t; - } - } - } - - // Check based on message frequency - for (const auto& [msg_cls, max_dt] : cls_max_dt) { - int64_t dt = (int64_t)nanos_since_boot() - (int64_t)last_recv_time[msg_cls]; - if (ignition_last && ignition_local && dt > max_dt) { - LOGD("ublox receive timeout, msg class: 0x%02x, dt %llu", msg_cls, dt); - // TODO: turn on reset after verification of logs - // need_reset = true; - } - } - // Check based on null bytes if (ignition_local && recv.length() > 0 && recv[0] == (char)0x00) { need_reset = true; @@ -594,12 +594,6 @@ void pigeon_thread(Panda *panda) { if((ignition_local && !ignition_last) || need_reset) { pigeon_active = true; pigeon->init(); - - // Set receive times to current time - uint64_t t = nanos_since_boot() + 10000000000ULL; // Give ublox 10 seconds to start - for (const auto& [msg_cls, dt] : cls_max_dt) { - last_recv_time[msg_cls] = t; - } } else if (!ignition_local && ignition_last) { // power off on falling edge of ignition LOGD("powering off pigeon\n"); @@ -615,23 +609,12 @@ void pigeon_thread(Panda *panda) { } } -int main(int argc, char *argv[]) { - LOGW("starting boardd"); - - if (!Hardware::PC()) { - int err; - err = util::set_realtime_priority(54); - assert(err == 0); - err = util::set_core_affinity({Hardware::TICI() ? 4 : 3}); - assert(err == 0); - } - - LOGW("attempting to connect"); - PubMaster pm({"pandaStates", "peripheralState"}); - - std::vector serials(argv + 1, argv + argc); +void boardd_main_thread(std::vector serials) { if (serials.size() == 0) serials.push_back(""); + PubMaster pm({"pandaStates", "peripheralState"}); + LOGW("attempting to connect"); + // connect to all provided serials std::vector pandas; for (int i = 0; i < serials.size() && !do_exit; /**/) { @@ -653,6 +636,8 @@ int main(int argc, char *argv[]) { Panda *peripheral_panda = pandas[0]; std::vector threads; + Params().put("LastPeripheralPandaType", std::to_string((int) peripheral_panda->get_hw_type())); + threads.emplace_back(panda_state_thread, &pm, pandas, getenv("STARTED") != nullptr); threads.emplace_back(peripheral_control_thread, peripheral_panda); threads.emplace_back(pigeon_thread, peripheral_panda); diff --git a/selfdrive/boardd/boardd.h b/selfdrive/boardd/boardd.h new file mode 100644 index 000000000..d3c9e1f94 --- /dev/null +++ b/selfdrive/boardd/boardd.h @@ -0,0 +1,6 @@ +#pragma once + +#include "selfdrive/boardd/panda.h" + +bool safety_setter_thread(std::vector pandas); +void boardd_main_thread(std::vector serials); diff --git a/selfdrive/boardd/main.cc b/selfdrive/boardd/main.cc new file mode 100644 index 000000000..d802e42f8 --- /dev/null +++ b/selfdrive/boardd/main.cc @@ -0,0 +1,22 @@ +#include + +#include "selfdrive/boardd/boardd.h" +#include "selfdrive/common/swaglog.h" +#include "selfdrive/common/util.h" +#include "selfdrive/hardware/hw.h" + +int main(int argc, char *argv[]) { + LOGW("starting boardd"); + + if (!Hardware::PC()) { + int err; + err = util::set_realtime_priority(54); + assert(err == 0); + err = util::set_core_affinity({Hardware::TICI() ? 4 : 3}); + assert(err == 0); + } + + std::vector serials(argv + 1, argv + argc); + boardd_main_thread(serials); + return 0; +} diff --git a/selfdrive/boardd/panda.cc b/selfdrive/boardd/panda.cc index 751f735ca..5e621b12c 100644 --- a/selfdrive/boardd/panda.cc +++ b/selfdrive/boardd/panda.cc @@ -45,11 +45,11 @@ Panda::Panda(std::string serial, uint32_t bus_offset) : bus_offset(bus_offset) { libusb_device_descriptor desc; libusb_get_device_descriptor(dev_list[i], &desc); if (desc.idVendor == 0xbbaa && desc.idProduct == 0xddcc) { - libusb_open(dev_list[i], &dev_handle); - if (dev_handle == NULL) { goto fail; } + int ret = libusb_open(dev_list[i], &dev_handle); + if (dev_handle == NULL || ret < 0) { goto fail; } unsigned char desc_serial[26] = { 0 }; - int ret = libusb_get_string_descriptor_ascii(dev_handle, desc.iSerialNumber, desc_serial, std::size(desc_serial)); + ret = libusb_get_string_descriptor_ascii(dev_handle, desc.iSerialNumber, desc_serial, std::size(desc_serial)); if (ret < 0) { goto fail; } usb_serial = std::string((char *)desc_serial, ret).c_str(); @@ -130,12 +130,14 @@ std::vector Panda::list() { libusb_get_device_descriptor(device, &desc); if (desc.idVendor == 0xbbaa && desc.idProduct == 0xddcc) { libusb_device_handle *handle = NULL; - libusb_open(device, &handle); - unsigned char desc_serial[26] = { 0 }; - int ret = libusb_get_string_descriptor_ascii(handle, desc.iSerialNumber, desc_serial, std::size(desc_serial)); - libusb_close(handle); - + int ret = libusb_open(device, &handle); if (ret < 0) { goto finish; } + + unsigned char desc_serial[26] = { 0 }; + ret = libusb_get_string_descriptor_ascii(handle, desc.iSerialNumber, desc_serial, std::size(desc_serial)); + libusb_close(handle); + if (ret < 0) { goto finish; } + serials.push_back(std::string((char *)desc_serial, ret).c_str()); } } @@ -309,10 +311,10 @@ void Panda::set_ir_pwr(uint16_t ir_pwr) { usb_write(0xb0, ir_pwr, 0); } -health_t Panda::get_state() { +std::optional Panda::get_state() { health_t health {0}; - usb_read(0xd2, 0, 0, (unsigned char*)&health, sizeof(health)); - return health; + int err = usb_read(0xd2, 0, 0, (unsigned char*)&health, sizeof(health)); + return err >= 0 ? std::make_optional(health) : std::nullopt; } void Panda::set_loopback(bool loopback) { @@ -340,8 +342,8 @@ void Panda::set_usb_power_mode(cereal::PeripheralState::UsbPowerMode power_mode) usb_write(0xe6, (uint16_t)power_mode, 0); } -void Panda::send_heartbeat() { - usb_write(0xf3, 1, 0); +void Panda::send_heartbeat(bool engaged) { + usb_write(0xf3, engaged, 0); } void Panda::set_can_speed_kbps(uint16_t bus, uint16_t speed) { diff --git a/selfdrive/boardd/panda.h b/selfdrive/boardd/panda.h index fe6918948..dbd866adf 100644 --- a/selfdrive/boardd/panda.h +++ b/selfdrive/boardd/panda.h @@ -13,6 +13,7 @@ #include "cereal/gen/cpp/car.capnp.h" #include "cereal/gen/cpp/log.capnp.h" +#include "panda/board/health.h" #define TIMEOUT 0 #define PANDA_BUS_CNT 4 @@ -24,29 +25,6 @@ #define CANPACKET_REJECTED (0xC0U) #define CANPACKET_RETURNED (0x80U) -// copied from panda/board/main.c -struct __attribute__((packed)) health_t { - uint32_t uptime; - uint32_t voltage; - uint32_t current; - uint32_t can_rx_errs; - uint32_t can_send_errs; - uint32_t can_fwd_errs; - uint32_t gmlan_send_errs; - uint32_t faults; - uint8_t ignition_line; - uint8_t ignition_can; - uint8_t controls_allowed; - uint8_t gas_interceptor_detected; - uint8_t car_harness_status; - uint8_t usb_power_mode; - uint8_t safety_model; - int16_t safety_param; - uint8_t fault_status; - uint8_t power_save_enabled; - uint8_t heartbeat_lost; -}; - struct __attribute__((packed)) can_header { uint8_t reserved : 1; uint8_t bus : 3; @@ -102,13 +80,13 @@ class Panda { void set_fan_speed(uint16_t fan_speed); uint16_t get_fan_speed(); void set_ir_pwr(uint16_t ir_pwr); - health_t get_state(); + std::optional get_state(); void set_loopback(bool loopback); std::optional> get_firmware_version(); std::optional get_serial(); void set_power_saving(bool power_saving); void set_usb_power_mode(cereal::PeripheralState::UsbPowerMode power_mode); - void send_heartbeat(); + void send_heartbeat(bool engaged); void set_can_speed_kbps(uint16_t bus, uint16_t speed); void set_data_speed_kbps(uint16_t bus, uint16_t speed); void can_send(capnp::List::Reader can_data_list); diff --git a/selfdrive/camerad/cameras/camera_common.cc b/selfdrive/camerad/cameras/camera_common.cc index 6dcbf18c4..b313f74e7 100644 --- a/selfdrive/camerad/cameras/camera_common.cc +++ b/selfdrive/camerad/cameras/camera_common.cc @@ -19,6 +19,7 @@ #include "selfdrive/hardware/hw.h" #ifdef QCOM +#include "CL/cl_ext_qcom.h" #include "selfdrive/camerad/cameras/camera_qcom.h" #elif QCOM2 #include "selfdrive/camerad/cameras/camera_qcom2.h" @@ -28,6 +29,8 @@ #include "selfdrive/camerad/cameras/camera_replay.h" #endif +ExitHandler do_exit; + class Debayer { public: Debayer(cl_device_id device_id, cl_context context, const CameraBuf *b, const CameraState *s) { @@ -200,7 +203,6 @@ void fill_frame_data(cereal::FrameData::Builder &framed, const FrameMetadata &fr framed.setMeasuredGreyFraction(frame_data.measured_grey_fraction); framed.setTargetGreyFraction(frame_data.target_grey_fraction); framed.setLensPos(frame_data.lens_pos); - framed.setLensSag(frame_data.lens_sag); framed.setLensErr(frame_data.lens_err); framed.setLensTruePos(frame_data.lens_true_pos); } @@ -340,8 +342,6 @@ float set_exposure_target(const CameraBuf *b, int x_start, int x_end, int x_skip return lum_med / 256.0; } -extern ExitHandler do_exit; - void *processing_thread(MultiCameraState *cameras, CameraState *cs, process_thread_cb callback) { const char *thread_name = nullptr; if (cs == &cameras->road_cam) { @@ -423,3 +423,27 @@ void common_process_driver_camera(MultiCameraState *s, CameraState *c, int cnt) } s->pm->send("driverCameraState", msg); } + + +void camerad_thread() { + cl_device_id device_id = cl_get_device_id(CL_DEVICE_TYPE_DEFAULT); + // TODO: do this for QCOM2 too +#if defined(QCOM) + const cl_context_properties props[] = {CL_CONTEXT_PRIORITY_HINT_QCOM, CL_PRIORITY_HINT_HIGH_QCOM, 0}; + cl_context context = CL_CHECK_ERR(clCreateContext(props, 1, &device_id, NULL, NULL, &err)); +#else + cl_context context = CL_CHECK_ERR(clCreateContext(NULL, 1, &device_id, NULL, NULL, &err)); +#endif + + MultiCameraState cameras = {}; + VisionIpcServer vipc_server("camerad", device_id, context); + + cameras_init(&vipc_server, &cameras, device_id, context); + cameras_open(&cameras); + + vipc_server.start_listener(); + + cameras_run(&cameras); + + CL_CHECK(clReleaseContext(context)); +} diff --git a/selfdrive/camerad/cameras/camera_common.h b/selfdrive/camerad/cameras/camera_common.h index 9394f9075..f53f06dce 100644 --- a/selfdrive/camerad/cameras/camera_common.h +++ b/selfdrive/camerad/cameras/camera_common.h @@ -41,6 +41,11 @@ const bool env_send_driver = getenv("SEND_DRIVER") != NULL; const bool env_send_road = getenv("SEND_ROAD") != NULL; const bool env_send_wide_road = getenv("SEND_WIDE_ROAD") != NULL; +// for debugging +// note: ONLY_ROAD doesn't work, likely due to a mixup with wideRoad cam in the kernel +const bool env_only_driver = getenv("ONLY_DRIVER") != NULL; +const bool env_debug_frames = getenv("DEBUG_FRAMES") != NULL; + typedef void (*release_cb)(void *cookie, int buf_idx); typedef struct CameraInfo { @@ -68,7 +73,6 @@ typedef struct FrameMetadata { // Focus unsigned int lens_pos; - float lens_sag; float lens_err; float lens_true_pos; } FrameMetadata; @@ -130,3 +134,4 @@ void cameras_open(MultiCameraState *s); void cameras_run(MultiCameraState *s); void cameras_close(MultiCameraState *s); void camera_autoexposure(CameraState *s, float grey_frac); +void camerad_thread(); diff --git a/selfdrive/camerad/cameras/camera_qcom.cc b/selfdrive/camerad/cameras/camera_qcom.cc index 06d58f2b0..ecb1c8ffe 100644 --- a/selfdrive/camerad/cameras/camera_qcom.cc +++ b/selfdrive/camerad/cameras/camera_qcom.cc @@ -852,21 +852,7 @@ static void parse_autofocus(CameraState *s, uint8_t *d) { s->focus_err = max_focus*1.0; } -static std::optional get_accel_z(SubMaster *sm) { - sm->update(0); - if(sm->updated("sensorEvents")) { - for (auto event : (*sm)["sensorEvents"].getSensorEvents()) { - if (event.which() == cereal::SensorEventData::ACCELERATION) { - if (auto v = event.getAcceleration().getV(); v.size() >= 3) - return -v[2]; - break; - } - } - } - return std::nullopt; -} - -static void do_autofocus(CameraState *s, SubMaster *sm) { +static void do_autofocus(CameraState *s) { float lens_true_pos = s->lens_true_pos.load(); if (!isnan(s->focus_err)) { // learn lens_true_pos @@ -874,23 +860,10 @@ static void do_autofocus(CameraState *s, SubMaster *sm) { lens_true_pos -= s->focus_err*focus_kp; } - if (auto accel_z = get_accel_z(sm)) { - s->last_sag_acc_z = *accel_z; - } - const float sag = (s->last_sag_acc_z / 9.8) * 128; // stay off the walls lens_true_pos = std::clamp(lens_true_pos, float(LP3_AF_DAC_DOWN), float(LP3_AF_DAC_UP)); - int target = std::clamp(lens_true_pos - sag, float(LP3_AF_DAC_DOWN), float(LP3_AF_DAC_UP)); s->lens_true_pos.store(lens_true_pos); - - /*char debug[4096]; - char *pdebug = debug; - pdebug += sprintf(pdebug, "focus "); - for (int i = 0; i < NUM_FOCUS; i++) pdebug += sprintf(pdebug, "%2x(%4d) ", s->confidence[i], s->focus[i]); - pdebug += sprintf(pdebug, " err: %7.2f offset: %6.2f sag: %6.2f lens_true_pos: %6.2f cur_lens_pos: %4d->%4d", err * focus_kp, offset, sag, s->lens_true_pos, s->cur_lens_pos, target); - LOGD(debug);*/ - - actuator_move(s, target); + actuator_move(s, lens_true_pos); } void camera_autoexposure(CameraState *s, float grey_frac) { @@ -1046,12 +1019,11 @@ static void ops_thread(MultiCameraState *s) { CameraExpInfo driver_cam_op; util::set_thread_name("camera_settings"); - SubMaster sm({"sensorEvents"}); while(!do_exit) { road_cam_op = road_cam_exp.load(); if (road_cam_op.op_id != last_road_cam_op_id) { do_autoexposure(&s->road_cam, road_cam_op.grey_frac); - do_autofocus(&s->road_cam, &sm); + do_autofocus(&s->road_cam); last_road_cam_op_id = road_cam_op.op_id; } @@ -1165,7 +1137,6 @@ void cameras_run(MultiCameraState *s) { .frame_length = (uint32_t)c->frame_length, .integ_lines = (uint32_t)c->cur_integ_lines, .lens_pos = c->cur_lens_pos, - .lens_sag = c->last_sag_acc_z, .lens_err = c->focus_err, .lens_true_pos = c->lens_true_pos, .gain = c->cur_gain_frac, diff --git a/selfdrive/camerad/cameras/camera_qcom.h b/selfdrive/camerad/cameras/camera_qcom.h index 207857e05..87bbe4b7e 100644 --- a/selfdrive/camerad/cameras/camera_qcom.h +++ b/selfdrive/camerad/cameras/camera_qcom.h @@ -76,7 +76,6 @@ typedef struct CameraState { // rear camera only,used for focusing unique_fd actuator_fd; std::atomic focus_err; - std::atomic last_sag_acc_z; std::atomic lens_true_pos; std::atomic self_recover; // af recovery counter, neg is patience, pos is active uint16_t cur_step_pos; diff --git a/selfdrive/camerad/cameras/camera_qcom2.cc b/selfdrive/camerad/cameras/camera_qcom2.cc index 030bbe47e..e86de9ffd 100644 --- a/selfdrive/camerad/cameras/camera_qcom2.cc +++ b/selfdrive/camerad/cameras/camera_qcom2.cc @@ -60,7 +60,7 @@ int cam_control(int fd, int op_code, void *handle, int size) { struct cam_control camcontrol = {0}; camcontrol.op_code = op_code; camcontrol.handle = (uint64_t)handle; - if (size == 0) { + if (size == 0) { camcontrol.size = 8; camcontrol.handle_type = CAM_HANDLE_MEM_HANDLE; } else { @@ -227,7 +227,7 @@ void sensors_init(int video0_fd, int sensor_fd, int camera_num) { buf_desc[0].size = buf_desc[0].length = sizeof(struct cam_cmd_i2c_info) + sizeof(struct cam_cmd_probe); buf_desc[0].type = CAM_CMD_BUF_LEGACY; struct cam_cmd_i2c_info *i2c_info = (struct cam_cmd_i2c_info *)alloc_w_mmu_hdl(video0_fd, buf_desc[0].size, (uint32_t*)&buf_desc[0].mem_handle); - struct cam_cmd_probe *probe = (struct cam_cmd_probe *)((uint8_t *)i2c_info) + sizeof(struct cam_cmd_i2c_info); + auto probe = (struct cam_cmd_probe *)(i2c_info + 1); switch (camera_num) { case 0: @@ -353,6 +353,9 @@ void config_isp(struct CameraState *s, int io_mem_handle, int fence, int request struct cam_packet *pkt = (struct cam_packet *)alloc_w_mmu_hdl(s->multi_cam_state->video0_fd, size, &cam_packet_handle); pkt->num_cmd_buf = 2; pkt->kmd_cmd_buf_index = 0; + // YUV has kmd_cmd_buf_offset = 1780 + // I guess this is the ISP command + // YUV also has patch_offset = 0x1030 and num_patches = 10 if (io_mem_handle != 0) { pkt->io_configs_offset = sizeof(struct cam_cmd_buf_desc)*2; @@ -377,28 +380,65 @@ void config_isp(struct CameraState *s, int io_mem_handle, int fence, int request buf_desc[0].mem_handle = buf0_mem_handle; buf_desc[0].offset = buf0_offset; - // cam_isp_packet_generic_blob_handler - uint32_t tmp[] = { - // size is 0x20, type is 0(CAM_ISP_GENERIC_BLOB_TYPE_HFR_CONFIG) - 0x2000, - 0x1, 0x0, CAM_ISP_IFE_OUT_RES_RDI_0, 0x1, 0x0, 0x1, 0x0, 0x0, // 1 port, CAM_ISP_IFE_OUT_RES_RDI_0 - // size is 0x38, type is 1(CAM_ISP_GENERIC_BLOB_TYPE_CLOCK_CONFIG), clocks - 0x3801, - 0x1, 0x4, // Dual mode, 4 RDI wires - 0x18148d00, 0x0, 0x18148d00, 0x0, 0x18148d00, 0x0, // rdi clock - 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, // junk? - // offset 0x60 - // size is 0xe0, type is 2(CAM_ISP_GENERIC_BLOB_TYPE_BW_CONFIG), bandwidth - 0xe002, - 0x1, 0x4, // 4 RDI - 0x0, 0x0, 0x1ad27480, 0x0, 0x1ad27480, 0x0, // left_pix_vote - 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, // right_pix_vote - 0x0, 0x0, 0x6ee11c0, 0x2, 0x6ee11c0, 0x2, // rdi_vote - 0x0, 0x0, 0x0, 0x0, - 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, - 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, - 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, - 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0}; + // parsed by cam_isp_packet_generic_blob_handler + struct isp_packet { + uint32_t type_0; + cam_isp_resource_hfr_config resource_hfr; + + uint32_t type_1; + cam_isp_clock_config clock; + uint64_t extra_rdi_hz[3]; + + uint32_t type_2; + cam_isp_bw_config bw; + struct cam_isp_bw_vote extra_rdi_vote[6]; + } __attribute__((packed)) tmp; + memset(&tmp, 0, sizeof(tmp)); + + tmp.type_0 = CAM_ISP_GENERIC_BLOB_TYPE_HFR_CONFIG; + tmp.type_0 |= sizeof(cam_isp_resource_hfr_config) << 8; + static_assert(sizeof(cam_isp_resource_hfr_config) == 0x20); + tmp.resource_hfr = { + .num_ports = 1, // 10 for YUV (but I don't think we need them) + .port_hfr_config[0] = { + .resource_type = CAM_ISP_IFE_OUT_RES_RDI_0, // CAM_ISP_IFE_OUT_RES_FULL for YUV + .subsample_pattern = 1, + .subsample_period = 0, + .framedrop_pattern = 1, + .framedrop_period = 0, + }}; + + tmp.type_1 = CAM_ISP_GENERIC_BLOB_TYPE_CLOCK_CONFIG; + tmp.type_1 |= (sizeof(cam_isp_clock_config) + sizeof(tmp.extra_rdi_hz)) << 8; + static_assert((sizeof(cam_isp_clock_config) + sizeof(tmp.extra_rdi_hz)) == 0x38); + tmp.clock = { + .usage_type = 1, // dual mode + .num_rdi = 4, + .left_pix_hz = 404000000, + .right_pix_hz = 404000000, + .rdi_hz[0] = 404000000, + }; + + + tmp.type_2 = CAM_ISP_GENERIC_BLOB_TYPE_BW_CONFIG; + tmp.type_2 |= (sizeof(cam_isp_bw_config) + sizeof(tmp.extra_rdi_vote)) << 8; + static_assert((sizeof(cam_isp_bw_config) + sizeof(tmp.extra_rdi_vote)) == 0xe0); + tmp.bw = { + .usage_type = 1, // dual mode + .num_rdi = 4, + .left_pix_vote = { + .resource_id = 0, + .cam_bw_bps = 450000000, + .ext_bw_bps = 450000000, + }, + .rdi_vote[0] = { + .resource_id = 0, + .cam_bw_bps = 8706200000, + .ext_bw_bps = 8706200000, + }, + }; + + static_assert(offsetof(struct isp_packet, type_2) == 0x60); buf_desc[1].size = sizeof(tmp); buf_desc[1].offset = io_mem_handle != 0 ? 0x60 : 0; @@ -406,7 +446,7 @@ void config_isp(struct CameraState *s, int io_mem_handle, int fence, int request buf_desc[1].type = CAM_CMD_BUF_GENERIC; buf_desc[1].meta_data = CAM_ISP_PACKET_META_GENERIC_BLOB_COMMON; uint32_t *buf2 = (uint32_t *)alloc_w_mmu_hdl(s->multi_cam_state->video0_fd, buf_desc[1].size, (uint32_t*)&buf_desc[1].mem_handle, 0x20); - memcpy(buf2, tmp, sizeof(tmp)); + memcpy(buf2, &tmp, sizeof(tmp)); if (io_mem_handle != 0) { io_cfg[0].mem_handle[0] = io_mem_handle; @@ -415,19 +455,20 @@ void config_isp(struct CameraState *s, int io_mem_handle, int fence, int request .height = FRAME_HEIGHT, .plane_stride = FRAME_STRIDE, .slice_height = FRAME_HEIGHT, - .meta_stride = 0x0, + .meta_stride = 0x0, // YUV has meta(stride=0x400, size=0x5000) .meta_size = 0x0, .meta_offset = 0x0, - .packer_config = 0x0, - .mode_config = 0x0, + .packer_config = 0x0, // 0xb for YUV + .mode_config = 0x0, // 0x9ef for YUV .tile_config = 0x0, .h_init = 0x0, .v_init = 0x0, }; - io_cfg[0].format = CAM_FORMAT_MIPI_RAW_10; - io_cfg[0].color_pattern = 0x5; - io_cfg[0].bpp = 0xc; - io_cfg[0].resource_type = CAM_ISP_IFE_OUT_RES_RDI_0; + io_cfg[0].format = CAM_FORMAT_MIPI_RAW_10; // CAM_FORMAT_UBWC_TP10 for YUV + io_cfg[0].color_space = CAM_COLOR_SPACE_BASE; // CAM_COLOR_SPACE_BT601_FULL for YUV + io_cfg[0].color_pattern = 0x5; // 0x0 for YUV + io_cfg[0].bpp = 0xa; + io_cfg[0].resource_type = CAM_ISP_IFE_OUT_RES_RDI_0; // CAM_ISP_IFE_OUT_RES_FULL for YUV io_cfg[0].fence = fence; io_cfg[0].direction = CAM_BUF_OUTPUT; io_cfg[0].subsample_pattern = 0x1; @@ -553,18 +594,14 @@ int open_v4l_by_name_and_index(const char name[], int index, int flags = O_RDWR static void camera_open(CameraState *s) { s->sensor_fd = open_v4l_by_name_and_index("cam-sensor-driver", s->camera_num); assert(s->sensor_fd >= 0); - LOGD("opened sensor"); - - s->csiphy_fd = open_v4l_by_name_and_index("cam-csiphy-driver", s->camera_num); - assert(s->csiphy_fd >= 0); - LOGD("opened csiphy"); + LOGD("opened sensor for %d", s->camera_num); // probe the sensor LOGD("-- Probing sensor %d", s->camera_num); sensors_init(s->multi_cam_state->video0_fd, s->sensor_fd, s->camera_num); // create session - struct cam_req_mgr_session_info session_info = {}; + struct cam_req_mgr_session_info session_info = {}; int ret = cam_control(s->multi_cam_state->video0_fd, CAM_REQ_MGR_CREATE_SESSION, &session_info, sizeof(session_info)); LOGD("get session: %d 0x%X", ret, session_info.session_hdl); s->session_handle = session_info.session_hdl; @@ -605,7 +642,7 @@ static void camera_open(CameraState *s) { .pixel_clk = 0x0, .batch_size = 0x0, - .dsp_mode = 0x0, + .dsp_mode = CAM_ISP_DSP_MODE_NONE, .hbi_cnt = 0x0, .custom_csid = 0x0, @@ -627,9 +664,13 @@ static void camera_open(CameraState *s) { auto isp_dev_handle = device_acquire(s->multi_cam_state->isp_fd, s->session_handle, &isp_resource); assert(isp_dev_handle); - s->isp_dev_handle = *isp_dev_handle; + s->isp_dev_handle = *isp_dev_handle; LOGD("acquire isp dev"); + s->csiphy_fd = open_v4l_by_name_and_index("cam-csiphy-driver", s->camera_num); + assert(s->csiphy_fd >= 0); + LOGD("opened csiphy for %d", s->camera_num); + struct cam_csiphy_acquire_dev_info csiphy_acquire_dev_info = {.combo_mode = 0}; auto csiphy_dev_handle = device_acquire(s->csiphy_fd, s->session_handle, &csiphy_acquire_dev_info); assert(csiphy_dev_handle); @@ -645,6 +686,7 @@ static void camera_open(CameraState *s) { //sensors_i2c(s, start_reg_array, std::size(start_reg_array), CAM_SENSOR_PACKET_OPCODE_SENSOR_STREAMON); //sensors_i2c(s, stop_reg_array, std::size(stop_reg_array), CAM_SENSOR_PACKET_OPCODE_SENSOR_STREAMOFF); + // config csiphy LOG("-- Config CSI PHY"); { @@ -686,8 +728,8 @@ static void camera_open(CameraState *s) { req_mgr_link_info.dev_hdls[0] = s->isp_dev_handle; req_mgr_link_info.dev_hdls[1] = s->sensor_dev_handle; ret = cam_control(s->multi_cam_state->video0_fd, CAM_REQ_MGR_LINK, &req_mgr_link_info, sizeof(req_mgr_link_info)); - LOGD("link: %d", ret); s->link_handle = req_mgr_link_info.link_hdl; + LOGD("link: %d hdl: 0x%X", ret, s->link_handle); struct cam_req_mgr_link_control req_mgr_link_control = {0}; req_mgr_link_control.ops = CAM_REQ_MGR_LINK_ACTIVATE; @@ -708,15 +750,17 @@ static void camera_open(CameraState *s) { } void cameras_init(VisionIpcServer *v, MultiCameraState *s, cl_device_id device_id, cl_context ctx) { - camera_init(s, v, &s->road_cam, CAMERA_ID_AR0231, 1, 20, device_id, ctx, - VISION_STREAM_RGB_BACK, VISION_STREAM_ROAD); // swap left/right - printf("road camera initted \n"); - camera_init(s, v, &s->wide_road_cam, CAMERA_ID_AR0231, 0, 20, device_id, ctx, - VISION_STREAM_RGB_WIDE, VISION_STREAM_WIDE_ROAD); - printf("wide road camera initted \n"); camera_init(s, v, &s->driver_cam, CAMERA_ID_AR0231, 2, 20, device_id, ctx, VISION_STREAM_RGB_FRONT, VISION_STREAM_DRIVER); printf("driver camera initted \n"); + if (!env_only_driver) { + camera_init(s, v, &s->road_cam, CAMERA_ID_AR0231, 1, 20, device_id, ctx, + VISION_STREAM_RGB_BACK, VISION_STREAM_ROAD); // swap left/right + printf("road camera initted \n"); + camera_init(s, v, &s->wide_road_cam, CAMERA_ID_AR0231, 0, 20, device_id, ctx, + VISION_STREAM_RGB_WIDE, VISION_STREAM_WIDE_ROAD); + printf("wide road camera initted \n"); + } s->sm = new SubMaster({"driverState"}); s->pm = new PubMaster({"roadCameraState", "driverCameraState", "wideRoadCameraState", "thumbnail"}); @@ -763,12 +807,14 @@ void cameras_open(MultiCameraState *s) { ret = HANDLE_EINTR(ioctl(s->video0_fd, VIDIOC_SUBSCRIBE_EVENT, &sub)); printf("req mgr subscribe: %d\n", ret); - camera_open(&s->road_cam); - printf("road camera opened \n"); - camera_open(&s->wide_road_cam); - printf("wide road camera opened \n"); camera_open(&s->driver_cam); printf("driver camera opened \n"); + if (!env_only_driver) { + camera_open(&s->road_cam); + printf("road camera opened \n"); + camera_open(&s->wide_road_cam); + printf("wide road camera opened \n"); + } } static void camera_close(CameraState *s) { @@ -816,9 +862,11 @@ static void camera_close(CameraState *s) { } void cameras_close(MultiCameraState *s) { - camera_close(&s->road_cam); - camera_close(&s->wide_road_cam); camera_close(&s->driver_cam); + if (!env_only_driver) { + camera_close(&s->road_cam); + camera_close(&s->wide_road_cam); + } delete s->sm; delete s->pm; @@ -1010,16 +1058,20 @@ void process_road_camera(MultiCameraState *s, CameraState *c, int cnt) { void cameras_run(MultiCameraState *s) { LOG("-- Starting threads"); std::vector threads; - threads.push_back(start_process_thread(s, &s->road_cam, process_road_camera)); threads.push_back(start_process_thread(s, &s->driver_cam, common_process_driver_camera)); - threads.push_back(start_process_thread(s, &s->wide_road_cam, process_road_camera)); + if (!env_only_driver) { + threads.push_back(start_process_thread(s, &s->road_cam, process_road_camera)); + threads.push_back(start_process_thread(s, &s->wide_road_cam, process_road_camera)); + } // start devices LOG("-- Starting devices"); int start_reg_len = sizeof(start_reg_array) / sizeof(struct i2c_random_wr_payload); - sensors_i2c(&s->road_cam, start_reg_array, start_reg_len, CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG); - sensors_i2c(&s->wide_road_cam, start_reg_array, start_reg_len, CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG); sensors_i2c(&s->driver_cam, start_reg_array, start_reg_len, CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG); + if (!env_only_driver) { + sensors_i2c(&s->road_cam, start_reg_array, start_reg_len, CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG); + sensors_i2c(&s->wide_road_cam, start_reg_array, start_reg_len, CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG); + } // poll events LOG("-- Dequeueing Video events"); @@ -1043,8 +1095,10 @@ void cameras_run(MultiCameraState *s) { if (ret == 0) { if (ev.type == V4L_EVENT_CAM_REQ_MGR_EVENT) { struct cam_req_mgr_message *event_data = (struct cam_req_mgr_message *)ev.u.data; - // LOGD("v4l2 event: sess_hdl %d, link_hdl %d, frame_id %d, req_id %lld, timestamp 0x%llx, sof_status %d\n", event_data->session_hdl, event_data->u.frame_msg.link_hdl, event_data->u.frame_msg.frame_id, event_data->u.frame_msg.request_id, event_data->u.frame_msg.timestamp, event_data->u.frame_msg.sof_status); - // printf("sess_hdl %d, link_hdl %d, frame_id %lu, req_id %lu, timestamp 0x%lx, sof_status %d\n", event_data->session_hdl, event_data->u.frame_msg.link_hdl, event_data->u.frame_msg.frame_id, event_data->u.frame_msg.request_id, event_data->u.frame_msg.timestamp, event_data->u.frame_msg.sof_status); + // LOGD("v4l2 event: sess_hdl 0x%X, link_hdl 0x%X, frame_id %d, req_id %lld, timestamp 0x%llx, sof_status %d\n", event_data->session_hdl, event_data->u.frame_msg.link_hdl, event_data->u.frame_msg.frame_id, event_data->u.frame_msg.request_id, event_data->u.frame_msg.timestamp, event_data->u.frame_msg.sof_status); + if (env_debug_frames) { + printf("sess_hdl 0x%X, link_hdl 0x%X, frame_id %lu, req_id %lu, timestamp 0x%lx, sof_status %d\n", event_data->session_hdl, event_data->u.frame_msg.link_hdl, event_data->u.frame_msg.frame_id, event_data->u.frame_msg.request_id, event_data->u.frame_msg.timestamp, event_data->u.frame_msg.sof_status); + } if (event_data->session_hdl == s->road_cam.session_handle) { handle_camera_event(&s->road_cam, event_data); diff --git a/selfdrive/camerad/main.cc b/selfdrive/camerad/main.cc index f06bd341d..668410d6f 100644 --- a/selfdrive/camerad/main.cc +++ b/selfdrive/camerad/main.cc @@ -1,48 +1,11 @@ -#include -#include -#include +#include "selfdrive/camerad/cameras/camera_common.h" #include -#include -#include -#include "libyuv.h" - -#include "cereal/visionipc/visionipc_server.h" -#include "selfdrive/common/clutil.h" #include "selfdrive/common/params.h" -#include "selfdrive/common/swaglog.h" #include "selfdrive/common/util.h" #include "selfdrive/hardware/hw.h" -#ifdef QCOM -#include "selfdrive/camerad/cameras/camera_qcom.h" -#elif QCOM2 -#include "selfdrive/camerad/cameras/camera_qcom2.h" -#elif WEBCAM -#include "selfdrive/camerad/cameras/camera_webcam.h" -#else -#include "selfdrive/camerad/cameras/camera_replay.h" -#endif - -ExitHandler do_exit; - -void party(cl_device_id device_id, cl_context context) { - MultiCameraState cameras = {}; - VisionIpcServer vipc_server("camerad", device_id, context); - - cameras_init(&vipc_server, &cameras, device_id, context); - cameras_open(&cameras); - - vipc_server.start_listener(); - - cameras_run(&cameras); -} - -#ifdef QCOM -#include "CL/cl_ext_qcom.h" -#endif - int main(int argc, char *argv[]) { if (!Hardware::PC()) { int ret; @@ -52,17 +15,6 @@ int main(int argc, char *argv[]) { assert(ret == 0 || Params().getBool("IsOffroad")); // failure ok while offroad due to offlining cores } - cl_device_id device_id = cl_get_device_id(CL_DEVICE_TYPE_DEFAULT); - - // TODO: do this for QCOM2 too -#if defined(QCOM) - const cl_context_properties props[] = {CL_CONTEXT_PRIORITY_HINT_QCOM, CL_PRIORITY_HINT_HIGH_QCOM, 0}; - cl_context context = CL_CHECK_ERR(clCreateContext(props, 1, &device_id, NULL, NULL, &err)); -#else - cl_context context = CL_CHECK_ERR(clCreateContext(NULL, 1, &device_id, NULL, NULL, &err)); -#endif - - party(device_id, context); - - CL_CHECK(clReleaseContext(context)); + camerad_thread(); + return 0; } diff --git a/selfdrive/car/car_helpers.py b/selfdrive/car/car_helpers.py index 786b00fa2..90bfdd8a9 100644 --- a/selfdrive/car/car_helpers.py +++ b/selfdrive/car/car_helpers.py @@ -1,7 +1,7 @@ import os from common.params import Params from common.basedir import BASEDIR -from selfdrive.version import get_comma_remote, get_tested_branch +from selfdrive.version import is_comma_remote, is_tested_branch from selfdrive.car.fingerprints import eliminate_incompatible_cars, all_legacy_fingerprint_cars from selfdrive.car.vin import get_vin, VIN_UNKNOWN from selfdrive.car.fw_versions import get_fw_versions, match_fw_to_car @@ -14,7 +14,7 @@ EventName = car.CarEvent.EventName def get_startup_event(car_recognized, controller_available, fw_seen): - if get_comma_remote() and get_tested_branch(): + if is_comma_remote() and is_tested_branch(): event = EventName.startup else: event = EventName.startupMaster @@ -39,7 +39,7 @@ def get_one_can(logcan): def load_interfaces(brand_names): ret = {} for brand_name in brand_names: - path = ('selfdrive.car.%s' % brand_name) + path = f'selfdrive.car.{brand_name}' CarInterface = __import__(path + '.interface', fromlist=['CarInterface']).CarInterface if os.path.exists(BASEDIR + '/' + path.replace('.', '/') + '/carstate.py'): @@ -65,10 +65,10 @@ def _get_interface_names(): for car_folder in [x[0] for x in os.walk(BASEDIR + '/selfdrive/car')]: try: brand_name = car_folder.split('/')[-1] - model_names = __import__('selfdrive.car.%s.values' % brand_name, fromlist=['CAR']).CAR + model_names = __import__(f'selfdrive.car.{brand_name}.values', fromlist=['CAR']).CAR model_names = [getattr(model_names, c) for c in model_names.__dict__.keys() if not c.startswith("__")] brand_names[brand_name] = model_names - except (ImportError, IOError): + except (ImportError, OSError): pass return brand_names @@ -125,13 +125,13 @@ def fingerprint(logcan, sendcan): # The fingerprint dict is generated for all buses, this way the car interface # can use it to detect a (valid) multipanda setup and initialize accordingly if can.src < 128: - if can.src not in finger.keys(): + if can.src not in finger: finger[can.src] = {} finger[can.src][can.address] = len(can.dat) for b in candidate_cars: # Ignore extended messages and VIN query response. - if can.src == b and can.address < 0x800 and can.address not in [0x7df, 0x7e0, 0x7e8]: + if can.src == b and can.address < 0x800 and can.address not in (0x7df, 0x7e0, 0x7e8): candidate_cars[b] = eliminate_incompatible_cars(can, candidate_cars[b]) # if we only have one car choice and the time since we got our first diff --git a/selfdrive/car/chrysler/carcontroller.py b/selfdrive/car/chrysler/carcontroller.py index 46681b13e..d491ccd4b 100644 --- a/selfdrive/car/chrysler/carcontroller.py +++ b/selfdrive/car/chrysler/carcontroller.py @@ -1,3 +1,4 @@ +from cereal import car from selfdrive.car import apply_toyota_steer_torque_limits from selfdrive.car.chrysler.chryslercan import create_lkas_hud, create_lkas_command, \ create_wheel_buttons @@ -20,9 +21,8 @@ class CarController(): # this seems needed to avoid steering faults and to force the sync with the EPS counter frame = CS.lkas_counter if self.prev_frame == frame: - return [] + return car.CarControl.Actuators.new_message(), [] - # *** compute control surfaces *** # steer torque new_steer = int(round(actuators.steer * CarControllerParams.STEER_MAX)) apply_steer = apply_toyota_steer_torque_limits(new_steer, self.apply_steer_last, @@ -67,4 +67,7 @@ class CarController(): self.ccframe += 1 self.prev_frame = frame - return can_sends + new_actuators = actuators.copy() + new_actuators.steer = apply_steer / CarControllerParams.STEER_MAX + + return new_actuators, can_sends diff --git a/selfdrive/car/chrysler/carstate.py b/selfdrive/car/chrysler/carstate.py index ab3125b01..30a0bf6a3 100644 --- a/selfdrive/car/chrysler/carstate.py +++ b/selfdrive/car/chrysler/carstate.py @@ -52,7 +52,7 @@ class CarState(CarStateBase): ret.cruiseState.available = ret.cruiseState.enabled # FIXME: for now same as enabled ret.cruiseState.speed = cp.vl["DASHBOARD"]["ACC_SPEED_CONFIG_KPH"] * CV.KPH_TO_MS # CRUISE_STATE is a three bit msg, 0 is off, 1 and 2 are Non-ACC mode, 3 and 4 are ACC mode, find if there are other states too - ret.cruiseState.nonAdaptive = cp.vl["DASHBOARD"]["CRUISE_STATE"] in [1, 2] + ret.cruiseState.nonAdaptive = cp.vl["DASHBOARD"]["CRUISE_STATE"] in (1, 2) ret.steeringTorque = cp.vl["EPS_STATUS"]["TORQUE_DRIVER"] ret.steeringTorqueEps = cp.vl["EPS_STATUS"]["TORQUE_MOTOR"] @@ -75,33 +75,33 @@ class CarState(CarStateBase): @staticmethod def get_can_parser(CP): signals = [ - # sig_name, sig_address, default - ("PRNDL", "GEAR", 0), - ("DOOR_OPEN_FL", "DOORS", 0), - ("DOOR_OPEN_FR", "DOORS", 0), - ("DOOR_OPEN_RL", "DOORS", 0), - ("DOOR_OPEN_RR", "DOORS", 0), - ("BRAKE_PRESSED_2", "BRAKE_2", 0), - ("ACCEL_134", "ACCEL_GAS_134", 0), - ("SPEED_LEFT", "SPEED_1", 0), - ("SPEED_RIGHT", "SPEED_1", 0), - ("WHEEL_SPEED_FL", "WHEEL_SPEEDS", 0), - ("WHEEL_SPEED_RR", "WHEEL_SPEEDS", 0), - ("WHEEL_SPEED_RL", "WHEEL_SPEEDS", 0), - ("WHEEL_SPEED_FR", "WHEEL_SPEEDS", 0), - ("STEER_ANGLE", "STEERING", 0), - ("STEERING_RATE", "STEERING", 0), - ("TURN_SIGNALS", "STEERING_LEVERS", 0), - ("ACC_STATUS_2", "ACC_2", 0), - ("HIGH_BEAM_FLASH", "STEERING_LEVERS", 0), - ("ACC_SPEED_CONFIG_KPH", "DASHBOARD", 0), - ("CRUISE_STATE", "DASHBOARD", 0), - ("TORQUE_DRIVER", "EPS_STATUS", 0), - ("TORQUE_MOTOR", "EPS_STATUS", 0), - ("LKAS_STATE", "EPS_STATUS", 1), - ("COUNTER", "EPS_STATUS", -1), - ("TRACTION_OFF", "TRACTION_BUTTON", 0), - ("SEATBELT_DRIVER_UNLATCHED", "SEATBELT_STATUS", 0), + # sig_name, sig_address + ("PRNDL", "GEAR"), + ("DOOR_OPEN_FL", "DOORS"), + ("DOOR_OPEN_FR", "DOORS"), + ("DOOR_OPEN_RL", "DOORS"), + ("DOOR_OPEN_RR", "DOORS"), + ("BRAKE_PRESSED_2", "BRAKE_2"), + ("ACCEL_134", "ACCEL_GAS_134"), + ("SPEED_LEFT", "SPEED_1"), + ("SPEED_RIGHT", "SPEED_1"), + ("WHEEL_SPEED_FL", "WHEEL_SPEEDS"), + ("WHEEL_SPEED_RR", "WHEEL_SPEEDS"), + ("WHEEL_SPEED_RL", "WHEEL_SPEEDS"), + ("WHEEL_SPEED_FR", "WHEEL_SPEEDS"), + ("STEER_ANGLE", "STEERING"), + ("STEERING_RATE", "STEERING"), + ("TURN_SIGNALS", "STEERING_LEVERS"), + ("ACC_STATUS_2", "ACC_2"), + ("HIGH_BEAM_FLASH", "STEERING_LEVERS"), + ("ACC_SPEED_CONFIG_KPH", "DASHBOARD"), + ("CRUISE_STATE", "DASHBOARD"), + ("TORQUE_DRIVER", "EPS_STATUS"), + ("TORQUE_MOTOR", "EPS_STATUS"), + ("LKAS_STATE", "EPS_STATUS"), + ("COUNTER", "EPS_STATUS",), + ("TRACTION_OFF", "TRACTION_BUTTON"), + ("SEATBELT_DRIVER_UNLATCHED", "SEATBELT_STATUS"), ] checks = [ @@ -123,20 +123,20 @@ class CarState(CarStateBase): if CP.enableBsm: signals += [ - ("BLIND_SPOT_RIGHT", "BLIND_SPOT_WARNINGS", 0), - ("BLIND_SPOT_LEFT", "BLIND_SPOT_WARNINGS", 0), + ("BLIND_SPOT_RIGHT", "BLIND_SPOT_WARNINGS"), + ("BLIND_SPOT_LEFT", "BLIND_SPOT_WARNINGS"), ] - checks += [("BLIND_SPOT_WARNINGS", 2)] + checks.append(("BLIND_SPOT_WARNINGS", 2)) return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 0) @staticmethod def get_cam_can_parser(CP): signals = [ - # sig_name, sig_address, default - ("COUNTER", "LKAS_COMMAND", -1), - ("CAR_MODEL", "LKAS_HUD", -1), - ("LKAS_STATUS_OK", "LKAS_HEARTBIT", -1) + # sig_name, sig_address + ("COUNTER", "LKAS_COMMAND"), + ("CAR_MODEL", "LKAS_HUD"), + ("LKAS_STATUS_OK", "LKAS_HEARTBIT") ] checks = [ ("LKAS_COMMAND", 100), diff --git a/selfdrive/car/chrysler/chryslercan.py b/selfdrive/car/chrysler/chryslercan.py index c72f15529..4d5226570 100644 --- a/selfdrive/car/chrysler/chryslercan.py +++ b/selfdrive/car/chrysler/chryslercan.py @@ -8,7 +8,7 @@ VisualAlert = car.CarControl.HUDControl.VisualAlert def create_lkas_hud(packer, gear, lkas_active, hud_alert, hud_count, lkas_car_model): # LKAS_HUD 0x2a6 (678) Controls what lane-keeping icon is displayed. - if hud_alert in [VisualAlert.steerRequired, VisualAlert.ldw]: + if hud_alert in (VisualAlert.steerRequired, VisualAlert.ldw): msg = b'\x00\x00\x00\x03\x00\x00\x00\x00' return make_can_msg(0x2a6, msg, 0) diff --git a/selfdrive/car/chrysler/interface.py b/selfdrive/car/chrysler/interface.py index 1822d76a1..aead03781 100755 --- a/selfdrive/car/chrysler/interface.py +++ b/selfdrive/car/chrysler/interface.py @@ -60,8 +60,7 @@ class CarInterface(CarInterfaceBase): ret.steeringRateLimited = self.CC.steer_rate_limited if self.CC is not None else False # events - events = self.create_common_events(ret, extra_gears=[car.CarState.GearShifter.low], - gas_resume_speed=2.) + events = self.create_common_events(ret, extra_gears=[car.CarState.GearShifter.low]) if ret.vEgo < self.CP.minSteerSpeed: events.add(car.CarEvent.EventName.belowSteerSpeed) @@ -78,8 +77,6 @@ class CarInterface(CarInterfaceBase): def apply(self, c): if (self.CS.frame == -1): - return [] # if we haven't seen a frame 220, then do not update. + return car.CarControl.Actuators.new_message(), [] # if we haven't seen a frame 220, then do not update. - can_sends = self.CC.update(c.enabled, self.CS, c.actuators, c.cruiseControl.cancel, c.hudControl.visualAlert) - - return can_sends + return self.CC.update(c.enabled, self.CS, c.actuators, c.cruiseControl.cancel, c.hudControl.visualAlert) diff --git a/selfdrive/car/chrysler/radar_interface.py b/selfdrive/car/chrysler/radar_interface.py index 3139efad3..8882dc2d9 100755 --- a/selfdrive/car/chrysler/radar_interface.py +++ b/selfdrive/car/chrysler/radar_interface.py @@ -11,30 +11,23 @@ NUMBER_MSGS = len(RADAR_MSGS_C) + len(RADAR_MSGS_D) def _create_radar_can_parser(car_fingerprint): msg_n = len(RADAR_MSGS_C) - # list of [(signal name, message name or number, initial values), (...)] - # [('RADAR_STATE', 1024, 0), - # ('LONG_DIST', 1072, 255), - # ('LONG_DIST', 1073, 255), - # ('LONG_DIST', 1074, 255), - # ('LONG_DIST', 1075, 255), + # list of [(signal name, message name or number), (...)] + # [('RADAR_STATE', 1024), + # ('LONG_DIST', 1072), + # ('LONG_DIST', 1073), + # ('LONG_DIST', 1074), + # ('LONG_DIST', 1075), - # The factor and offset are applied by the dbc parsing library, so the - # default values should be after the factor/offset are applied. signals = list(zip(['LONG_DIST'] * msg_n + - ['LAT_DIST'] * msg_n + - ['REL_SPEED'] * msg_n, - RADAR_MSGS_C * 2 + # LONG_DIST, LAT_DIST - RADAR_MSGS_D, # REL_SPEED - [0] * msg_n + # LONG_DIST - [-1000] * msg_n + # LAT_DIST - [-146.278] * msg_n)) # REL_SPEED set to 0, factor/offset to this - # TODO what are the checks actually used for? - # honda only checks the last message, - # toyota checks all the messages. Which do we want? + ['LAT_DIST'] * msg_n + + ['REL_SPEED'] * msg_n, + RADAR_MSGS_C * 2 + # LONG_DIST, LAT_DIST + RADAR_MSGS_D)) # REL_SPEED + checks = list(zip(RADAR_MSGS_C + - RADAR_MSGS_D, - [20]*msg_n + # 20Hz (0.05s) - [20]*msg_n)) # 20Hz (0.05s) + RADAR_MSGS_D, + [20] * msg_n + # 20Hz (0.05s) + [20] * msg_n)) # 20Hz (0.05s) return CANParser(DBC[car_fingerprint]['radar'], signals, checks, 1) diff --git a/selfdrive/car/chrysler/values.py b/selfdrive/car/chrysler/values.py index e32de1950..3fd32e9bc 100644 --- a/selfdrive/car/chrysler/values.py +++ b/selfdrive/car/chrysler/values.py @@ -1,5 +1,3 @@ -# flake8: noqa - from selfdrive.car import dbc_dict from cereal import car Ecu = car.CarParams.Ecu diff --git a/selfdrive/car/fingerprints.py b/selfdrive/car/fingerprints.py index b09e14a42..9b280f3b4 100644 --- a/selfdrive/car/fingerprints.py +++ b/selfdrive/car/fingerprints.py @@ -11,7 +11,7 @@ def get_attr_from_cars(attr, result=dict, combine_brands=True): for car_folder in [x[0] for x in os.walk(BASEDIR + '/selfdrive/car')]: try: car_name = car_folder.split('/')[-1] - values = __import__('selfdrive.car.%s.values' % car_name, fromlist=[attr]) + values = __import__(f'selfdrive.car.{car_name}.values', fromlist=[attr]) if hasattr(values, attr): attr_values = getattr(values, attr) else: @@ -28,7 +28,7 @@ def get_attr_from_cars(attr, result=dict, combine_brands=True): elif isinstance(attr_values, list): result += attr_values - except (ImportError, IOError): + except (ImportError, OSError): pass return result diff --git a/selfdrive/car/ford/carcontroller.py b/selfdrive/car/ford/carcontroller.py index 06c5f2579..389d3d8d8 100644 --- a/selfdrive/car/ford/carcontroller.py +++ b/selfdrive/car/ford/carcontroller.py @@ -22,7 +22,7 @@ class CarController(): def update(self, enabled, CS, frame, actuators, visual_alert, pcm_cancel): can_sends = [] - steer_alert = visual_alert in [VisualAlert.steerRequired, VisualAlert.ldw] + steer_alert = visual_alert in (VisualAlert.steerRequired, VisualAlert.ldw) apply_steer = actuators.steer @@ -32,7 +32,7 @@ class CarController(): if (frame % 3) == 0: - curvature = self.vehicle_model.calc_curvature(actuators.steeringAngleDeg*math.pi/180., CS.out.vEgo) + curvature = self.vehicle_model.calc_curvature(math.radians(actuators.steeringAngleDeg), CS.out.vEgo, 0.0) # The use of the toggle below is handy for trying out the various LKAS modes if TOGGLE_DEBUG: @@ -83,4 +83,4 @@ class CarController(): self.main_on_last = CS.out.cruiseState.available self.steer_alert_last = steer_alert - return can_sends + return actuators, can_sends diff --git a/selfdrive/car/ford/carstate.py b/selfdrive/car/ford/carstate.py index a621ab16a..eba623f5c 100644 --- a/selfdrive/car/ford/carstate.py +++ b/selfdrive/car/ford/carstate.py @@ -25,7 +25,7 @@ class CarState(CarStateBase): ret.steeringPressed = not cp.vl["Lane_Keep_Assist_Status"]["LaHandsOff_B_Actl"] ret.steerError = cp.vl["Lane_Keep_Assist_Status"]["LaActDeny_B_Actl"] == 1 ret.cruiseState.speed = cp.vl["Cruise_Status"]["Set_Speed"] * CV.MPH_TO_MS - ret.cruiseState.enabled = not (cp.vl["Cruise_Status"]["Cruise_State"] in [0, 3]) + ret.cruiseState.enabled = not (cp.vl["Cruise_Status"]["Cruise_State"] in (0, 3)) ret.cruiseState.available = cp.vl["Cruise_Status"]["Cruise_State"] != 0 ret.gas = cp.vl["EngineData_14"]["ApedPosScal_Pc_Actl"] / 100. ret.gasPressed = ret.gas > 1e-6 @@ -39,20 +39,20 @@ class CarState(CarStateBase): @staticmethod def get_can_parser(CP): signals = [ - # sig_name, sig_address, default - ("WhlRr_W_Meas", "WheelSpeed_CG1", 0.), - ("WhlRl_W_Meas", "WheelSpeed_CG1", 0.), - ("WhlFr_W_Meas", "WheelSpeed_CG1", 0.), - ("WhlFl_W_Meas", "WheelSpeed_CG1", 0.), - ("SteWhlRelInit_An_Sns", "Steering_Wheel_Data_CG1", 0.), - ("Cruise_State", "Cruise_Status", 0.), - ("Set_Speed", "Cruise_Status", 0.), - ("LaActAvail_D_Actl", "Lane_Keep_Assist_Status", 0), - ("LaHandsOff_B_Actl", "Lane_Keep_Assist_Status", 0), - ("LaActDeny_B_Actl", "Lane_Keep_Assist_Status", 0), - ("ApedPosScal_Pc_Actl", "EngineData_14", 0.), - ("Dist_Incr", "Steering_Buttons", 0.), - ("Brake_Drv_Appl", "Cruise_Status", 0.), + # sig_name, sig_address + ("WhlRr_W_Meas", "WheelSpeed_CG1"), + ("WhlRl_W_Meas", "WheelSpeed_CG1"), + ("WhlFr_W_Meas", "WheelSpeed_CG1"), + ("WhlFl_W_Meas", "WheelSpeed_CG1"), + ("SteWhlRelInit_An_Sns", "Steering_Wheel_Data_CG1"), + ("Cruise_State", "Cruise_Status"), + ("Set_Speed", "Cruise_Status"), + ("LaActAvail_D_Actl", "Lane_Keep_Assist_Status"), + ("LaHandsOff_B_Actl", "Lane_Keep_Assist_Status"), + ("LaActDeny_B_Actl", "Lane_Keep_Assist_Status"), + ("ApedPosScal_Pc_Actl", "EngineData_14"), + ("Dist_Incr", "Steering_Buttons"), + ("Brake_Drv_Appl", "Cruise_Status"), ] checks = [] return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 0, enforce_checks=False) diff --git a/selfdrive/car/ford/fordcan.py b/selfdrive/car/ford/fordcan.py index e98dec584..5a8b0b2de 100644 --- a/selfdrive/car/ford/fordcan.py +++ b/selfdrive/car/ford/fordcan.py @@ -6,7 +6,7 @@ def create_steer_command(packer, angle_cmd, enabled, lkas_state, angle_steers, c """Creates a CAN message for the Ford Steer Command.""" #if enabled and lkas available: - if enabled and lkas_state in [2, 3]: # and (frame % 500) >= 3: + if enabled and lkas_state in (2, 3): # and (frame % 500) >= 3: action = lkas_action else: action = 0xf diff --git a/selfdrive/car/ford/interface.py b/selfdrive/car/ford/interface.py index 8c0b1e1fa..0faaa3f66 100755 --- a/selfdrive/car/ford/interface.py +++ b/selfdrive/car/ford/interface.py @@ -21,7 +21,7 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.01], [0.005]] # TODO: tune this ret.lateralTuning.pid.kf = 1. / MAX_ANGLE # MAX Steer angle to normalize FF ret.steerActuatorDelay = 0.1 # Default delay, not measured yet - ret.steerLimitTimer = 0.8 + ret.steerLimitTimer = 1.0 ret.steerRateCost = 1.0 ret.centerToFront = ret.wheelbase * 0.44 tire_stiffness_factor = 0.5328 @@ -51,7 +51,7 @@ class CarInterface(CarInterfaceBase): # events events = self.create_common_events(ret) - if self.CS.lkas_state not in [2, 3] and ret.vEgo > 13. * CV.MPH_TO_MS and ret.cruiseState.enabled: + if self.CS.lkas_state not in (2, 3) and ret.vEgo > 13. * CV.MPH_TO_MS and ret.cruiseState.enabled: events.add(car.CarEvent.EventName.steerTempUnavailable) ret.events = events.to_msg() @@ -63,8 +63,8 @@ class CarInterface(CarInterfaceBase): # to be called @ 100hz def apply(self, c): - can_sends = self.CC.update(c.enabled, self.CS, self.frame, c.actuators, + ret = self.CC.update(c.enabled, self.CS, self.frame, c.actuators, c.hudControl.visualAlert, c.cruiseControl.cancel) self.frame += 1 - return can_sends + return ret diff --git a/selfdrive/car/ford/radar_interface.py b/selfdrive/car/ford/radar_interface.py index 20a435b08..94eb8bb0c 100755 --- a/selfdrive/car/ford/radar_interface.py +++ b/selfdrive/car/ford/radar_interface.py @@ -7,12 +7,12 @@ from selfdrive.car.interfaces import RadarInterfaceBase RADAR_MSGS = list(range(0x500, 0x540)) + def _create_radar_can_parser(car_fingerprint): msg_n = len(RADAR_MSGS) signals = list(zip(['X_Rel'] * msg_n + ['Angle'] * msg_n + ['V_Rel'] * msg_n, - RADAR_MSGS * 3, - [0] * msg_n + [0] * msg_n + [0] * msg_n)) - checks = list(zip(RADAR_MSGS, [20]*msg_n)) + RADAR_MSGS * 3)) + checks = list(zip(RADAR_MSGS, [20] * msg_n)) return CANParser(DBC[car_fingerprint]['radar'], signals, checks, 1) diff --git a/selfdrive/car/ford/values.py b/selfdrive/car/ford/values.py index 7c6cc6d2d..e1e220647 100644 --- a/selfdrive/car/ford/values.py +++ b/selfdrive/car/ford/values.py @@ -1,5 +1,3 @@ -# flake8: noqa - from selfdrive.car import dbc_dict from cereal import car Ecu = car.CarParams.Ecu diff --git a/selfdrive/car/fw_versions.py b/selfdrive/car/fw_versions.py index 5d982d6a8..59fd4fe8a 100755 --- a/selfdrive/car/fw_versions.py +++ b/selfdrive/car/fw_versions.py @@ -84,8 +84,21 @@ NISSAN_VERSION_RESPONSE_STANDARD = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIF NISSAN_RX_OFFSET = 0x20 +SUBARU_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \ + p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_DATA_IDENTIFICATION) +SUBARU_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \ + p16(uds.DATA_IDENTIFIER_TYPE.APPLICATION_DATA_IDENTIFICATION) + + # brand, request, response, response offset REQUESTS = [ + # Subaru + ( + "subaru", + [TESTER_PRESENT_REQUEST, SUBARU_VERSION_REQUEST], + [TESTER_PRESENT_RESPONSE, SUBARU_VERSION_RESPONSE], + DEFAULT_RX_OFFSET, + ), # Hyundai ( "hyundai", @@ -221,7 +234,7 @@ def match_fw_to_car_fuzzy(fw_versions_dict, log=True, exclude=None): if match_count >= 2: if log: cloudlog.error(f"Fingerprinted {candidate} using fuzzy match. {match_count} matching ECUs") - return set([candidate]) + return {candidate} else: return set() @@ -240,11 +253,11 @@ def match_fw_to_car_exact(fw_versions_dict): addr = ecu[1:] found_version = fw_versions_dict.get(addr, None) ESSENTIAL_ECUS = [Ecu.engine, Ecu.eps, Ecu.esp, Ecu.fwdRadar, Ecu.fwdCamera, Ecu.vsa] - if ecu_type == Ecu.esp and candidate in [TOYOTA.RAV4, TOYOTA.COROLLA, TOYOTA.HIGHLANDER, TOYOTA.SIENNA, TOYOTA.LEXUS_IS] and found_version is None: + if ecu_type == Ecu.esp and candidate in (TOYOTA.RAV4, TOYOTA.COROLLA, TOYOTA.HIGHLANDER, TOYOTA.SIENNA, TOYOTA.LEXUS_IS) and found_version is None: continue # On some Toyota models, the engine can show on two different addresses - if ecu_type == Ecu.engine and candidate in [TOYOTA.CAMRY, TOYOTA.COROLLA_TSS2, TOYOTA.CHR, TOYOTA.LEXUS_IS] and found_version is None: + if ecu_type == Ecu.engine and candidate in (TOYOTA.CAMRY, TOYOTA.COROLLA_TSS2, TOYOTA.CHR, TOYOTA.LEXUS_IS) and found_version is None: continue # Ignore non essential ecus @@ -362,7 +375,7 @@ if __name__ == "__main__": print("Getting vin...") addr, vin = get_vin(logcan, sendcan, 1, retry=10, debug=args.debug) print(f"VIN: {vin}") - print("Getting VIN took %.3f s" % (time.time() - t)) + print(f"Getting VIN took {time.time() - t:.3f} s") print() t = time.time() @@ -379,4 +392,4 @@ if __name__ == "__main__": print() print("Possible matches:", candidates) - print("Getting fw took %.3f s" % (time.time() - t)) + print(f"Getting fw took {time.time() - t:.3f} s") diff --git a/selfdrive/car/gm/carcontroller.py b/selfdrive/car/gm/carcontroller.py index 8f4d0f27c..7ad1e7cf8 100644 --- a/selfdrive/car/gm/carcontroller.py +++ b/selfdrive/car/gm/carcontroller.py @@ -14,6 +14,9 @@ class CarController(): def __init__(self, dbc_name, CP, VM): self.start_time = 0. self.apply_steer_last = 0 + self.apply_gas = 0 + self.apply_brake = 0 + self.lka_steering_cmd_counter_last = -1 self.lka_icon_status_last = (False, False) self.steer_rate_limited = False @@ -24,7 +27,7 @@ class CarController(): self.packer_obj = CANPacker(DBC[CP.carFingerprint]['radar']) self.packer_ch = CANPacker(DBC[CP.carFingerprint]['chassis']) - def update(self, enabled, CS, frame, actuators, + def update(self, c, enabled, CS, frame, actuators, hud_v_cruise, hud_show_lanes, hud_show_car, hud_alert): P = self.params @@ -38,7 +41,7 @@ class CarController(): if CS.lka_steering_cmd_counter != self.lka_steering_cmd_counter_last: self.lka_steering_cmd_counter_last = CS.lka_steering_cmd_counter elif (frame % P.STEER_STEP) == 0: - lkas_enabled = enabled and not (CS.out.steerWarning or CS.out.steerError) and CS.out.vEgo > P.MIN_STEER_SPEED + lkas_enabled = c.active and not (CS.out.steerWarning or CS.out.steerError) and CS.out.vEgo > P.MIN_STEER_SPEED if lkas_enabled: new_steer = int(round(actuators.steer * P.STEER_MAX)) apply_steer = apply_std_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, P) @@ -53,22 +56,22 @@ class CarController(): can_sends.append(gmcan.create_steering_control(self.packer_pt, CanBus.POWERTRAIN, apply_steer, idx, lkas_enabled)) - if not enabled: - # Stock ECU sends max regen when not enabled. - apply_gas = P.MAX_ACC_REGEN - apply_brake = 0 - else: - apply_gas = int(round(interp(actuators.accel, P.GAS_LOOKUP_BP, P.GAS_LOOKUP_V))) - apply_brake = int(round(interp(actuators.accel, P.BRAKE_LOOKUP_BP, P.BRAKE_LOOKUP_V))) - # Gas/regen and brakes - all at 25Hz if (frame % 4) == 0: + if not c.active: + # Stock ECU sends max regen when not enabled. + self.apply_gas = P.MAX_ACC_REGEN + self.apply_brake = 0 + else: + self.apply_gas = int(round(interp(actuators.accel, P.GAS_LOOKUP_BP, P.GAS_LOOKUP_V))) + self.apply_brake = int(round(interp(actuators.accel, P.BRAKE_LOOKUP_BP, P.BRAKE_LOOKUP_V))) + idx = (frame // 4) % 4 at_full_stop = enabled and CS.out.standstill near_stop = enabled and (CS.out.vEgo < P.NEAR_STOP_BRAKE_PHASE) - can_sends.append(gmcan.create_friction_brake_command(self.packer_ch, CanBus.CHASSIS, apply_brake, idx, near_stop, at_full_stop)) - can_sends.append(gmcan.create_gas_regen_command(self.packer_pt, CanBus.POWERTRAIN, apply_gas, idx, enabled, at_full_stop)) + can_sends.append(gmcan.create_friction_brake_command(self.packer_ch, CanBus.CHASSIS, self.apply_brake, idx, near_stop, at_full_stop)) + can_sends.append(gmcan.create_gas_regen_command(self.packer_pt, CanBus.POWERTRAIN, self.apply_gas, idx, enabled, at_full_stop)) # Send dashboard UI commands (ACC status), 25hz if (frame % 4) == 0: @@ -102,8 +105,13 @@ class CarController(): lka_critical = lka_active and abs(actuators.steer) > 0.9 lka_icon_status = (lka_active, lka_critical) if frame % P.CAMERA_KEEPALIVE_STEP == 0 or lka_icon_status != self.lka_icon_status_last: - steer_alert = hud_alert in [VisualAlert.steerRequired, VisualAlert.ldw] + steer_alert = hud_alert in (VisualAlert.steerRequired, VisualAlert.ldw) can_sends.append(gmcan.create_lka_icon_command(CanBus.SW_GMLAN, lka_active, lka_critical, steer_alert)) self.lka_icon_status_last = lka_icon_status - return can_sends + new_actuators = actuators.copy() + new_actuators.steer = self.apply_steer_last / P.STEER_MAX + new_actuators.gas = self.apply_gas + new_actuators.brake = self.apply_brake + + return new_actuators, can_sends diff --git a/selfdrive/car/gm/carstate.py b/selfdrive/car/gm/carstate.py index e4d644834..4a6b75fa3 100644 --- a/selfdrive/car/gm/carstate.py +++ b/selfdrive/car/gm/carstate.py @@ -3,8 +3,7 @@ from common.numpy_fast import mean from opendbc.can.can_define import CANDefine from opendbc.can.parser import CANParser from selfdrive.car.interfaces import CarStateBase -from selfdrive.car.gm.values import DBC, CAR, AccState, CanBus, \ - CruiseButtons, STEER_THRESHOLD +from selfdrive.car.gm.values import DBC, CAR, AccState, CanBus, STEER_THRESHOLD class CarState(CarStateBase): @@ -31,12 +30,10 @@ class CarState(CarStateBase): ret.standstill = ret.vEgoRaw < 0.01 ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(pt_cp.vl["ECMPRDNL"]["PRNDL"], None)) + ret.brakePressed = pt_cp.vl["ECMEngineStatus"]["Brake_Pressed"] != 0 ret.brake = pt_cp.vl["EBCMBrakePedalPosition"]["BrakePedalPosition"] / 0xd0 - # Brake pedal's potentiometer returns near-zero reading even when pedal is not pressed. - if ret.brake < 10/0xd0: - ret.brake = 0. - ret.gas = pt_cp.vl["AcceleratorPedal"]["AcceleratorPedal"] / 254. + ret.gas = pt_cp.vl["AcceleratorPedal2"]["AcceleratorPedal2"] / 254. ret.gasPressed = ret.gas > 1e-5 ret.steeringAngleDeg = pt_cp.vl["PSCMSteeringAngle"]["SteeringWheelAngle"] @@ -63,14 +60,13 @@ class CarState(CarStateBase): ret.rightBlinker = pt_cp.vl["BCMTurnSignals"]["TurnSignals"] == 2 self.park_brake = pt_cp.vl["EPBStatus"]["EPBClosed"] - ret.cruiseState.available = bool(pt_cp.vl["ECMEngineStatus"]["CruiseMainOn"]) + ret.cruiseState.available = pt_cp.vl["ECMEngineStatus"]["CruiseMainOn"] != 0 ret.espDisabled = pt_cp.vl["ESPStatus"]["TractionControlOn"] != 1 self.pcm_acc_status = pt_cp.vl["AcceleratorPedal2"]["CruiseState"] - ret.brakePressed = ret.brake > 1e-5 # Regen braking is braking if self.car_fingerprint == CAR.VOLT: - ret.brakePressed = ret.brakePressed or bool(pt_cp.vl["EBCMRegenPaddle"]["RegenPaddle"]) + ret.brakePressed = ret.brakePressed or pt_cp.vl["EBCMRegenPaddle"]["RegenPaddle"] != 0 ret.cruiseState.enabled = self.pcm_acc_status != AccState.OFF ret.cruiseState.standstill = self.pcm_acc_status == AccState.STANDSTILL @@ -79,33 +75,33 @@ class CarState(CarStateBase): @staticmethod def get_can_parser(CP): - # this function generates lists for signal, messages and initial values signals = [ - # sig_name, sig_address, default - ("BrakePedalPosition", "EBCMBrakePedalPosition", 0), - ("FrontLeftDoor", "BCMDoorBeltStatus", 0), - ("FrontRightDoor", "BCMDoorBeltStatus", 0), - ("RearLeftDoor", "BCMDoorBeltStatus", 0), - ("RearRightDoor", "BCMDoorBeltStatus", 0), - ("LeftSeatBelt", "BCMDoorBeltStatus", 0), - ("RightSeatBelt", "BCMDoorBeltStatus", 0), - ("TurnSignals", "BCMTurnSignals", 0), - ("AcceleratorPedal", "AcceleratorPedal", 0), - ("CruiseState", "AcceleratorPedal2", 0), - ("ACCButtons", "ASCMSteeringButton", CruiseButtons.UNPRESS), - ("SteeringWheelAngle", "PSCMSteeringAngle", 0), - ("SteeringWheelRate", "PSCMSteeringAngle", 0), - ("FLWheelSpd", "EBCMWheelSpdFront", 0), - ("FRWheelSpd", "EBCMWheelSpdFront", 0), - ("RLWheelSpd", "EBCMWheelSpdRear", 0), - ("RRWheelSpd", "EBCMWheelSpdRear", 0), - ("PRNDL", "ECMPRDNL", 0), - ("LKADriverAppldTrq", "PSCMStatus", 0), - ("LKATorqueDelivered", "PSCMStatus", 0), - ("LKATorqueDeliveredStatus", "PSCMStatus", 0), - ("TractionControlOn", "ESPStatus", 0), - ("EPBClosed", "EPBStatus", 0), - ("CruiseMainOn", "ECMEngineStatus", 0), + # sig_name, sig_address + ("BrakePedalPosition", "EBCMBrakePedalPosition"), + ("FrontLeftDoor", "BCMDoorBeltStatus"), + ("FrontRightDoor", "BCMDoorBeltStatus"), + ("RearLeftDoor", "BCMDoorBeltStatus"), + ("RearRightDoor", "BCMDoorBeltStatus"), + ("LeftSeatBelt", "BCMDoorBeltStatus"), + ("RightSeatBelt", "BCMDoorBeltStatus"), + ("TurnSignals", "BCMTurnSignals"), + ("AcceleratorPedal2", "AcceleratorPedal2"), + ("CruiseState", "AcceleratorPedal2"), + ("ACCButtons", "ASCMSteeringButton"), + ("SteeringWheelAngle", "PSCMSteeringAngle"), + ("SteeringWheelRate", "PSCMSteeringAngle"), + ("FLWheelSpd", "EBCMWheelSpdFront"), + ("FRWheelSpd", "EBCMWheelSpdFront"), + ("RLWheelSpd", "EBCMWheelSpdRear"), + ("RRWheelSpd", "EBCMWheelSpdRear"), + ("PRNDL", "ECMPRDNL"), + ("LKADriverAppldTrq", "PSCMStatus"), + ("LKATorqueDelivered", "PSCMStatus"), + ("LKATorqueDeliveredStatus", "PSCMStatus"), + ("TractionControlOn", "ESPStatus"), + ("EPBClosed", "EPBStatus"), + ("CruiseMainOn", "ECMEngineStatus"), + ("Brake_Pressed", "ECMEngineStatus"), ] checks = [ @@ -117,7 +113,6 @@ class CarState(CarStateBase): ("EPBStatus", 20), ("EBCMWheelSpdFront", 20), ("EBCMWheelSpdRear", 20), - ("AcceleratorPedal", 33), ("AcceleratorPedal2", 33), ("ASCMSteeringButton", 33), ("ECMEngineStatus", 100), @@ -126,19 +121,15 @@ class CarState(CarStateBase): ] if CP.carFingerprint == CAR.VOLT: - signals += [ - ("RegenPaddle", "EBCMRegenPaddle", 0), - ] - checks += [ - ("EBCMRegenPaddle", 50), - ] + signals.append(("RegenPaddle", "EBCMRegenPaddle")) + checks.append(("EBCMRegenPaddle", 50)) return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, CanBus.POWERTRAIN) @staticmethod def get_loopback_can_parser(CP): signals = [ - ("RollingCounter", "ASCMLKASteeringCmd", 0), + ("RollingCounter", "ASCMLKASteeringCmd"), ] checks = [ diff --git a/selfdrive/car/gm/interface.py b/selfdrive/car/gm/interface.py index b06e5373a..d6a2d3cfe 100755 --- a/selfdrive/car/gm/interface.py +++ b/selfdrive/car/gm/interface.py @@ -44,6 +44,11 @@ class CarInterface(CarInterfaceBase): ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.gm)] ret.pcmCruise = False # stock cruise control is kept off + # These cars have been put into dashcam only due to both a lack of users and test coverage. + # These cars likely still work fine. Once a user confirms each car works and a test route is + # added to selfdrive/test/test_routes, we can remove it from this list. + ret.dashcamOnly = candidate in {CAR.CADILLAC_ATS, CAR.HOLDEN_ASTRA, CAR.MALIBU, CAR.BUICK_REGAL} + # Presence of a camera on the object bus is ok. # Have to go to read_only if ASCM is online (ACC-enabled cars), # or camera is on powertrain bus (LKA cars without ACC). @@ -198,7 +203,7 @@ class CarInterface(CarInterfaceBase): # handle button presses for b in ret.buttonEvents: # do enable on both accel and decel buttons - if b.type in [ButtonType.accelCruise, ButtonType.decelCruise] and not b.pressed: + if b.type in (ButtonType.accelCruise, ButtonType.decelCruise) and not b.pressed: events.add(EventName.buttonEnable) # do disable on button down if b.type == ButtonType.cancel and b.pressed: @@ -212,7 +217,8 @@ class CarInterface(CarInterfaceBase): return self.CS.out def apply(self, c): - hud_v_cruise = c.hudControl.setSpeed + hud_control = c.hudControl + hud_v_cruise = hud_control.setSpeed if hud_v_cruise > 70: hud_v_cruise = 0 @@ -220,10 +226,10 @@ class CarInterface(CarInterfaceBase): # In GM, PCM faults out if ACC command overlaps user gas. enabled = c.enabled and not self.CS.out.gasPressed - can_sends = self.CC.update(enabled, self.CS, self.frame, - c.actuators, - hud_v_cruise, c.hudControl.lanesVisible, - c.hudControl.leadVisible, c.hudControl.visualAlert) + ret = self.CC.update(c, enabled, self.CS, self.frame, + c.actuators, + hud_v_cruise, hud_control.lanesVisible, + hud_control.leadVisible, hud_control.visualAlert) self.frame += 1 - return can_sends + return ret diff --git a/selfdrive/car/gm/radar_interface.py b/selfdrive/car/gm/radar_interface.py index 4cb1e0781..66fac5474 100755 --- a/selfdrive/car/gm/radar_interface.py +++ b/selfdrive/car/gm/radar_interface.py @@ -1,5 +1,4 @@ #!/usr/bin/env python3 -from __future__ import print_function import math from cereal import car from opendbc.can.parser import CANParser @@ -15,6 +14,7 @@ NUM_SLOTS = 20 # messages that are present in DBC LAST_RADAR_MSG = RADAR_HEADER_MSG + NUM_SLOTS + def create_radar_can_parser(car_fingerprint): if car_fingerprint not in (CAR.VOLT, CAR.MALIBU, CAR.HOLDEN_ASTRA, CAR.ACADIA, CAR.CADILLAC_ATS, CAR.ESCALADE_ESV): return None @@ -22,17 +22,13 @@ def create_radar_can_parser(car_fingerprint): # C1A-ARS3-A by Continental radar_targets = list(range(SLOT_1_MSG, SLOT_1_MSG + NUM_SLOTS)) signals = list(zip(['FLRRNumValidTargets', - 'FLRRSnsrBlckd', 'FLRRYawRtPlsblityFlt', - 'FLRRHWFltPrsntInt', 'FLRRAntTngFltPrsnt', - 'FLRRAlgnFltPrsnt', 'FLRRSnstvFltPrsntInt'] + - ['TrkRange'] * NUM_SLOTS + ['TrkRangeRate'] * NUM_SLOTS + - ['TrkRangeAccel'] * NUM_SLOTS + ['TrkAzimuth'] * NUM_SLOTS + - ['TrkWidth'] * NUM_SLOTS + ['TrkObjectID'] * NUM_SLOTS, - [RADAR_HEADER_MSG] * 7 + radar_targets * 6, - [0] * 7 + - [0.0] * NUM_SLOTS + [0.0] * NUM_SLOTS + - [0.0] * NUM_SLOTS + [0.0] * NUM_SLOTS + - [0.0] * NUM_SLOTS + [0] * NUM_SLOTS)) + 'FLRRSnsrBlckd', 'FLRRYawRtPlsblityFlt', + 'FLRRHWFltPrsntInt', 'FLRRAntTngFltPrsnt', + 'FLRRAlgnFltPrsnt', 'FLRRSnstvFltPrsntInt'] + + ['TrkRange'] * NUM_SLOTS + ['TrkRangeRate'] * NUM_SLOTS + + ['TrkRangeAccel'] * NUM_SLOTS + ['TrkAzimuth'] * NUM_SLOTS + + ['TrkWidth'] * NUM_SLOTS + ['TrkObjectID'] * NUM_SLOTS, + [RADAR_HEADER_MSG] * 7 + radar_targets * 6)) checks = list({(s[1], 14) for s in signals}) diff --git a/selfdrive/car/gm/values.py b/selfdrive/car/gm/values.py index d475b4bd6..8e0907671 100644 --- a/selfdrive/car/gm/values.py +++ b/selfdrive/car/gm/values.py @@ -1,5 +1,3 @@ -# flake8: noqa - from cereal import car from selfdrive.car import dbc_dict Ecu = car.CarParams.Ecu @@ -115,11 +113,11 @@ FINGERPRINTS = { } DBC = { - CAR.HOLDEN_ASTRA: dbc_dict('gm_global_a_powertrain', 'gm_global_a_object', chassis_dbc='gm_global_a_chassis'), - CAR.VOLT: dbc_dict('gm_global_a_powertrain', 'gm_global_a_object', chassis_dbc='gm_global_a_chassis'), - CAR.MALIBU: dbc_dict('gm_global_a_powertrain', 'gm_global_a_object', chassis_dbc='gm_global_a_chassis'), - CAR.ACADIA: dbc_dict('gm_global_a_powertrain', 'gm_global_a_object', chassis_dbc='gm_global_a_chassis'), - CAR.CADILLAC_ATS: dbc_dict('gm_global_a_powertrain', 'gm_global_a_object', chassis_dbc='gm_global_a_chassis'), - CAR.BUICK_REGAL: dbc_dict('gm_global_a_powertrain', 'gm_global_a_object', chassis_dbc='gm_global_a_chassis'), - CAR.ESCALADE_ESV: dbc_dict('gm_global_a_powertrain', 'gm_global_a_object', chassis_dbc='gm_global_a_chassis'), + CAR.HOLDEN_ASTRA: dbc_dict('gm_global_a_powertrain_generated', 'gm_global_a_object', chassis_dbc='gm_global_a_chassis'), + CAR.VOLT: dbc_dict('gm_global_a_powertrain_generated', 'gm_global_a_object', chassis_dbc='gm_global_a_chassis'), + CAR.MALIBU: dbc_dict('gm_global_a_powertrain_generated', 'gm_global_a_object', chassis_dbc='gm_global_a_chassis'), + CAR.ACADIA: dbc_dict('gm_global_a_powertrain_generated', 'gm_global_a_object', chassis_dbc='gm_global_a_chassis'), + CAR.CADILLAC_ATS: dbc_dict('gm_global_a_powertrain_generated', 'gm_global_a_object', chassis_dbc='gm_global_a_chassis'), + CAR.BUICK_REGAL: dbc_dict('gm_global_a_powertrain_generated', 'gm_global_a_object', chassis_dbc='gm_global_a_chassis'), + CAR.ESCALADE_ESV: dbc_dict('gm_global_a_powertrain_generated', 'gm_global_a_object', chassis_dbc='gm_global_a_chassis'), } diff --git a/selfdrive/car/honda/carcontroller.py b/selfdrive/car/honda/carcontroller.py index e1488eda2..49581799a 100644 --- a/selfdrive/car/honda/carcontroller.py +++ b/selfdrive/car/honda/carcontroller.py @@ -83,7 +83,7 @@ def process_hud_alert(hud_alert): # priority is: FCW, steer required, all others if hud_alert == VisualAlert.fcw: fcw_display = VISUAL_HUD[hud_alert.raw] - elif hud_alert in [VisualAlert.steerRequired, VisualAlert.ldw]: + elif hud_alert in (VisualAlert.steerRequired, VisualAlert.ldw): steer_required = VISUAL_HUD[hud_alert.raw] else: acc_alert = VISUAL_HUD[hud_alert.raw] @@ -105,6 +105,11 @@ class CarController(): self.last_pump_ts = 0. self.packer = CANPacker(dbc_name) + self.accel = 0 + self.speed = 0 + self.gas = 0 + self.brake = 0 + self.params = CarControllerParams(CP) def update(self, enabled, active, CS, frame, actuators, pcm_cancel_cmd, @@ -112,7 +117,7 @@ class CarController(): P = self.params - if enabled: + if active: accel = actuators.accel gas, brake = compute_gas_brake(actuators.accel, CS.out.vEgo, CS.CP.carFingerprint) else: @@ -147,7 +152,7 @@ class CarController(): # steer torque is converted back to CAN reference (positive when steering right) apply_steer = int(interp(-actuators.steer * P.STEER_MAX, P.STEER_LOOKUP_BP, P.STEER_LOOKUP_V)) - lkas_active = enabled and not CS.steer_not_allowed + lkas_active = active and not CS.steer_not_allowed # Send CAN commands. can_sends = [] @@ -163,7 +168,6 @@ class CarController(): lkas_active, CS.CP.carFingerprint, idx, CS.CP.openpilotLongitudinalControl)) stopping = actuators.longControlState == LongCtrlState.stopping - starting = actuators.longControlState == LongCtrlState.starting # wind brake from air resistance decel at high speed wind_brake = interp(CS.out.vEgo, [0.0, 2.3, 35.0], [0.001, 0.002, 0.15]) @@ -211,10 +215,9 @@ class CarController(): ts = frame * DT_CTRL if CS.CP.carFingerprint in HONDA_BOSCH: - accel = clip(accel, P.BOSCH_ACCEL_MIN, P.BOSCH_ACCEL_MAX) - bosch_gas = interp(accel, P.BOSCH_GAS_LOOKUP_BP, P.BOSCH_GAS_LOOKUP_V) - can_sends.extend(hondacan.create_acc_commands(self.packer, enabled, active, accel, bosch_gas, idx, stopping, starting, CS.CP.carFingerprint)) - + self.accel = clip(accel, P.BOSCH_ACCEL_MIN, P.BOSCH_ACCEL_MAX) + self.gas = interp(accel, P.BOSCH_GAS_LOOKUP_BP, P.BOSCH_GAS_LOOKUP_V) + can_sends.extend(hondacan.create_acc_commands(self.packer, enabled, active, accel, self.gas, idx, stopping, CS.CP.carFingerprint)) else: apply_brake = clip(self.brake_last - wind_brake, 0.0, 1.0) apply_brake = int(clip(apply_brake * P.NIDEC_BRAKE_MAX, 0, P.NIDEC_BRAKE_MAX - 1)) @@ -224,6 +227,7 @@ class CarController(): can_sends.append(hondacan.create_brake_command(self.packer, apply_brake, pump_on, pcm_override, pcm_cancel_cmd, fcw_display, idx, CS.CP.carFingerprint, CS.stock_brake)) self.apply_brake_last = apply_brake + self.brake = apply_brake / P.NIDEC_BRAKE_MAX if CS.CP.enableGasInterceptor: # way too aggressive at low speed without this @@ -233,17 +237,28 @@ class CarController(): # Sending non-zero gas when OP is not enabled will cause the PCM not to respond to throttle as expected # when you do enable. if active: - apply_gas = clip(gas_mult * (gas - brake + wind_brake*3/4), 0., 1.) + self.gas = clip(gas_mult * (gas - brake + wind_brake*3/4), 0., 1.) else: - apply_gas = 0.0 - can_sends.append(create_gas_interceptor_command(self.packer, apply_gas, idx)) - - hud = HUDData(int(pcm_accel), int(round(hud_v_cruise)), hud_car, - hud_lanes, fcw_display, acc_alert, steer_required) + self.gas = 0.0 + can_sends.append(create_gas_interceptor_command(self.packer, self.gas, idx)) # Send dashboard UI commands. if (frame % 10) == 0: idx = (frame//10) % 4 + hud = HUDData(int(pcm_accel), int(round(hud_v_cruise)), hud_car, + hud_lanes, fcw_display, acc_alert, steer_required) can_sends.extend(hondacan.create_ui_commands(self.packer, CS.CP, pcm_speed, hud, CS.is_metric, idx, CS.stock_hud)) - return can_sends + if (CS.CP.openpilotLongitudinalControl) and (CS.CP.carFingerprint not in HONDA_BOSCH): + self.speed = pcm_speed + + if not CS.CP.enableGasInterceptor: + self.gas = pcm_accel / 0xc6 + + new_actuators = actuators.copy() + new_actuators.speed = self.speed + new_actuators.accel = self.accel + new_actuators.gas = self.gas + new_actuators.brake = self.brake + + return new_actuators, can_sends diff --git a/selfdrive/car/honda/carstate.py b/selfdrive/car/honda/carstate.py index 12a4ae4c2..0a56a02b9 100644 --- a/selfdrive/car/honda/carstate.py +++ b/selfdrive/car/honda/carstate.py @@ -11,34 +11,33 @@ TransmissionType = car.CarParams.TransmissionType def get_can_signals(CP, gearbox_msg, main_on_sig_msg): - # this function generates lists for signal, messages and initial values signals = [ - ("XMISSION_SPEED", "ENGINE_DATA", 0), - ("WHEEL_SPEED_FL", "WHEEL_SPEEDS", 0), - ("WHEEL_SPEED_FR", "WHEEL_SPEEDS", 0), - ("WHEEL_SPEED_RL", "WHEEL_SPEEDS", 0), - ("WHEEL_SPEED_RR", "WHEEL_SPEEDS", 0), - ("STEER_ANGLE", "STEERING_SENSORS", 0), - ("STEER_ANGLE_RATE", "STEERING_SENSORS", 0), - ("MOTOR_TORQUE", "STEER_MOTOR_TORQUE", 0), - ("STEER_TORQUE_SENSOR", "STEER_STATUS", 0), - ("LEFT_BLINKER", "SCM_FEEDBACK", 0), - ("RIGHT_BLINKER", "SCM_FEEDBACK", 0), - ("GEAR", gearbox_msg, 0), - ("SEATBELT_DRIVER_LAMP", "SEATBELT_STATUS", 1), - ("SEATBELT_DRIVER_LATCHED", "SEATBELT_STATUS", 0), - ("BRAKE_PRESSED", "POWERTRAIN_DATA", 0), - ("BRAKE_SWITCH", "POWERTRAIN_DATA", 0), - ("CRUISE_BUTTONS", "SCM_BUTTONS", 0), - ("ESP_DISABLED", "VSA_STATUS", 1), - ("USER_BRAKE", "VSA_STATUS", 0), - ("BRAKE_HOLD_ACTIVE", "VSA_STATUS", 0), - ("STEER_STATUS", "STEER_STATUS", 5), - ("GEAR_SHIFTER", gearbox_msg, 0), - ("PEDAL_GAS", "POWERTRAIN_DATA", 0), - ("CRUISE_SETTING", "SCM_BUTTONS", 0), - ("ACC_STATUS", "POWERTRAIN_DATA", 0), - ("MAIN_ON", main_on_sig_msg, 0), + ("XMISSION_SPEED", "ENGINE_DATA"), + ("WHEEL_SPEED_FL", "WHEEL_SPEEDS"), + ("WHEEL_SPEED_FR", "WHEEL_SPEEDS"), + ("WHEEL_SPEED_RL", "WHEEL_SPEEDS"), + ("WHEEL_SPEED_RR", "WHEEL_SPEEDS"), + ("STEER_ANGLE", "STEERING_SENSORS"), + ("STEER_ANGLE_RATE", "STEERING_SENSORS"), + ("MOTOR_TORQUE", "STEER_MOTOR_TORQUE"), + ("STEER_TORQUE_SENSOR", "STEER_STATUS"), + ("LEFT_BLINKER", "SCM_FEEDBACK"), + ("RIGHT_BLINKER", "SCM_FEEDBACK"), + ("GEAR", gearbox_msg), + ("SEATBELT_DRIVER_LAMP", "SEATBELT_STATUS"), + ("SEATBELT_DRIVER_LATCHED", "SEATBELT_STATUS"), + ("BRAKE_PRESSED", "POWERTRAIN_DATA"), + ("BRAKE_SWITCH", "POWERTRAIN_DATA"), + ("CRUISE_BUTTONS", "SCM_BUTTONS"), + ("ESP_DISABLED", "VSA_STATUS"), + ("USER_BRAKE", "VSA_STATUS"), + ("BRAKE_HOLD_ACTIVE", "VSA_STATUS"), + ("STEER_STATUS", "STEER_STATUS"), + ("GEAR_SHIFTER", gearbox_msg), + ("PEDAL_GAS", "POWERTRAIN_DATA"), + ("CRUISE_SETTING", "SCM_BUTTONS"), + ("ACC_STATUS", "POWERTRAIN_DATA"), + ("MAIN_ON", main_on_sig_msg), ] checks = [ @@ -65,22 +64,18 @@ def get_can_signals(CP, gearbox_msg, main_on_sig_msg): ] if CP.carFingerprint in (CAR.CRV_HYBRID, CAR.CIVIC_BOSCH_DIESEL, CAR.ACURA_RDX_3G, CAR.HONDA_E): - checks += [ - (gearbox_msg, 50), - ] + checks.append((gearbox_msg, 50)) else: - checks += [ - (gearbox_msg, 100), - ] + checks.append((gearbox_msg, 100)) if CP.carFingerprint in HONDA_BOSCH_ALT_BRAKE_SIGNAL: - signals += [("BRAKE_PRESSED", "BRAKE_MODULE", 0)] - checks += [("BRAKE_MODULE", 50)] + signals.append(("BRAKE_PRESSED", "BRAKE_MODULE")) + checks.append(("BRAKE_MODULE", 50)) if CP.carFingerprint in HONDA_BOSCH: signals += [ - ("EPB_STATE", "EPB_STATUS", 0), - ("IMPERIAL_UNIT", "CAR_SPEED", 1), + ("EPB_STATE", "EPB_STATUS"), + ("IMPERIAL_UNIT", "CAR_SPEED"), ] checks += [ ("EPB_STATUS", 50), @@ -89,65 +84,65 @@ def get_can_signals(CP, gearbox_msg, main_on_sig_msg): if not CP.openpilotLongitudinalControl: signals += [ - ("CRUISE_CONTROL_LABEL", "ACC_HUD", 0), - ("CRUISE_SPEED", "ACC_HUD", 0), - ("ACCEL_COMMAND", "ACC_CONTROL", 0), - ("AEB_STATUS", "ACC_CONTROL", 0), + ("CRUISE_CONTROL_LABEL", "ACC_HUD"), + ("CRUISE_SPEED", "ACC_HUD"), + ("ACCEL_COMMAND", "ACC_CONTROL"), + ("AEB_STATUS", "ACC_CONTROL"), ] checks += [ ("ACC_HUD", 10), ("ACC_CONTROL", 50), ] else: # Nidec signals - signals += [("CRUISE_SPEED_PCM", "CRUISE", 0), - ("CRUISE_SPEED_OFFSET", "CRUISE_PARAMS", 0)] + signals += [("CRUISE_SPEED_PCM", "CRUISE"), + ("CRUISE_SPEED_OFFSET", "CRUISE_PARAMS")] if CP.carFingerprint == CAR.ODYSSEY_CHN: - checks += [("CRUISE_PARAMS", 10)] + checks.append(("CRUISE_PARAMS", 10)) else: - checks += [("CRUISE_PARAMS", 50)] + checks.append(("CRUISE_PARAMS", 50)) if CP.carFingerprint in (CAR.ACCORD, CAR.ACCORDH, CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_HYBRID, CAR.INSIGHT, CAR.ACURA_RDX_3G, CAR.HONDA_E): - signals += [("DRIVERS_DOOR_OPEN", "SCM_FEEDBACK", 1)] + signals.append(("DRIVERS_DOOR_OPEN", "SCM_FEEDBACK")) elif CP.carFingerprint == CAR.ODYSSEY_CHN: - signals += [("DRIVERS_DOOR_OPEN", "SCM_BUTTONS", 1)] + signals.append(("DRIVERS_DOOR_OPEN", "SCM_BUTTONS")) elif CP.carFingerprint in (CAR.FREED, CAR.HRV): - signals += [("DRIVERS_DOOR_OPEN", "SCM_BUTTONS", 1), - ("WHEELS_MOVING", "STANDSTILL", 1)] + signals += [("DRIVERS_DOOR_OPEN", "SCM_BUTTONS"), + ("WHEELS_MOVING", "STANDSTILL")] else: - signals += [("DOOR_OPEN_FL", "DOORS_STATUS", 1), - ("DOOR_OPEN_FR", "DOORS_STATUS", 1), - ("DOOR_OPEN_RL", "DOORS_STATUS", 1), - ("DOOR_OPEN_RR", "DOORS_STATUS", 1), - ("WHEELS_MOVING", "STANDSTILL", 1)] + signals += [("DOOR_OPEN_FL", "DOORS_STATUS"), + ("DOOR_OPEN_FR", "DOORS_STATUS"), + ("DOOR_OPEN_RL", "DOORS_STATUS"), + ("DOOR_OPEN_RR", "DOORS_STATUS"), + ("WHEELS_MOVING", "STANDSTILL")] checks += [ ("DOORS_STATUS", 3), ("STANDSTILL", 50), ] if CP.carFingerprint == CAR.CIVIC: - signals += [("IMPERIAL_UNIT", "HUD_SETTING", 0), - ("EPB_STATE", "EPB_STATUS", 0)] + signals += [("IMPERIAL_UNIT", "HUD_SETTING"), + ("EPB_STATE", "EPB_STATUS")] checks += [ ("HUD_SETTING", 50), ("EPB_STATUS", 50), ] elif CP.carFingerprint in (CAR.ODYSSEY, CAR.ODYSSEY_CHN): - signals += [("EPB_STATE", "EPB_STATUS", 0)] - checks += [("EPB_STATUS", 50)] + signals.append(("EPB_STATE", "EPB_STATUS")) + checks.append(("EPB_STATUS", 50)) # add gas interceptor reading if we are using it if CP.enableGasInterceptor: - signals.append(("INTERCEPTOR_GAS", "GAS_SENSOR", 0)) - signals.append(("INTERCEPTOR_GAS2", "GAS_SENSOR", 0)) + signals.append(("INTERCEPTOR_GAS", "GAS_SENSOR")) + signals.append(("INTERCEPTOR_GAS2", "GAS_SENSOR")) checks.append(("GAS_SENSOR", 50)) if CP.openpilotLongitudinalControl: signals += [ - ("BRAKE_ERROR_1", "STANDSTILL", 1), - ("BRAKE_ERROR_2", "STANDSTILL", 1) + ("BRAKE_ERROR_1", "STANDSTILL"), + ("BRAKE_ERROR_2", "STANDSTILL") ] - checks += [("STANDSTILL", 50)] + checks.append(("STANDSTILL", 50)) return signals, checks @@ -167,8 +162,9 @@ class CarState(CarStateBase): self.shifter_values = can_define.dv[self.gearbox_msg]["GEAR_SHIFTER"] self.steer_status_values = defaultdict(lambda: "UNKNOWN", can_define.dv["STEER_STATUS"]["STEER_STATUS"]) - self.brake_switch_prev = 0 - self.brake_switch_prev_ts = 0 + self.brake_error = False + self.brake_switch_prev = False + self.brake_switch_active = False self.cruise_setting = 0 self.v_cruise_pcm_prev = 0 @@ -201,15 +197,13 @@ class CarState(CarStateBase): ret.seatbeltUnlatched = bool(cp.vl["SEATBELT_STATUS"]["SEATBELT_DRIVER_LAMP"] or not cp.vl["SEATBELT_STATUS"]["SEATBELT_DRIVER_LATCHED"]) steer_status = self.steer_status_values[cp.vl["STEER_STATUS"]["STEER_STATUS"]] - ret.steerError = steer_status not in ["NORMAL", "NO_TORQUE_ALERT_1", "NO_TORQUE_ALERT_2", "LOW_SPEED_LOCKOUT", "TMP_FAULT"] + ret.steerError = steer_status not in ("NORMAL", "NO_TORQUE_ALERT_1", "NO_TORQUE_ALERT_2", "LOW_SPEED_LOCKOUT", "TMP_FAULT") # NO_TORQUE_ALERT_2 can be caused by bump OR steering nudge from driver - self.steer_not_allowed = steer_status not in ["NORMAL", "NO_TORQUE_ALERT_2"] + self.steer_not_allowed = steer_status not in ("NORMAL", "NO_TORQUE_ALERT_2") # LOW_SPEED_LOCKOUT is not worth a warning - ret.steerWarning = steer_status not in ["NORMAL", "LOW_SPEED_LOCKOUT", "NO_TORQUE_ALERT_2"] + ret.steerWarning = steer_status not in ("NORMAL", "LOW_SPEED_LOCKOUT", "NO_TORQUE_ALERT_2") - if not self.CP.openpilotLongitudinalControl: - self.brake_error = 0 - else: + if self.CP.openpilotLongitudinalControl: self.brake_error = cp.vl["STANDSTILL"]["BRAKE_ERROR_1"] or cp.vl["STANDSTILL"]["BRAKE_ERROR_2"] ret.espDisabled = cp.vl["VSA_STATUS"]["ESP_DISABLED"] != 0 @@ -245,15 +239,11 @@ class CarState(CarStateBase): gear = int(cp.vl[self.gearbox_msg]["GEAR_SHIFTER"]) ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(gear, None)) - ret.gas = cp.vl["POWERTRAIN_DATA"]["PEDAL_GAS"] - - # this is a hack for the interceptor. This is now only used in the simulation - # TODO: Replace tests by toyota so this can go away if self.CP.enableGasInterceptor: - user_gas = (cp.vl["GAS_SENSOR"]["INTERCEPTOR_GAS"] + cp.vl["GAS_SENSOR"]["INTERCEPTOR_GAS2"]) / 2. - ret.gasPressed = user_gas > 1e-5 # this works because interceptor reads < 0 when pedal position is 0. Once calibrated, this will change + ret.gas = (cp.vl["GAS_SENSOR"]["INTERCEPTOR_GAS"] + cp.vl["GAS_SENSOR"]["INTERCEPTOR_GAS2"]) / 2. else: - ret.gasPressed = ret.gas > 1e-5 + ret.gas = cp.vl["POWERTRAIN_DATA"]["PEDAL_GAS"] + ret.gasPressed = ret.gas > 1e-5 ret.steeringTorque = cp.vl["STEER_STATUS"]["STEER_TORQUE_SENSOR"] ret.steeringTorqueEps = cp.vl["STEER_MOTOR_TORQUE"]["MOTOR_TORQUE"] @@ -270,26 +260,28 @@ class CarState(CarStateBase): else: ret.cruiseState.speed = cp.vl["CRUISE"]["CRUISE_SPEED_PCM"] * CV.KPH_TO_MS - self.brake_switch = cp.vl["POWERTRAIN_DATA"]["BRAKE_SWITCH"] != 0 if self.CP.carFingerprint in HONDA_BOSCH_ALT_BRAKE_SIGNAL: ret.brakePressed = cp.vl["BRAKE_MODULE"]["BRAKE_PRESSED"] != 0 else: # brake switch has shown some single time step noise, so only considered when # switch is on for at least 2 consecutive CAN samples - # panda safety only checks BRAKE_PRESSED signal - ret.brakePressed = bool(cp.vl["POWERTRAIN_DATA"]["BRAKE_PRESSED"] or - (self.brake_switch and self.brake_switch_prev and cp.ts["POWERTRAIN_DATA"]["BRAKE_SWITCH"] != self.brake_switch_prev_ts)) - - self.brake_switch_prev = self.brake_switch - self.brake_switch_prev_ts = cp.ts["POWERTRAIN_DATA"]["BRAKE_SWITCH"] + # brake switch rises earlier than brake pressed but is never 1 when in park + brake_switch_vals = cp.vl_all["POWERTRAIN_DATA"]["BRAKE_SWITCH"] + if len(brake_switch_vals): + brake_switch = cp.vl["POWERTRAIN_DATA"]["BRAKE_SWITCH"] != 0 + if len(brake_switch_vals) > 1: + self.brake_switch_prev = brake_switch_vals[-2] != 0 + self.brake_switch_active = brake_switch and self.brake_switch_prev + self.brake_switch_prev = brake_switch + ret.brakePressed = (cp.vl["POWERTRAIN_DATA"]["BRAKE_PRESSED"] != 0) or self.brake_switch_active ret.brake = cp.vl["VSA_STATUS"]["USER_BRAKE"] ret.cruiseState.enabled = cp.vl["POWERTRAIN_DATA"]["ACC_STATUS"] != 0 ret.cruiseState.available = bool(cp.vl[self.main_on_sig_msg]["MAIN_ON"]) # Gets rid of Pedal Grinding noise when brake is pressed at slow speeds for some models - if self.CP.carFingerprint in (CAR.PILOT, CAR.PILOT_2019, CAR.PASSPORT, CAR.RIDGELINE): - if ret.brake > 0.05: + if self.CP.carFingerprint in (CAR.PILOT, CAR.PASSPORT, CAR.RIDGELINE): + if ret.brake > 0.1: ret.brakePressed = True # TODO: discover the CAN msg that has the imperial unit bit for all other cars @@ -334,14 +326,14 @@ class CarState(CarStateBase): ] if CP.carFingerprint not in HONDA_BOSCH: - signals += [("COMPUTER_BRAKE", "BRAKE_COMMAND", 0), - ("AEB_REQ_1", "BRAKE_COMMAND", 0), - ("FCW", "BRAKE_COMMAND", 0), - ("CHIME", "BRAKE_COMMAND", 0), - ("FCM_OFF", "ACC_HUD", 0), - ("FCM_OFF_2", "ACC_HUD", 0), - ("FCM_PROBLEM", "ACC_HUD", 0), - ("ICONS", "ACC_HUD", 0)] + signals += [("COMPUTER_BRAKE", "BRAKE_COMMAND"), + ("AEB_REQ_1", "BRAKE_COMMAND"), + ("FCW", "BRAKE_COMMAND"), + ("CHIME", "BRAKE_COMMAND"), + ("FCM_OFF", "ACC_HUD"), + ("FCM_OFF_2", "ACC_HUD"), + ("FCM_PROBLEM", "ACC_HUD"), + ("ICONS", "ACC_HUD")] checks += [ ("ACC_HUD", 10), ("BRAKE_COMMAND", 50), @@ -352,8 +344,8 @@ class CarState(CarStateBase): @staticmethod def get_body_can_parser(CP): if CP.enableBsm and CP.carFingerprint == CAR.CRV_5G: - signals = [("BSM_ALERT", "BSM_STATUS_RIGHT", 0), - ("BSM_ALERT", "BSM_STATUS_LEFT", 0)] + signals = [("BSM_ALERT", "BSM_STATUS_RIGHT"), + ("BSM_ALERT", "BSM_STATUS_LEFT")] checks = [ ("BSM_STATUS_LEFT", 3), diff --git a/selfdrive/car/honda/hondacan.py b/selfdrive/car/honda/hondacan.py index 7fcafe67f..db7104cd4 100644 --- a/selfdrive/car/honda/hondacan.py +++ b/selfdrive/car/honda/hondacan.py @@ -43,7 +43,7 @@ def create_brake_command(packer, apply_brake, pump_on, pcm_override, pcm_cancel_ return packer.make_can_msg("BRAKE_COMMAND", bus, values, idx) -def create_acc_commands(packer, enabled, active, accel, gas, idx, stopping, starting, car_fingerprint): +def create_acc_commands(packer, enabled, active, accel, gas, idx, stopping, car_fingerprint): commands = [] bus = get_pt_bus(car_fingerprint) min_gas_accel = CarControllerParams.BOSCH_GAS_LOOKUP_BP[0] @@ -53,7 +53,7 @@ def create_acc_commands(packer, enabled, active, accel, gas, idx, stopping, star accel_command = accel if active else 0 braking = 1 if active and accel < min_gas_accel else 0 standstill = 1 if active and stopping else 0 - standstill_release = 1 if active and starting else 0 + standstill_release = 1 if active and not stopping else 0 acc_control_values = { # setting CONTROL_ON causes car to set POWERTRAIN_DATA->ACC_STATUS = 1 diff --git a/selfdrive/car/honda/interface.py b/selfdrive/car/honda/interface.py index 03074b875..94e430590 100755 --- a/selfdrive/car/honda/interface.py +++ b/selfdrive/car/honda/interface.py @@ -47,7 +47,6 @@ class CarInterface(CarInterfaceBase): ret.openpilotLongitudinalControl = True ret.pcmCruise = not ret.enableGasInterceptor - ret.communityFeature = ret.enableGasInterceptor if candidate == CAR.CRV_5G: ret.enableBsm = 0x12f8bfa7 in fingerprint[0] @@ -227,7 +226,7 @@ class CarInterface(CarInterfaceBase): ret.centerToFront = ret.wheelbase * 0.41 ret.steerRatio = 11.95 # as spec ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 3840], [0, 3840]] - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.18]] + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2], [0.06]] tire_stiffness_factor = 0.677 elif candidate == CAR.ODYSSEY: @@ -250,17 +249,7 @@ class CarInterface(CarInterfaceBase): tire_stiffness_factor = 0.82 ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.28], [0.08]] - elif candidate in (CAR.PILOT, CAR.PILOT_2019): - stop_and_go = False - ret.mass = 4204. * CV.LB_TO_KG + STD_CARGO_KG # average weight - ret.wheelbase = 2.82 - ret.centerToFront = ret.wheelbase * 0.428 - ret.steerRatio = 17.25 # as spec - ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end - tire_stiffness_factor = 0.444 - ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.38], [0.11]] - - elif candidate == CAR.PASSPORT: + elif candidate in (CAR.PILOT, CAR.PASSPORT): stop_and_go = False ret.mass = 4204. * CV.LB_TO_KG + STD_CARGO_KG # average weight ret.wheelbase = 2.82 @@ -301,7 +290,7 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.18]] # TODO: can probably use some tuning else: - raise ValueError("unsupported car %s" % candidate) + raise ValueError(f"unsupported car {candidate}") # These cars use alternate user brake msg (0x1BE) if candidate in HONDA_BOSCH_ALT_BRAKE_SIGNAL: @@ -350,7 +339,6 @@ class CarInterface(CarInterfaceBase): ret = self.CS.update(self.cp, self.cp_cam, self.cp_body) ret.canValid = self.cp.can_valid and self.cp_cam.can_valid and (self.cp_body is None or self.cp_body.can_valid) - ret.yawRate = self.VM.yaw_rate(ret.steeringAngleDeg * CV.DEG_TO_RAD, ret.vEgo) buttonEvents = [] @@ -417,7 +405,7 @@ class CarInterface(CarInterfaceBase): for b in ret.buttonEvents: # do enable on both accel and decel buttons - if b.type in [ButtonType.accelCruise, ButtonType.decelCruise] and not b.pressed: + if b.type in (ButtonType.accelCruise, ButtonType.decelCruise) and not b.pressed: if not self.CP.pcmCruise: events.add(EventName.buttonEnable) @@ -433,18 +421,19 @@ class CarInterface(CarInterfaceBase): # pass in a car.CarControl # to be called @ 100hz def apply(self, c): - if c.hudControl.speedVisible: - hud_v_cruise = c.hudControl.setSpeed * CV.MS_TO_KPH + hud_control = c.hudControl + if hud_control.speedVisible: + hud_v_cruise = hud_control.setSpeed * CV.MS_TO_KPH else: hud_v_cruise = 255 - can_sends = self.CC.update(c.enabled, c.active, self.CS, self.frame, - c.actuators, - c.cruiseControl.cancel, - hud_v_cruise, - c.hudControl.lanesVisible, - hud_show_car=c.hudControl.leadVisible, - hud_alert=c.hudControl.visualAlert) + ret = self.CC.update(c.enabled, c.active, self.CS, self.frame, + c.actuators, + c.cruiseControl.cancel, + hud_v_cruise, + hud_control.lanesVisible, + hud_show_car=hud_control.leadVisible, + hud_alert=hud_control.visualAlert) self.frame += 1 - return can_sends + return ret diff --git a/selfdrive/car/honda/radar_interface.py b/selfdrive/car/honda/radar_interface.py index 45e015af6..629ab01d4 100755 --- a/selfdrive/car/honda/radar_interface.py +++ b/selfdrive/car/honda/radar_interface.py @@ -4,13 +4,13 @@ from opendbc.can.parser import CANParser from selfdrive.car.interfaces import RadarInterfaceBase from selfdrive.car.honda.values import DBC + def _create_nidec_can_parser(car_fingerprint): radar_messages = [0x400] + list(range(0x430, 0x43A)) + list(range(0x440, 0x446)) signals = list(zip(['RADAR_STATE'] + - ['LONG_DIST'] * 16 + ['NEW_TRACK'] * 16 + ['LAT_DIST'] * 16 + - ['REL_SPEED'] * 16, - [0x400] + radar_messages[1:] * 4, - [0] + [255] * 16 + [1] * 16 + [0] * 16 + [0] * 16)) + ['LONG_DIST'] * 16 + ['NEW_TRACK'] * 16 + ['LAT_DIST'] * 16 + + ['REL_SPEED'] * 16, + [0x400] + radar_messages[1:] * 4)) checks = [(s[1], 20) for s in signals] return CANParser(DBC[car_fingerprint]['radar'], signals, checks, 1) diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py index 083a52bb8..50ea52faa 100644 --- a/selfdrive/car/honda/values.py +++ b/selfdrive/car/honda/values.py @@ -82,7 +82,6 @@ class CAR: ACURA_RDX = "ACURA RDX 2018" ACURA_RDX_3G = "ACURA RDX 2020" PILOT = "HONDA PILOT 2017" - PILOT_2019 = "HONDA PILOT 2019" PASSPORT = "HONDA PASSPORT 2021" RIDGELINE = "HONDA RIDGELINE 2017" INSIGHT = "HONDA INSIGHT 2019" @@ -990,23 +989,44 @@ FW_VERSIONS = { b'37805-RLV-C530\x00\x00', b'37805-RLV-C910\x00\x00', ], + (Ecu.gateway, 0x18daeff1, None): [ + b'38897-TG7-A030\x00\x00', + b'38897-TG7-A040\x00\x00', + b'38897-TG7-A110\x00\x00', + b'38897-TG7-A210\x00\x00', + ], (Ecu.eps, 0x18da30f1, None): [ b'39990-TG7-A030\x00\x00', b'39990-TG7-A040\x00\x00', b'39990-TG7-A060\x00\x00', + b'39990-TG7-A070\x00\x00', + b'39990-TGS-A230\x00\x00', ], (Ecu.fwdCamera, 0x18dab0f1, None): [ + b'36161-TG7-A310\x00\x00', b'36161-TG7-A520\x00\x00', + b'36161-TG7-A630\x00\x00', b'36161-TG7-A720\x00\x00', b'36161-TG7-A820\x00\x00', + b'36161-TG7-A930\x00\x00', b'36161-TG7-C520\x00\x00', b'36161-TG7-D520\x00\x00', + b'36161-TG7-D630\x00\x00', + b'36161-TG7-Y630\x00\x00', b'36161-TG8-A520\x00\x00', + b'36161-TG8-A630\x00\x00', b'36161-TG8-A720\x00\x00', + b'36161-TG8-A830\x00\x00', + b'36161-TGS-A130\x00\x00', + b'36161-TGT-A030\x00\x00', + b'36161-TGT-A130\x00\x00', ], (Ecu.srs, 0x18da53f1, None): [ - b'77959-TG7-A110\x00\x00', b'77959-TG7-A020\x00\x00', + b'77959-TG7-A110\x00\x00', + b'77959-TG7-A210\x00\x00', + b'77959-TG7-Y210\x00\x00', + b'77959-TGS-A010\x00\x00', ], (Ecu.combinationMeter, 0x18da60f1, None): [ b'78109-TG7-A040\x00\x00', @@ -1014,50 +1034,6 @@ FW_VERSIONS = { b'78109-TG7-A420\x00\x00', b'78109-TG7-A520\x00\x00', b'78109-TG7-A720\x00\x00', - b'78109-TG7-D020\x00\x00', - b'78109-TG8-A420\x00\x00', - b'78109-TG8-A520\x00\x00', - ], - (Ecu.vsa, 0x18da28f1, None): [ - b'57114-TG7-A130\x00\x00', - b'57114-TG7-A140\x00\x00', - b'57114-TG7-A230\x00\x00', - b'57114-TG7-A240\x00\x00', - b'57114-TG8-A140\x00\x00', - b'57114-TG8-A240\x00\x00', - ], - - }, - CAR.PILOT_2019: { - (Ecu.eps, 0x18da30f1, None): [ - b'39990-TG7-A060\x00\x00', - b'39990-TG7-A070\x00\x00', - b'39990-TGS-A230\x00\x00', - ], - (Ecu.gateway, 0x18daeff1, None): [ - b'38897-TG7-A030\x00\x00', - b'38897-TG7-A040\x00\x00', - b'38897-TG7-A110\x00\x00', - b'38897-TG7-A210\x00\x00', - ], - (Ecu.fwdCamera, 0x18dab0f1, None): [ - b'36161-TG7-A310\x00\x00', - b'36161-TG7-A630\x00\x00', - b'36161-TG7-A930\x00\x00', - b'36161-TG7-D630\x00\x00', - b'36161-TG7-Y630\x00\x00', - b'36161-TG8-A630\x00\x00', - b'36161-TG8-A830\x00\x00', - b'36161-TGS-A130\x00\x00', - b'36161-TGT-A030\x00\x00', - b'36161-TGT-A130\x00\x00', - ], - (Ecu.srs, 0x18da53f1, None): [ - b'77959-TG7-A210\x00\x00', - b'77959-TG7-Y210\x00\x00', - b'77959-TGS-A010\x00\x00', - ], - (Ecu.combinationMeter, 0x18da60f1, None): [ b'78109-TG7-AJ10\x00\x00', b'78109-TG7-AJ20\x00\x00', b'78109-TG7-AK10\x00\x00', @@ -1069,8 +1045,11 @@ FW_VERSIONS = { b'78109-TG7-AT20\x00\x00', b'78109-TG7-AU20\x00\x00', b'78109-TG7-AX20\x00\x00', + b'78109-TG7-D020\x00\x00', b'78109-TG7-DJ10\x00\x00', b'78109-TG7-YK20\x00\x00', + b'78109-TG8-A420\x00\x00', + b'78109-TG8-A520\x00\x00', b'78109-TG8-AJ10\x00\x00', b'78109-TG8-AJ20\x00\x00', b'78109-TG8-AK20\x00\x00', @@ -1080,8 +1059,14 @@ FW_VERSIONS = { b'78109-TGT-AK30\x00\x00', ], (Ecu.vsa, 0x18da28f1, None): [ + b'57114-TG7-A130\x00\x00', + b'57114-TG7-A140\x00\x00', + b'57114-TG7-A230\x00\x00', + b'57114-TG7-A240\x00\x00', b'57114-TG7-A630\x00\x00', b'57114-TG7-A730\x00\x00', + b'57114-TG8-A140\x00\x00', + b'57114-TG8-A240\x00\x00', b'57114-TG8-A630\x00\x00', b'57114-TG8-A730\x00\x00', b'57114-TGS-A530\x00\x00', @@ -1361,20 +1346,19 @@ DBC = { CAR.ACURA_RDX_3G: dbc_dict('acura_rdx_2020_can_generated', None), CAR.CIVIC: dbc_dict('honda_civic_touring_2016_can_generated', 'acura_ilx_2016_nidec'), CAR.CIVIC_BOSCH: dbc_dict('honda_civic_hatchback_ex_2017_can_generated', None), - CAR.CIVIC_BOSCH_DIESEL: dbc_dict('honda_civic_sedan_16_diesel_2019_can_generated', None), + CAR.CIVIC_BOSCH_DIESEL: dbc_dict('honda_accord_2018_can_generated', None), CAR.CRV: dbc_dict('honda_crv_touring_2016_can_generated', 'acura_ilx_2016_nidec'), CAR.CRV_5G: dbc_dict('honda_crv_ex_2017_can_generated', None, body_dbc='honda_crv_ex_2017_body_generated'), CAR.CRV_EU: dbc_dict('honda_crv_executive_2016_can_generated', 'acura_ilx_2016_nidec'), - CAR.CRV_HYBRID: dbc_dict('honda_crv_hybrid_2019_can_generated', None), + CAR.CRV_HYBRID: dbc_dict('honda_accord_2018_can_generated', None), CAR.FIT: dbc_dict('honda_fit_ex_2018_can_generated', 'acura_ilx_2016_nidec'), CAR.FREED: dbc_dict('honda_fit_ex_2018_can_generated', 'acura_ilx_2016_nidec'), CAR.HRV: dbc_dict('honda_fit_ex_2018_can_generated', 'acura_ilx_2016_nidec'), CAR.ODYSSEY: dbc_dict('honda_odyssey_exl_2018_generated', 'acura_ilx_2016_nidec'), CAR.ODYSSEY_CHN: dbc_dict('honda_odyssey_extreme_edition_2018_china_can_generated', 'acura_ilx_2016_nidec'), - CAR.PILOT: dbc_dict('honda_pilot_touring_2017_can_generated', 'acura_ilx_2016_nidec'), - CAR.PILOT_2019: dbc_dict('honda_pilot_touring_2017_can_generated', 'acura_ilx_2016_nidec'), - CAR.PASSPORT: dbc_dict('honda_pilot_touring_2017_can_generated', 'acura_ilx_2016_nidec'), - CAR.RIDGELINE: dbc_dict('honda_ridgeline_black_edition_2017_can_generated', 'acura_ilx_2016_nidec'), + CAR.PILOT: dbc_dict('acura_ilx_2016_can_generated', 'acura_ilx_2016_nidec'), + CAR.PASSPORT: dbc_dict('acura_ilx_2016_can_generated', 'acura_ilx_2016_nidec'), + CAR.RIDGELINE: dbc_dict('acura_ilx_2016_can_generated', 'acura_ilx_2016_nidec'), CAR.INSIGHT: dbc_dict('honda_insight_ex_2019_can_generated', None), CAR.HONDA_E: dbc_dict('acura_rdx_2020_can_generated', None), } @@ -1385,9 +1369,9 @@ STEER_THRESHOLD = { CAR.CRV_EU: 400, } -HONDA_NIDEC_ALT_PCM_ACCEL = set([CAR.ODYSSEY]) -HONDA_NIDEC_ALT_SCM_MESSAGES = set([CAR.ACURA_ILX, CAR.ACURA_RDX, CAR.CRV, CAR.CRV_EU, CAR.FIT, CAR.FREED, CAR.HRV, CAR.ODYSSEY_CHN, - CAR.PILOT, CAR.PILOT_2019, CAR.PASSPORT, CAR.RIDGELINE]) -HONDA_BOSCH = set([CAR.ACCORD, CAR.ACCORDH, CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_5G, - CAR.CRV_HYBRID, CAR.INSIGHT, CAR.ACURA_RDX_3G, CAR.HONDA_E]) -HONDA_BOSCH_ALT_BRAKE_SIGNAL = set([CAR.ACCORD, CAR.CRV_5G, CAR.ACURA_RDX_3G]) +HONDA_NIDEC_ALT_PCM_ACCEL = {CAR.ODYSSEY} +HONDA_NIDEC_ALT_SCM_MESSAGES = {CAR.ACURA_ILX, CAR.ACURA_RDX, CAR.CRV, CAR.CRV_EU, CAR.FIT, CAR.FREED, CAR.HRV, CAR.ODYSSEY_CHN, + CAR.PILOT, CAR.PASSPORT, CAR.RIDGELINE} +HONDA_BOSCH = {CAR.ACCORD, CAR.ACCORDH, CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_5G, + CAR.CRV_HYBRID, CAR.INSIGHT, CAR.ACURA_RDX_3G, CAR.HONDA_E} +HONDA_BOSCH_ALT_BRAKE_SIGNAL = {CAR.ACCORD, CAR.CRV_5G, CAR.ACURA_RDX_3G} diff --git a/selfdrive/car/hyundai/carcontroller.py b/selfdrive/car/hyundai/carcontroller.py index a8b70fcf9..f7c43bd6e 100644 --- a/selfdrive/car/hyundai/carcontroller.py +++ b/selfdrive/car/hyundai/carcontroller.py @@ -13,7 +13,7 @@ LongCtrlState = car.CarControl.Actuators.LongControlState def process_hud_alert(enabled, fingerprint, visual_alert, left_lane, right_lane, left_lane_depart, right_lane_depart): - sys_warning = (visual_alert in [VisualAlert.steerRequired, VisualAlert.ldw]) + sys_warning = (visual_alert in (VisualAlert.steerRequired, VisualAlert.ldw)) # initialize to no line visible sys_state = 1 @@ -28,9 +28,9 @@ def process_hud_alert(enabled, fingerprint, visual_alert, left_lane, left_lane_warning = 0 right_lane_warning = 0 if left_lane_depart: - left_lane_warning = 1 if fingerprint in [CAR.GENESIS_G90, CAR.GENESIS_G80] else 2 + left_lane_warning = 1 if fingerprint in (CAR.GENESIS_G90, CAR.GENESIS_G80) else 2 if right_lane_depart: - right_lane_warning = 1 if fingerprint in [CAR.GENESIS_G90, CAR.GENESIS_G80] else 2 + right_lane_warning = 1 if fingerprint in (CAR.GENESIS_G90, CAR.GENESIS_G80) else 2 return sys_warning, sys_state, left_lane_warning, right_lane_warning @@ -44,8 +44,9 @@ class CarController(): self.car_fingerprint = CP.carFingerprint self.steer_rate_limited = False self.last_resume_frame = 0 + self.accel = 0 - def update(self, enabled, CS, frame, actuators, pcm_cancel_cmd, visual_alert, hud_speed, + def update(self, c, enabled, CS, frame, actuators, pcm_cancel_cmd, visual_alert, hud_speed, left_lane, right_lane, left_lane_depart, right_lane_depart): # Steering Torque new_steer = int(round(actuators.steer * self.p.STEER_MAX)) @@ -53,7 +54,7 @@ class CarController(): self.steer_rate_limited = new_steer != apply_steer # disable when temp fault is active, or below LKA minimum speed - lkas_active = enabled and not CS.out.steerWarning and CS.out.vEgo >= CS.CP.minSteerSpeed + lkas_active = c.active and not CS.out.steerWarning and CS.out.vEgo >= CS.CP.minSteerSpeed if not lkas_active: apply_steer = 0 @@ -88,7 +89,7 @@ class CarController(): if frame % 2 == 0 and CS.CP.openpilotLongitudinalControl: lead_visible = False - accel = actuators.accel if enabled else 0 + accel = actuators.accel if c.active else 0 jerk = clip(2.0 * (accel - CS.out.aEgo), -12.7, 12.7) @@ -100,12 +101,13 @@ class CarController(): stopping = (actuators.longControlState == LongCtrlState.stopping) set_speed_in_units = hud_speed * (CV.MS_TO_MPH if CS.clu11["CF_Clu_SPEED_UNIT"] == 1 else CV.MS_TO_KPH) can_sends.extend(create_acc_commands(self.packer, enabled, accel, jerk, int(frame / 2), lead_visible, set_speed_in_units, stopping)) + self.accel = accel # 20 Hz LFA MFA message - if frame % 5 == 0 and self.car_fingerprint in [CAR.SONATA, CAR.PALISADE, CAR.IONIQ, CAR.KIA_NIRO_EV, CAR.KIA_NIRO_HEV_2021, + if frame % 5 == 0 and self.car_fingerprint in (CAR.SONATA, CAR.PALISADE, CAR.IONIQ, CAR.KIA_NIRO_EV, CAR.KIA_NIRO_HEV_2021, CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV, CAR.KIA_CEED, CAR.KIA_SELTOS, CAR.KONA_EV, CAR.ELANTRA_2021, CAR.ELANTRA_HEV_2021, CAR.SONATA_HYBRID, CAR.KONA_HEV, CAR.SANTA_FE_2022, - CAR.KIA_K5_2021, CAR.IONIQ_HEV_2022, CAR.SANTA_FE_HEV_2022, CAR.GENESIS_G70_2020]: + CAR.KIA_K5_2021, CAR.IONIQ_HEV_2022, CAR.SANTA_FE_HEV_2022, CAR.GENESIS_G70_2020, CAR.SANTA_FE_PHEV_2022): can_sends.append(create_lfahda_mfc(self.packer, enabled)) # 5 Hz ACC options @@ -116,4 +118,8 @@ class CarController(): if frame % 50 == 0 and CS.CP.openpilotLongitudinalControl: can_sends.append(create_frt_radar_opt(self.packer)) - return can_sends + new_actuators = actuators.copy() + new_actuators.steer = apply_steer / self.p.STEER_MAX + new_actuators.accel = self.accel + + return new_actuators, can_sends diff --git a/selfdrive/car/hyundai/carstate.py b/selfdrive/car/hyundai/carstate.py index e889f24fc..bdd49e206 100644 --- a/selfdrive/car/hyundai/carstate.py +++ b/selfdrive/car/hyundai/carstate.py @@ -120,57 +120,57 @@ class CarState(CarStateBase): @staticmethod def get_can_parser(CP): signals = [ - # sig_name, sig_address, default - ("WHL_SPD_FL", "WHL_SPD11", 0), - ("WHL_SPD_FR", "WHL_SPD11", 0), - ("WHL_SPD_RL", "WHL_SPD11", 0), - ("WHL_SPD_RR", "WHL_SPD11", 0), + # sig_name, sig_address + ("WHL_SPD_FL", "WHL_SPD11"), + ("WHL_SPD_FR", "WHL_SPD11"), + ("WHL_SPD_RL", "WHL_SPD11"), + ("WHL_SPD_RR", "WHL_SPD11"), - ("YAW_RATE", "ESP12", 0), + ("YAW_RATE", "ESP12"), - ("CF_Gway_DrvSeatBeltInd", "CGW4", 1), + ("CF_Gway_DrvSeatBeltInd", "CGW4"), - ("CF_Gway_DrvSeatBeltSw", "CGW1", 0), - ("CF_Gway_DrvDrSw", "CGW1", 0), # Driver Door - ("CF_Gway_AstDrSw", "CGW1", 0), # Passenger door - ("CF_Gway_RLDrSw", "CGW2", 0), # Rear reft door - ("CF_Gway_RRDrSw", "CGW2", 0), # Rear right door - ("CF_Gway_TurnSigLh", "CGW1", 0), - ("CF_Gway_TurnSigRh", "CGW1", 0), - ("CF_Gway_ParkBrakeSw", "CGW1", 0), + ("CF_Gway_DrvSeatBeltSw", "CGW1"), + ("CF_Gway_DrvDrSw", "CGW1"), # Driver Door + ("CF_Gway_AstDrSw", "CGW1"), # Passenger door + ("CF_Gway_RLDrSw", "CGW2"), # Rear reft door + ("CF_Gway_RRDrSw", "CGW2"), # Rear right door + ("CF_Gway_TurnSigLh", "CGW1"), + ("CF_Gway_TurnSigRh", "CGW1"), + ("CF_Gway_ParkBrakeSw", "CGW1"), - ("CYL_PRES", "ESP12", 0), + ("CYL_PRES", "ESP12"), - ("CF_Clu_CruiseSwState", "CLU11", 0), - ("CF_Clu_CruiseSwMain", "CLU11", 0), - ("CF_Clu_SldMainSW", "CLU11", 0), - ("CF_Clu_ParityBit1", "CLU11", 0), - ("CF_Clu_VanzDecimal" , "CLU11", 0), - ("CF_Clu_Vanz", "CLU11", 0), - ("CF_Clu_SPEED_UNIT", "CLU11", 0), - ("CF_Clu_DetentOut", "CLU11", 0), - ("CF_Clu_RheostatLevel", "CLU11", 0), - ("CF_Clu_CluInfo", "CLU11", 0), - ("CF_Clu_AmpInfo", "CLU11", 0), - ("CF_Clu_AliveCnt1", "CLU11", 0), + ("CF_Clu_CruiseSwState", "CLU11"), + ("CF_Clu_CruiseSwMain", "CLU11"), + ("CF_Clu_SldMainSW", "CLU11"), + ("CF_Clu_ParityBit1", "CLU11"), + ("CF_Clu_VanzDecimal" , "CLU11"), + ("CF_Clu_Vanz", "CLU11"), + ("CF_Clu_SPEED_UNIT", "CLU11"), + ("CF_Clu_DetentOut", "CLU11"), + ("CF_Clu_RheostatLevel", "CLU11"), + ("CF_Clu_CluInfo", "CLU11"), + ("CF_Clu_AmpInfo", "CLU11"), + ("CF_Clu_AliveCnt1", "CLU11"), - ("ACCEnable", "TCS13", 0), - ("ACC_REQ", "TCS13", 0), - ("DriverBraking", "TCS13", 0), - ("StandStill", "TCS13", 0), - ("PBRAKE_ACT", "TCS13", 0), + ("ACCEnable", "TCS13"), + ("ACC_REQ", "TCS13"), + ("DriverBraking", "TCS13"), + ("StandStill", "TCS13"), + ("PBRAKE_ACT", "TCS13"), - ("ESC_Off_Step", "TCS15", 0), - ("AVH_LAMP", "TCS15", 0), + ("ESC_Off_Step", "TCS15"), + ("AVH_LAMP", "TCS15"), - ("CR_Mdps_StrColTq", "MDPS12", 0), - ("CF_Mdps_ToiActive", "MDPS12", 0), - ("CF_Mdps_ToiUnavail", "MDPS12", 0), - ("CF_Mdps_ToiFlt", "MDPS12", 0), - ("CR_Mdps_OutTq", "MDPS12", 0), + ("CR_Mdps_StrColTq", "MDPS12"), + ("CF_Mdps_ToiActive", "MDPS12"), + ("CF_Mdps_ToiUnavail", "MDPS12"), + ("CF_Mdps_ToiFlt", "MDPS12"), + ("CR_Mdps_OutTq", "MDPS12"), - ("SAS_Angle", "SAS11", 0), - ("SAS_Speed", "SAS11", 0), + ("SAS_Angle", "SAS11"), + ("SAS_Speed", "SAS11"), ] checks = [ @@ -189,11 +189,11 @@ class CarState(CarStateBase): if not CP.openpilotLongitudinalControl: signals += [ - ("MainMode_ACC", "SCC11", 0), - ("VSetDis", "SCC11", 0), - ("SCCInfoDisplay", "SCC11", 0), - ("ACC_ObjDist", "SCC11", 0), - ("ACCMode", "SCC12", 1), + ("MainMode_ACC", "SCC11"), + ("VSetDis", "SCC11"), + ("SCCInfoDisplay", "SCC11"), + ("ACC_ObjDist", "SCC11"), + ("ACCMode", "SCC12"), ] checks += [ @@ -203,39 +203,33 @@ class CarState(CarStateBase): if CP.carFingerprint in FEATURES["use_fca"]: signals += [ - ("FCA_CmdAct", "FCA11", 0), - ("CF_VSM_Warn", "FCA11", 0), + ("FCA_CmdAct", "FCA11"), + ("CF_VSM_Warn", "FCA11"), ] - checks += [("FCA11", 50)] + checks.append(("FCA11", 50)) else: signals += [ - ("AEB_CmdAct", "SCC12", 0), - ("CF_VSM_Warn", "SCC12", 0), + ("AEB_CmdAct", "SCC12"), + ("CF_VSM_Warn", "SCC12"), ] if CP.enableBsm: signals += [ - ("CF_Lca_IndLeft", "LCA11", 0), - ("CF_Lca_IndRight", "LCA11", 0), + ("CF_Lca_IndLeft", "LCA11"), + ("CF_Lca_IndRight", "LCA11"), ] - checks += [("LCA11", 50)] + checks.append(("LCA11", 50)) if CP.carFingerprint in (HYBRID_CAR | EV_CAR): if CP.carFingerprint in HYBRID_CAR: - signals += [ - ("CR_Vcu_AccPedDep_Pos", "E_EMS11", 0) - ] + signals.append(("CR_Vcu_AccPedDep_Pos", "E_EMS11")) else: - signals += [ - ("Accel_Pedal_Pos", "E_EMS11", 0) - ] - checks += [ - ("E_EMS11", 50), - ] + signals.append(("Accel_Pedal_Pos", "E_EMS11")) + checks.append(("E_EMS11", 50)) else: signals += [ - ("PV_AV_CAN", "EMS12", 0), - ("CF_Ems_AclAct", "EMS16", 0), + ("PV_AV_CAN", "EMS12"), + ("CF_Ems_AclAct", "EMS16"), ] checks += [ ("EMS12", 100), @@ -243,52 +237,39 @@ class CarState(CarStateBase): ] if CP.carFingerprint in FEATURES["use_cluster_gears"]: - signals += [ - ("CF_Clu_Gear", "CLU15", 0), - ] - checks += [ - ("CLU15", 5) - ] + signals.append(("CF_Clu_Gear", "CLU15")) + checks.append(("CLU15", 5)) elif CP.carFingerprint in FEATURES["use_tcu_gears"]: - signals += [ - ("CUR_GR", "TCU12", 0) - ] - checks += [ - ("TCU12", 100) - ] + signals.append(("CUR_GR", "TCU12")) + checks.append(("TCU12", 100)) elif CP.carFingerprint in FEATURES["use_elect_gears"]: - signals += [("Elect_Gear_Shifter", "ELECT_GEAR", 0)] - checks += [("ELECT_GEAR", 20)] + signals.append(("Elect_Gear_Shifter", "ELECT_GEAR")) + checks.append(("ELECT_GEAR", 20)) else: - signals += [ - ("CF_Lvr_Gear", "LVR12", 0) - ] - checks += [ - ("LVR12", 100) - ] + signals.append(("CF_Lvr_Gear", "LVR12")) + checks.append(("LVR12", 100)) return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 0) @staticmethod def get_cam_can_parser(CP): - signals = [ - # sig_name, sig_address, default - ("CF_Lkas_LdwsActivemode", "LKAS11", 0), - ("CF_Lkas_LdwsSysState", "LKAS11", 0), - ("CF_Lkas_SysWarning", "LKAS11", 0), - ("CF_Lkas_LdwsLHWarning", "LKAS11", 0), - ("CF_Lkas_LdwsRHWarning", "LKAS11", 0), - ("CF_Lkas_HbaLamp", "LKAS11", 0), - ("CF_Lkas_FcwBasReq", "LKAS11", 0), - ("CF_Lkas_HbaSysState", "LKAS11", 0), - ("CF_Lkas_FcwOpt", "LKAS11", 0), - ("CF_Lkas_HbaOpt", "LKAS11", 0), - ("CF_Lkas_FcwSysState", "LKAS11", 0), - ("CF_Lkas_FcwCollisionWarning", "LKAS11", 0), - ("CF_Lkas_FusionState", "LKAS11", 0), - ("CF_Lkas_FcwOpt_USM", "LKAS11", 0), - ("CF_Lkas_LdwsOpt_USM", "LKAS11", 0), + # sig_name, sig_address + ("CF_Lkas_LdwsActivemode", "LKAS11"), + ("CF_Lkas_LdwsSysState", "LKAS11"), + ("CF_Lkas_SysWarning", "LKAS11"), + ("CF_Lkas_LdwsLHWarning", "LKAS11"), + ("CF_Lkas_LdwsRHWarning", "LKAS11"), + ("CF_Lkas_HbaLamp", "LKAS11"), + ("CF_Lkas_FcwBasReq", "LKAS11"), + ("CF_Lkas_HbaSysState", "LKAS11"), + ("CF_Lkas_FcwOpt", "LKAS11"), + ("CF_Lkas_HbaOpt", "LKAS11"), + ("CF_Lkas_FcwSysState", "LKAS11"), + ("CF_Lkas_FcwCollisionWarning", "LKAS11"), + ("CF_Lkas_FusionState", "LKAS11"), + ("CF_Lkas_FcwOpt_USM", "LKAS11"), + ("CF_Lkas_LdwsOpt_USM", "LKAS11"), ] checks = [ diff --git a/selfdrive/car/hyundai/hyundaican.py b/selfdrive/car/hyundai/hyundaican.py index 50031231b..fd3fc78e8 100644 --- a/selfdrive/car/hyundai/hyundaican.py +++ b/selfdrive/car/hyundai/hyundaican.py @@ -16,10 +16,10 @@ def create_lkas11(packer, frame, car_fingerprint, apply_steer, steer_req, values["CF_Lkas_ActToi"] = steer_req values["CF_Lkas_MsgCount"] = frame % 0x10 - if car_fingerprint in [CAR.SONATA, CAR.PALISADE, CAR.KIA_NIRO_EV, CAR.KIA_NIRO_HEV_2021, CAR.SANTA_FE, + if car_fingerprint in (CAR.SONATA, CAR.PALISADE, CAR.KIA_NIRO_EV, CAR.KIA_NIRO_HEV_2021, CAR.SANTA_FE, CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV, CAR.KIA_SELTOS, CAR.ELANTRA_2021, CAR.GENESIS_G70_2020, CAR.ELANTRA_HEV_2021, CAR.SONATA_HYBRID, CAR.KONA_EV, CAR.KONA_HEV, CAR.SANTA_FE_2022, - CAR.KIA_K5_2021, CAR.IONIQ_HEV_2022, CAR.SANTA_FE_HEV_2022]: + CAR.KIA_K5_2021, CAR.IONIQ_HEV_2022, CAR.SANTA_FE_HEV_2022, CAR.SANTA_FE_PHEV_2022): values["CF_Lkas_LdwsActivemode"] = int(left_lane) + (int(right_lane) << 1) values["CF_Lkas_LdwsOpt_USM"] = 2 diff --git a/selfdrive/car/hyundai/interface.py b/selfdrive/car/hyundai/interface.py index 57b313e53..463ff3569 100644 --- a/selfdrive/car/hyundai/interface.py +++ b/selfdrive/car/hyundai/interface.py @@ -41,11 +41,10 @@ class CarInterface(CarInterfaceBase): ret.longitudinalTuning.kpV = [0.1] ret.longitudinalTuning.kiV = [0.0] ret.stopAccel = 0.0 - ret.startAccel = 0.0 ret.longitudinalActuatorDelayUpperBound = 1.0 # s - if candidate in [CAR.SANTA_FE, CAR.SANTA_FE_2022, CAR.SANTA_FE_HEV_2022]: + if candidate in (CAR.SANTA_FE, CAR.SANTA_FE_2022, CAR.SANTA_FE_HEV_2022, CAR.SANTA_FE_PHEV_2022): ret.lateralTuning.pid.kf = 0.00005 ret.mass = 3982. * CV.LB_TO_KG + STD_CARGO_KG ret.wheelbase = 2.766 @@ -54,7 +53,7 @@ class CarInterface(CarInterfaceBase): tire_stiffness_factor = 0.82 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[9., 22.], [9., 22.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2, 0.35], [0.05, 0.09]] - elif candidate in [CAR.SONATA, CAR.SONATA_HYBRID]: + elif candidate in (CAR.SONATA, CAR.SONATA_HYBRID): ret.lateralTuning.pid.kf = 0.00005 ret.mass = 1513. + STD_CARGO_KG ret.wheelbase = 2.84 @@ -77,7 +76,7 @@ class CarInterface(CarInterfaceBase): tire_stiffness_factor = 0.63 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.3], [0.05]] - elif candidate in [CAR.ELANTRA, CAR.ELANTRA_GT_I30]: + elif candidate in (CAR.ELANTRA, CAR.ELANTRA_GT_I30): ret.lateralTuning.pid.kf = 0.00006 ret.mass = 1275. + STD_CARGO_KG ret.wheelbase = 2.7 @@ -117,7 +116,7 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.indi.actuatorEffectivenessBP = [0.] ret.lateralTuning.indi.actuatorEffectivenessV = [2.3] ret.minSteerSpeed = 60 * CV.KPH_TO_MS - elif candidate in [CAR.KONA, CAR.KONA_EV, CAR.KONA_HEV]: + elif candidate in (CAR.KONA, CAR.KONA_EV, CAR.KONA_HEV): ret.lateralTuning.pid.kf = 0.00005 ret.mass = {CAR.KONA_EV: 1685., CAR.KONA_HEV: 1425.}.get(candidate, 1275.) + STD_CARGO_KG ret.wheelbase = 2.7 @@ -125,7 +124,7 @@ class CarInterface(CarInterfaceBase): tire_stiffness_factor = 0.385 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] - elif candidate in [CAR.IONIQ, CAR.IONIQ_EV_LTD, CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV, CAR.IONIQ_HEV_2022]: + elif candidate in (CAR.IONIQ, CAR.IONIQ_EV_LTD, CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV, CAR.IONIQ_HEV_2022): ret.lateralTuning.pid.kf = 0.00006 ret.mass = 1490. + STD_CARGO_KG # weight per hyundai site https://www.hyundaiusa.com/ioniq-electric/specifications.aspx ret.wheelbase = 2.7 @@ -133,7 +132,7 @@ class CarInterface(CarInterfaceBase): tire_stiffness_factor = 0.385 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] - if candidate not in [CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV, CAR.IONIQ_HEV_2022]: + if candidate not in (CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV, CAR.IONIQ_HEV_2022): ret.minSteerSpeed = 32 * CV.MPH_TO_MS elif candidate == CAR.VELOSTER: ret.lateralTuning.pid.kf = 0.00005 @@ -152,7 +151,7 @@ class CarInterface(CarInterfaceBase): ret.steerRatio = 14.4 * 1.1 # 10% higher at the center seems reasonable ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]] - elif candidate in [CAR.KIA_NIRO_EV, CAR.KIA_NIRO_HEV, CAR.KIA_NIRO_HEV_2021]: + elif candidate in (CAR.KIA_NIRO_EV, CAR.KIA_NIRO_HEV, CAR.KIA_NIRO_HEV_2021): ret.lateralTuning.pid.kf = 0.00006 ret.mass = 1737. + STD_CARGO_KG ret.wheelbase = 2.7 @@ -176,7 +175,7 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.indi.timeConstantV = [1.4] ret.lateralTuning.indi.actuatorEffectivenessBP = [0.] ret.lateralTuning.indi.actuatorEffectivenessV = [1.8] - elif candidate in [CAR.KIA_OPTIMA, CAR.KIA_OPTIMA_H]: + elif candidate in (CAR.KIA_OPTIMA, CAR.KIA_OPTIMA_H): ret.lateralTuning.pid.kf = 0.00005 ret.mass = 3558. * CV.LB_TO_KG ret.wheelbase = 2.80 @@ -327,7 +326,7 @@ class CarInterface(CarInterfaceBase): for b in ret.buttonEvents: # do enable on both accel and decel buttons - if b.type in [ButtonType.accelCruise, ButtonType.decelCruise] and not b.pressed: + if b.type in (ButtonType.accelCruise, ButtonType.decelCruise) and not b.pressed: events.add(EventName.buttonEnable) # do disable on button down if b.type == ButtonType.cancel and b.pressed: @@ -347,8 +346,9 @@ class CarInterface(CarInterfaceBase): return self.CS.out def apply(self, c): - can_sends = self.CC.update(c.enabled, self.CS, self.frame, c.actuators, - c.cruiseControl.cancel, c.hudControl.visualAlert, c.hudControl.setSpeed, c.hudControl.leftLaneVisible, - c.hudControl.rightLaneVisible, c.hudControl.leftLaneDepart, c.hudControl.rightLaneDepart) + hud_control = c.hudControl + ret = self.CC.update(c, c.enabled, self.CS, self.frame, c.actuators, + c.cruiseControl.cancel, hud_control.visualAlert, hud_control.setSpeed, hud_control.leftLaneVisible, + hud_control.rightLaneVisible, hud_control.leftLaneDepart, hud_control.rightLaneDepart) self.frame += 1 - return can_sends + return ret diff --git a/selfdrive/car/hyundai/radar_interface.py b/selfdrive/car/hyundai/radar_interface.py index 6022069a2..0d22611fb 100644 --- a/selfdrive/car/hyundai/radar_interface.py +++ b/selfdrive/car/hyundai/radar_interface.py @@ -20,11 +20,11 @@ def get_radar_can_parser(CP): for addr in range(RADAR_START_ADDR, RADAR_START_ADDR + RADAR_MSG_COUNT): msg = f"RADAR_TRACK_{addr:x}" signals += [ - ("STATE", msg, 0), - ("AZIMUTH", msg, 0), - ("LONG_DIST", msg, 0), - ("REL_ACCEL", msg, 0), - ("REL_SPEED", msg, 0), + ("STATE", msg), + ("AZIMUTH", msg), + ("LONG_DIST", msg), + ("REL_ACCEL", msg), + ("REL_SPEED", msg), ] checks += [(msg, 50)] return CANParser(DBC[CP.carFingerprint]['radar'], signals, checks, 1) @@ -74,14 +74,14 @@ class RadarInterface(RadarInterfaceBase): self.pts[addr].trackId = self.track_id self.track_id += 1 - valid = msg['STATE'] in [3, 4] + valid = msg['STATE'] in (3, 4) if valid: azimuth = math.radians(msg['AZIMUTH']) self.pts[addr].measured = True self.pts[addr].dRel = math.cos(azimuth) * msg['LONG_DIST'] self.pts[addr].yRel = 0.5 * -math.sin(azimuth) * msg['LONG_DIST'] self.pts[addr].vRel = msg['REL_SPEED'] - self.pts[addr].aRel = msg['REL_ACCEL'] + self.pts[addr].aRel = msg['REL_ACCEL'] self.pts[addr].yvRel = float('nan') else: diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py index df2e10dbe..818dbe57f 100644 --- a/selfdrive/car/hyundai/values.py +++ b/selfdrive/car/hyundai/values.py @@ -1,5 +1,3 @@ -# flake8: noqa - from cereal import car from selfdrive.car import dbc_dict Ecu = car.CarParams.Ecu @@ -10,13 +8,14 @@ class CarControllerParams: ACCEL_MAX = 2.0 # m/s def __init__(self, CP): - if CP.carFingerprint in [CAR.SONATA, CAR.PALISADE, CAR.SANTA_FE, CAR.VELOSTER, CAR.GENESIS_G70, CAR.GENESIS_G70_2020, - CAR.IONIQ_EV_2020, CAR.KIA_CEED, CAR.KIA_SELTOS, CAR.ELANTRA_2021, - CAR.ELANTRA_HEV_2021, CAR.SONATA_HYBRID, CAR.KONA_HEV, CAR.SANTA_FE_2022, - CAR.KIA_K5_2021, CAR.KONA_EV, CAR.KONA, CAR.IONIQ_HEV_2022, CAR.SANTA_FE_HEV_2022]: - self.STEER_MAX = 384 - else: + # To determine the limit for your car, find the maximum value that the stock LKAS will request. + # If the max stock LKAS request is <384, add your car to this list. + if CP.carFingerprint in (CAR.GENESIS_G80, CAR.GENESIS_G90, CAR.ELANTRA, CAR.HYUNDAI_GENESIS, CAR.ELANTRA_GT_I30, CAR.IONIQ, + CAR.IONIQ_EV_LTD, CAR.IONIQ_PHEV, CAR.SANTA_FE_PHEV_2022, CAR.SONATA_LF, CAR.KIA_FORTE, CAR.KIA_NIRO_HEV, + CAR.KIA_NIRO_HEV_2021, CAR.KIA_OPTIMA_H, CAR.KIA_OPTIMA, CAR.KIA_SORENTO, CAR.KIA_STINGER): self.STEER_MAX = 255 + else: + self.STEER_MAX = 384 self.STEER_DELTA_UP = 3 self.STEER_DELTA_DOWN = 7 self.STEER_DRIVER_ALLOWANCE = 50 @@ -41,6 +40,7 @@ class CAR: SANTA_FE = "HYUNDAI SANTA FE 2019" SANTA_FE_2022 = "HYUNDAI SANTA FE 2022" SANTA_FE_HEV_2022 = "HYUNDAI SANTA FE HYBRID 2022" + SANTA_FE_PHEV_2022 = "HYUNDAI SANTA FE PlUG-IN HYBRID 2022" SONATA = "HYUNDAI SONATA 2020" SONATA_LF = "HYUNDAI SONATA 2019" PALISADE = "HYUNDAI PALISADE 2020" @@ -463,22 +463,27 @@ FW_VERSIONS = { b'\xf1\x00TM ESC \x03 101 \x08\x02 58910-S2DA0', b'\xf1\x8758910-S2DA0\xf1\x00TM ESC \x03 101 \x08\x02 58910-S2DA0', b'\xf1\x8758910-S2GA0\xf1\x00TM ESC \x02 101 \x08\x04 58910-S2GA0', + b'\xf1\x8758910-S1DA0\xf1\x00TM ESC \x1e 102 \x08\x08 58910-S1DA0', ], (Ecu.engine, 0x7e0, None): [ b'\xf1\x82TMBZN5TMD3XXXG2E', b'\xf1\x82TACVN5GSI3XXXH0A', + b'\xf1\x82TMCFD5MMCXXXXG0A', ], (Ecu.eps, 0x7d4, None): [ b'\xf1\x00TM MDPS C 1.00 1.02 56370-S2AA0 0B19', + b'\xf1\x00TM MDPS C 1.00 1.01 56310-S1AB0 4TSDC101', ], (Ecu.fwdCamera, 0x7c4, None): [ b'\xf1\x00TMA MFC AT MEX LHD 1.00 1.01 99211-S2500 210205', b'\xf1\x00TMA MFC AT USA LHD 1.00 1.00 99211-S2500 200720', + b'\xf1\x00TM MFC AT EUR LHD 1.00 1.03 99211-S1500 210224', ], (Ecu.transmission, 0x7e1, None): [ b'\xf1\x00T02601BL T02730A1 VTMPT25XXX730NS2\xa6\x06\x88\xf7', b'\xf1\x87SDMXCA8653204GN1EVugEUuWwwwwww\x87wwwwwv/\xfb\xff\xa8\x88\x9f\xff\xa5\x9c\xf1\x89HT6WAD00A1\xf1\x82STM4G25NH1\x00\x00\x00\x00\x00\x00', b'\xf1\x87954A02N250\x00\x00\x00\x00\x00\xf1\x81T02730A1 \xf1\x00T02601BL T02730A1 VTMPT25XXX730NS2\xa6\x06\x88\xf7', + b'\xf1\x87KMMYBU034207SB72x\x89\x88\x98h\x88\x98\x89\x87fhvvfWf33_\xff\x87\xff\x8f\xfa\x81\xe5\xf1\x89HT6TAF00A1\xf1\x82STM0M25GS1\x00\x00\x00\x00\x00\x00', ], }, CAR.SANTA_FE_HEV_2022: { @@ -498,6 +503,23 @@ FW_VERSIONS = { b'\xf1\x87391312MTC1', ], }, + CAR.SANTA_FE_PHEV_2022: { + (Ecu.fwdRadar, 0x7d0, None): [ + b'\xf1\x8799110CL500\xf1\x00TMhe SCC FHCUP 1.00 1.00 99110-CL500 ', + ], + (Ecu.eps, 0x7d4, None): [ + b'\xf1\x00TM MDPS C 1.00 1.02 56310-CLAC0 4TSHC102', + ], + (Ecu.fwdCamera, 0x7c4, None): [ + b'\xf1\x00TMP MFC AT USA LHD 1.00 1.03 99211-S1500 210224', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xf1\x8795441-3D121\x00\xf1\x81E16\x00\x00\x00\x00\x00\x00\x00\xf1\x00PSBG2333 E16\x00\x00\x00\x00\x00\x00\x00TTM2P16SA0o\x88^\xbe', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xf1\x87391312MTF0', + ], + }, CAR.KIA_STINGER: { (Ecu.fwdRadar, 0x7d0, None): [ b'\xf1\x00CK__ SCC F_CUP 1.00 1.01 96400-J5100 ', @@ -653,7 +675,7 @@ FW_VERSIONS = { b'\xf1\x00IK MDPS R 1.00 1.07 57700-G9220 4I2VL107', ], (Ecu.transmission, 0x7e1, None): [ - b'\xf1\x87VCJLP18407832DN3\x88vXfvUVT\x97eFU\x87d7v\x88eVeveFU\x89\x98\x7f\xff\xb2\xb0\xf1\x81E25\x00\x00\x00' + b'\xf1\x87VCJLP18407832DN3\x88vXfvUVT\x97eFU\x87d7v\x88eVeveFU\x89\x98\x7f\xff\xb2\xb0\xf1\x81E25\x00\x00\x00', b'\x00\x00\x00\x00\xf1\x00bcsh8p54 E25\x00\x00\x00\x00\x00\x00\x00SIK0T33NB4\xecE\xefL', ], (Ecu.fwdRadar, 0x7d0, None): [ @@ -777,25 +799,22 @@ FW_VERSIONS = { b'\xf1\x00DEev SCC F-CUP 1.00 1.00 99110-Q4000 ', b'\xf1\x00DEev SCC F-CUP 1.00 1.02 96400-Q4100 ', b'\xf1\x00DEev SCC F-CUP 1.00 1.03 96400-Q4100 ', - b'\xf1\x00OSev SCC F-CUP 1.00 1.01 99110-K4000 ', b'\xf1\x8799110Q4000\xf1\x00DEev SCC F-CUP 1.00 1.00 99110-Q4000 ', b'\xf1\x8799110Q4100\xf1\x00DEev SCC F-CUP 1.00 1.00 99110-Q4100 ', - b'\xf1\x8799110Q4500\xf1\000DEev SCC F-CUP 1.00 1.00 99110-Q4500 ', - ], - (Ecu.esp, 0x7D1, None): [ - b'\xf1\x00OS IEB \r 212 \x11\x13 58520-K4000', + b'\xf1\x8799110Q4500\xf1\x00DEev SCC F-CUP 1.00 1.00 99110-Q4500 ', + b'\xf1\x8799110Q4600\xf1\x00DEev SCC FNCUP 1.00 1.00 99110-Q4600 ', + b'\xf1\x8799110Q4600\xf1\x00DEev SCC FHCUP 1.00 1.00 99110-Q4600 ', ], (Ecu.eps, 0x7D4, None): [ b'\xf1\x00DE MDPS C 1.00 1.05 56310Q4000\x00 4DEEC105', b'\xf1\x00DE MDPS C 1.00 1.05 56310Q4100\x00 4DEEC105', - b'\xf1\x00OS MDPS C 1.00 1.04 56310K4050\x00 4OEDC104', ], (Ecu.fwdCamera, 0x7C4, None): [ - b'\xf1\000DEE MFC AT EUR LHD 1.00 1.00 99211-Q4100 200706', + b'\xf1\x00DEE MFC AT EUR LHD 1.00 1.00 99211-Q4100 200706', b'\xf1\x00DEE MFC AT EUR LHD 1.00 1.00 99211-Q4000 191211', b'\xf1\x00DEE MFC AT USA LHD 1.00 1.00 99211-Q4000 191211', b'\xf1\x00DEE MFC AT USA LHD 1.00 1.03 95740-Q4000 180821', - b'\xf1\x00OSE LKAS AT EUR LHD 1.00 1.00 95740-K4100 W40', + b'\xf1\x00DEE MFC AT USA LHD 1.00 1.01 99211-Q4500 210428', ], }, CAR.KIA_NIRO_HEV: { @@ -981,25 +1000,25 @@ FW_VERSIONS = { } CHECKSUM = { - "crc8": [CAR.SANTA_FE, CAR.SONATA, CAR.PALISADE, CAR.KIA_SELTOS, CAR.ELANTRA_2021, CAR.ELANTRA_HEV_2021, CAR.SONATA_HYBRID, CAR.SANTA_FE_2022, CAR.KIA_K5_2021, CAR.SANTA_FE_HEV_2022], + "crc8": [CAR.SANTA_FE, CAR.SONATA, CAR.PALISADE, CAR.KIA_SELTOS, CAR.ELANTRA_2021, CAR.ELANTRA_HEV_2021, CAR.SONATA_HYBRID, CAR.SANTA_FE_2022, CAR.KIA_K5_2021, CAR.SANTA_FE_HEV_2022, CAR.SANTA_FE_PHEV_2022], "6B": [CAR.KIA_SORENTO, CAR.HYUNDAI_GENESIS], } FEATURES = { # which message has the gear - "use_cluster_gears": set([CAR.ELANTRA, CAR.ELANTRA_GT_I30, CAR.KONA]), - "use_tcu_gears": set([CAR.KIA_OPTIMA, CAR.SONATA_LF, CAR.VELOSTER]), - "use_elect_gears": set([CAR.KIA_NIRO_EV, CAR.KIA_NIRO_HEV, CAR.KIA_NIRO_HEV_2021, CAR.KIA_OPTIMA_H, CAR.IONIQ_EV_LTD, CAR.KONA_EV, CAR.IONIQ, CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV, CAR.ELANTRA_HEV_2021,CAR.SONATA_HYBRID, CAR.KONA_HEV, CAR.IONIQ_HEV_2022, CAR.SANTA_FE_HEV_2022]), + "use_cluster_gears": {CAR.ELANTRA, CAR.ELANTRA_GT_I30, CAR.KONA}, + "use_tcu_gears": {CAR.KIA_OPTIMA, CAR.SONATA_LF, CAR.VELOSTER}, + "use_elect_gears": {CAR.KIA_NIRO_EV, CAR.KIA_NIRO_HEV, CAR.KIA_NIRO_HEV_2021, CAR.KIA_OPTIMA_H, CAR.IONIQ_EV_LTD, CAR.KONA_EV, CAR.IONIQ, CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV, CAR.ELANTRA_HEV_2021,CAR.SONATA_HYBRID, CAR.KONA_HEV, CAR.IONIQ_HEV_2022, CAR.SANTA_FE_HEV_2022, CAR.SANTA_FE_PHEV_2022}, # these cars use the FCA11 message for the AEB and FCW signals, all others use SCC12 - "use_fca": set([CAR.SONATA, CAR.SONATA_HYBRID, CAR.ELANTRA, CAR.ELANTRA_2021, CAR.ELANTRA_HEV_2021, CAR.ELANTRA_GT_I30, CAR.KIA_STINGER, CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV, CAR.KONA_EV, CAR.KIA_FORTE, CAR.KIA_NIRO_EV, CAR.PALISADE, CAR.GENESIS_G70, CAR.GENESIS_G70_2020, CAR.KONA, CAR.SANTA_FE, CAR.KIA_SELTOS, CAR.KONA_HEV, CAR.SANTA_FE_2022, CAR.KIA_K5_2021, CAR.IONIQ_HEV_2022, CAR.SANTA_FE_HEV_2022]), + "use_fca": {CAR.SONATA, CAR.SONATA_HYBRID, CAR.ELANTRA, CAR.ELANTRA_2021, CAR.ELANTRA_HEV_2021, CAR.ELANTRA_GT_I30, CAR.KIA_STINGER, CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV, CAR.KONA_EV, CAR.KIA_FORTE, CAR.KIA_NIRO_EV, CAR.PALISADE, CAR.GENESIS_G70, CAR.GENESIS_G70_2020, CAR.KONA, CAR.SANTA_FE, CAR.KIA_SELTOS, CAR.KONA_HEV, CAR.SANTA_FE_2022, CAR.KIA_K5_2021, CAR.IONIQ_HEV_2022, CAR.SANTA_FE_HEV_2022, CAR.SANTA_FE_PHEV_2022}, } -HYBRID_CAR = set([CAR.IONIQ_PHEV, CAR.ELANTRA_HEV_2021, CAR.KIA_NIRO_HEV, CAR.KIA_NIRO_HEV_2021, CAR.SONATA_HYBRID, CAR.KONA_HEV, CAR.IONIQ, CAR.IONIQ_HEV_2022, CAR.SANTA_FE_HEV_2022]) # these cars use a different gas signal -EV_CAR = set([CAR.IONIQ_EV_2020, CAR.IONIQ_EV_LTD, CAR.KONA_EV, CAR.KIA_NIRO_EV]) +HYBRID_CAR = {CAR.IONIQ_PHEV, CAR.ELANTRA_HEV_2021, CAR.KIA_NIRO_HEV, CAR.KIA_NIRO_HEV_2021, CAR.SONATA_HYBRID, CAR.KONA_HEV, CAR.IONIQ, CAR.IONIQ_HEV_2022, CAR.SANTA_FE_HEV_2022, CAR.SANTA_FE_PHEV_2022} # these cars use a different gas signal +EV_CAR = {CAR.IONIQ_EV_2020, CAR.IONIQ_EV_LTD, CAR.KONA_EV, CAR.KIA_NIRO_EV} # these cars require a special panda safety mode due to missing counters and checksums in the messages -LEGACY_SAFETY_MODE_CAR = set([CAR.HYUNDAI_GENESIS, CAR.IONIQ_EV_2020, CAR.IONIQ_EV_LTD, CAR.IONIQ_PHEV, CAR.IONIQ, CAR.KONA_EV, CAR.KIA_SORENTO, CAR.SONATA_LF, CAR.KIA_NIRO_EV, CAR.KIA_OPTIMA, CAR.VELOSTER, CAR.KIA_STINGER, CAR.GENESIS_G70, CAR.GENESIS_G80, CAR.KIA_CEED, CAR.ELANTRA, CAR.IONIQ_HEV_2022]) +LEGACY_SAFETY_MODE_CAR = {CAR.HYUNDAI_GENESIS, CAR.IONIQ_EV_2020, CAR.IONIQ_EV_LTD, CAR.IONIQ_PHEV, CAR.IONIQ, CAR.KONA_EV, CAR.KIA_SORENTO, CAR.SONATA_LF, CAR.KIA_OPTIMA, CAR.VELOSTER, CAR.KIA_STINGER, CAR.GENESIS_G70, CAR.GENESIS_G80, CAR.KIA_CEED, CAR.ELANTRA, CAR.IONIQ_HEV_2022} # If 0x500 is present on bus 1 it probably has a Mando radar outputting radar points. # If no points are outputted by default it might be possible to turn it on using selfdrive/debug/hyundai_enable_radar_points.py @@ -1020,7 +1039,7 @@ DBC = { CAR.IONIQ_HEV_2022: dbc_dict('hyundai_kia_generic', None), CAR.KIA_FORTE: dbc_dict('hyundai_kia_generic', None), CAR.KIA_K5_2021: dbc_dict('hyundai_kia_generic', None), - CAR.KIA_NIRO_EV: dbc_dict('hyundai_kia_generic', None), + CAR.KIA_NIRO_EV: dbc_dict('hyundai_kia_generic', 'hyundai_kia_mando_front_radar'), CAR.KIA_NIRO_HEV: dbc_dict('hyundai_kia_generic', 'hyundai_kia_mando_front_radar'), CAR.KIA_NIRO_HEV_2021: dbc_dict('hyundai_kia_generic', None), CAR.KIA_OPTIMA: dbc_dict('hyundai_kia_generic', None), @@ -1034,6 +1053,7 @@ DBC = { CAR.SANTA_FE: dbc_dict('hyundai_kia_generic', 'hyundai_kia_mando_front_radar'), CAR.SANTA_FE_2022: dbc_dict('hyundai_kia_generic', None), CAR.SANTA_FE_HEV_2022: dbc_dict('hyundai_kia_generic', None), + CAR.SANTA_FE_PHEV_2022: dbc_dict('hyundai_kia_generic', None), CAR.SONATA: dbc_dict('hyundai_kia_generic', 'hyundai_kia_mando_front_radar'), CAR.SONATA_LF: dbc_dict('hyundai_kia_generic', None), # Has 0x5XX messages, but different format CAR.PALISADE: dbc_dict('hyundai_kia_generic', 'hyundai_kia_mando_front_radar'), diff --git a/selfdrive/car/interfaces.py b/selfdrive/car/interfaces.py index bef3456a7..aa06b960d 100644 --- a/selfdrive/car/interfaces.py +++ b/selfdrive/car/interfaces.py @@ -1,6 +1,7 @@ import os import time -from typing import Dict +from abc import abstractmethod, ABC +from typing import Dict, Tuple, List from cereal import car from common.kalman.simple_kalman import KF1D @@ -22,7 +23,7 @@ ACCEL_MIN = -3.5 # generic car and radar interfaces -class CarInterfaceBase(): +class CarInterfaceBase(ABC): def __init__(self, CP, CarController, CarState): self.CP = CP self.VM = VehicleModel(CP) @@ -48,8 +49,9 @@ class CarInterfaceBase(): return ACCEL_MIN, ACCEL_MAX @staticmethod + @abstractmethod def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=None): - raise NotImplementedError + pass @staticmethod def init(CP, logcan, sendcan): @@ -70,6 +72,7 @@ class CarInterfaceBase(): def get_std_params(candidate, fingerprint): ret = car.CarParams.new_message() ret.carFingerprint = candidate + ret.unsafeMode = 0 # see panda/board/safety_declarations.h for allowed values # standard ALC params ret.steerControlType = car.CarParams.SteerControlType.torque @@ -82,13 +85,10 @@ class CarInterfaceBase(): ret.minEnableSpeed = -1. # enable is done by stock ACC, so ignore this ret.steerRatioRear = 0. # no rear steering, at least on the listed cars aboveA ret.openpilotLongitudinalControl = False - ret.minSpeedCan = 0.3 - ret.startAccel = -0.8 ret.stopAccel = -2.0 - ret.startingAccelRate = 3.2 # brake_travel/s while releasing on restart ret.stoppingDecelRate = 0.8 # brake_travel/s while trying to stop ret.vEgoStopping = 0.5 - ret.vEgoStarting = 0.5 + ret.vEgoStarting = 0.5 # needs to be >= vEgoStopping to avoid state transition oscillation ret.stoppingControl = True ret.longitudinalTuning.deadzoneBP = [0.] ret.longitudinalTuning.deadzoneV = [0.] @@ -98,17 +98,18 @@ class CarInterfaceBase(): ret.longitudinalTuning.kiV = [1.] ret.longitudinalActuatorDelayLowerBound = 0.15 ret.longitudinalActuatorDelayUpperBound = 0.15 + ret.steerLimitTimer = 1.0 return ret - # returns a car.CarState, pass in car.CarControl - def update(self, c, can_strings): - raise NotImplementedError + @abstractmethod + def update(self, c: car.CarControl, can_strings: List[bytes]) -> car.CarState: + pass - # return sendcan, pass in a car.CarControl - def apply(self, c): - raise NotImplementedError + @abstractmethod + def apply(self, c: car.CarControl) -> Tuple[car.CarControl.Actuators, List[bytes]]: + pass - def create_common_events(self, cs_out, extra_gears=None, gas_resume_speed=-1, pcm_enable=True): + def create_common_events(self, cs_out, extra_gears=None, pcm_enable=True): events = Events() if cs_out.doorOpen: @@ -153,9 +154,7 @@ class CarInterfaceBase(): events.add(EventName.steerUnavailable) # Disable on rising edge of gas or brake. Also disable on brake when speed > 0. - # Optionally allow to press gas at zero speed to resume. - # e.g. Chrysler does not spam the resume button yet, so resuming with gas is handy. FIXME! - if (cs_out.gasPressed and (not self.CS.out.gasPressed) and cs_out.vEgo > gas_resume_speed) or \ + if (cs_out.gasPressed and not self.CS.out.gasPressed) or \ (cs_out.brakePressed and (not self.CS.out.brakePressed or not cs_out.standstill)): events.add(EventName.pedalPressed) @@ -169,7 +168,7 @@ class CarInterfaceBase(): return events -class RadarInterfaceBase(): +class RadarInterfaceBase(ABC): def __init__(self, CP): self.pts = {} self.delay = 0 @@ -183,7 +182,7 @@ class RadarInterfaceBase(): return ret -class CarStateBase: +class CarStateBase(ABC): def __init__(self, CP): self.CP = CP self.car_fingerprint = CP.carFingerprint diff --git a/selfdrive/car/mazda/carcontroller.py b/selfdrive/car/mazda/carcontroller.py index 06c5eb094..60bb62037 100644 --- a/selfdrive/car/mazda/carcontroller.py +++ b/selfdrive/car/mazda/carcontroller.py @@ -19,7 +19,7 @@ class CarController(): apply_steer = 0 self.steer_rate_limited = False - if c.enabled: + if c.active: # calculate steer and also set limits due to driver torque new_steer = int(round(c.actuators.steer * CarControllerParams.STEER_MAX)) apply_steer = apply_std_steer_torque_limits(new_steer, self.apply_steer_last, @@ -58,4 +58,8 @@ class CarController(): # send steering command can_sends.append(mazdacan.create_steering_control(self.packer, CS.CP.carFingerprint, frame, apply_steer, CS.cam_lkas)) - return can_sends + + new_actuators = c.actuators.copy() + new_actuators.steer = apply_steer / CarControllerParams.STEER_MAX + + return new_actuators, can_sends diff --git a/selfdrive/car/mazda/carstate.py b/selfdrive/car/mazda/carstate.py index 7ebf60c96..feb114754 100644 --- a/selfdrive/car/mazda/carstate.py +++ b/selfdrive/car/mazda/carstate.py @@ -16,6 +16,7 @@ class CarState(CarStateBase): self.acc_active_last = False self.low_speed_alert = False self.lkas_allowed_speed = False + self.lkas_disabled = False def update(self, cp, cp_cam): @@ -64,12 +65,13 @@ class CarState(CarStateBase): # Either due to low speed or hands off lkas_blocked = cp.vl["STEER_RATE"]["LKAS_BLOCK"] == 1 - # LKAS is enabled at 52kph going up and disabled at 45kph going down - # wait for LKAS_BLOCK signal to clear when going up since it lags behind the speed sometimes - if speed_kph > LKAS_LIMITS.ENABLE_SPEED and not lkas_blocked: - self.lkas_allowed_speed = True - elif speed_kph < LKAS_LIMITS.DISABLE_SPEED: - self.lkas_allowed_speed = False + if self.CP.minSteerSpeed > 0: + # LKAS is enabled at 52kph going up and disabled at 45kph going down + # wait for LKAS_BLOCK signal to clear when going up since it lags behind the speed sometimes + if speed_kph > LKAS_LIMITS.ENABLE_SPEED and not lkas_blocked: + self.lkas_allowed_speed = True + elif speed_kph < LKAS_LIMITS.DISABLE_SPEED: + self.lkas_allowed_speed = False # TODO: the signal used for available seems to be the adaptive cruise signal, instead of the main on # it should be used for carState.cruiseState.nonAdaptive instead @@ -86,34 +88,35 @@ class CarState(CarStateBase): # Check if LKAS is disabled due to lack of driver torque when all other states indicate # it should be enabled (steer lockout). Don't warn until we actually get lkas active # and lose it again, i.e, after initial lkas activation - ret.steerWarning = self.lkas_allowed_speed and lkas_blocked self.acc_active_last = ret.cruiseState.enabled + self.crz_btns_counter = cp.vl["CRZ_BTNS"]["CTR"] + + # camera signals + self.lkas_disabled = cp_cam.vl["CAM_LANEINFO"]["LANE_LINES"] == 0 self.cam_lkas = cp_cam.vl["CAM_LKAS"] self.cam_laneinfo = cp_cam.vl["CAM_LANEINFO"] - self.crz_btns_counter = cp.vl["CRZ_BTNS"]["CTR"] ret.steerError = cp_cam.vl["CAM_LKAS"]["ERR_BIT_1"] == 1 return ret @staticmethod def get_can_parser(CP): - # this function generates lists for signal, messages and initial values signals = [ - # sig_name, sig_address, default - ("LEFT_BLINK", "BLINK_INFO", 0), - ("RIGHT_BLINK", "BLINK_INFO", 0), - ("HIGH_BEAMS", "BLINK_INFO", 0), - ("STEER_ANGLE", "STEER", 0), - ("STEER_ANGLE_RATE", "STEER_RATE", 0), - ("STEER_TORQUE_SENSOR", "STEER_TORQUE", 0), - ("STEER_TORQUE_MOTOR", "STEER_TORQUE", 0), - ("FL", "WHEEL_SPEEDS", 0), - ("FR", "WHEEL_SPEEDS", 0), - ("RL", "WHEEL_SPEEDS", 0), - ("RR", "WHEEL_SPEEDS", 0), + # sig_name, sig_address + ("LEFT_BLINK", "BLINK_INFO"), + ("RIGHT_BLINK", "BLINK_INFO"), + ("HIGH_BEAMS", "BLINK_INFO"), + ("STEER_ANGLE", "STEER"), + ("STEER_ANGLE_RATE", "STEER_RATE"), + ("STEER_TORQUE_SENSOR", "STEER_TORQUE"), + ("STEER_TORQUE_MOTOR", "STEER_TORQUE"), + ("FL", "WHEEL_SPEEDS"), + ("FR", "WHEEL_SPEEDS"), + ("RL", "WHEEL_SPEEDS"), + ("RR", "WHEEL_SPEEDS"), ] checks = [ @@ -127,26 +130,26 @@ class CarState(CarStateBase): if CP.carFingerprint in GEN1: signals += [ - ("LKAS_BLOCK", "STEER_RATE", 0), - ("LKAS_TRACK_STATE", "STEER_RATE", 0), - ("HANDS_OFF_5_SECONDS", "STEER_RATE", 0), - ("CRZ_ACTIVE", "CRZ_CTRL", 0), - ("CRZ_AVAILABLE", "CRZ_CTRL", 0), - ("CRZ_SPEED", "CRZ_EVENTS", 0), - ("STANDSTILL", "PEDALS", 0), - ("BRAKE_ON", "PEDALS", 0), - ("BRAKE_PRESSURE", "BRAKE", 0), - ("GEAR", "GEAR", 0), - ("DRIVER_SEATBELT", "SEATBELT", 0), - ("FL", "DOORS", 0), - ("FR", "DOORS", 0), - ("BL", "DOORS", 0), - ("BR", "DOORS", 0), - ("PEDAL_GAS", "ENGINE_DATA", 0), - ("SPEED", "ENGINE_DATA", 0), - ("CTR", "CRZ_BTNS", 0), - ("LEFT_BS1", "BSM", 0), - ("RIGHT_BS1", "BSM", 0), + ("LKAS_BLOCK", "STEER_RATE"), + ("LKAS_TRACK_STATE", "STEER_RATE"), + ("HANDS_OFF_5_SECONDS", "STEER_RATE"), + ("CRZ_ACTIVE", "CRZ_CTRL"), + ("CRZ_AVAILABLE", "CRZ_CTRL"), + ("CRZ_SPEED", "CRZ_EVENTS"), + ("STANDSTILL", "PEDALS"), + ("BRAKE_ON", "PEDALS"), + ("BRAKE_PRESSURE", "BRAKE"), + ("GEAR", "GEAR"), + ("DRIVER_SEATBELT", "SEATBELT"), + ("FL", "DOORS"), + ("FR", "DOORS"), + ("BL", "DOORS"), + ("BR", "DOORS"), + ("PEDAL_GAS", "ENGINE_DATA"), + ("SPEED", "ENGINE_DATA"), + ("CTR", "CRZ_BTNS"), + ("LEFT_BS1", "BSM"), + ("RIGHT_BS1", "BSM"), ] checks += [ @@ -171,26 +174,26 @@ class CarState(CarStateBase): if CP.carFingerprint in GEN1: signals += [ - # sig_name, sig_address, default - ("LKAS_REQUEST", "CAM_LKAS", 0), - ("CTR", "CAM_LKAS", 0), - ("ERR_BIT_1", "CAM_LKAS", 0), - ("LINE_NOT_VISIBLE", "CAM_LKAS", 0), - ("BIT_1", "CAM_LKAS", 1), - ("ERR_BIT_2", "CAM_LKAS", 0), - ("STEERING_ANGLE", "CAM_LKAS", 0), - ("ANGLE_ENABLED", "CAM_LKAS", 0), - ("CHKSUM", "CAM_LKAS", 0), + # sig_name, sig_address + ("LKAS_REQUEST", "CAM_LKAS"), + ("CTR", "CAM_LKAS"), + ("ERR_BIT_1", "CAM_LKAS"), + ("LINE_NOT_VISIBLE", "CAM_LKAS"), + ("BIT_1", "CAM_LKAS"), + ("ERR_BIT_2", "CAM_LKAS"), + ("STEERING_ANGLE", "CAM_LKAS"), + ("ANGLE_ENABLED", "CAM_LKAS"), + ("CHKSUM", "CAM_LKAS"), - ("LINE_VISIBLE", "CAM_LANEINFO", 0), - ("LINE_NOT_VISIBLE", "CAM_LANEINFO", 1), - ("LANE_LINES", "CAM_LANEINFO", 0), - ("BIT1", "CAM_LANEINFO", 0), - ("BIT2", "CAM_LANEINFO", 0), - ("BIT3", "CAM_LANEINFO", 0), - ("NO_ERR_BIT", "CAM_LANEINFO", 1), - ("S1", "CAM_LANEINFO", 0), - ("S1_HBEAM", "CAM_LANEINFO", 0), + ("LINE_VISIBLE", "CAM_LANEINFO"), + ("LINE_NOT_VISIBLE", "CAM_LANEINFO"), + ("LANE_LINES", "CAM_LANEINFO"), + ("BIT1", "CAM_LANEINFO"), + ("BIT2", "CAM_LANEINFO"), + ("BIT3", "CAM_LANEINFO"), + ("NO_ERR_BIT", "CAM_LANEINFO"), + ("S1", "CAM_LANEINFO"), + ("S1_HBEAM", "CAM_LANEINFO"), ] checks += [ diff --git a/selfdrive/car/mazda/interface.py b/selfdrive/car/mazda/interface.py index 8364bf000..fb8edd6f4 100755 --- a/selfdrive/car/mazda/interface.py +++ b/selfdrive/car/mazda/interface.py @@ -22,21 +22,21 @@ class CarInterface(CarInterfaceBase): ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.mazda)] ret.radarOffCan = True - ret.dashcamOnly = candidate not in [CAR.CX9_2021] + ret.dashcamOnly = candidate not in (CAR.CX5_2022, CAR.CX9_2021) ret.steerActuatorDelay = 0.1 ret.steerRateCost = 1.0 ret.steerLimitTimer = 0.8 tire_stiffness_factor = 0.70 # not optimized yet - if candidate == CAR.CX5: + if candidate in (CAR.CX5, CAR.CX5_2022): ret.mass = 3655 * CV.LB_TO_KG + STD_CARGO_KG ret.wheelbase = 2.7 ret.steerRatio = 15.5 ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.19], [0.019]] ret.lateralTuning.pid.kf = 0.00006 - elif candidate in [CAR.CX9, CAR.CX9_2021]: + elif candidate in (CAR.CX9, CAR.CX9_2021): ret.mass = 4217 * CV.LB_TO_KG + STD_CARGO_KG ret.wheelbase = 3.1 ret.steerRatio = 17.6 @@ -58,8 +58,8 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.19], [0.019]] ret.lateralTuning.pid.kf = 0.00006 - # No steer below disable speed - ret.minSteerSpeed = LKAS_LIMITS.DISABLE_SPEED * CV.KPH_TO_MS + if candidate not in (CAR.CX5_2022, ): + ret.minSteerSpeed = LKAS_LIMITS.DISABLE_SPEED * CV.KPH_TO_MS ret.centerToFront = ret.wheelbase * 0.41 @@ -86,7 +86,9 @@ class CarInterface(CarInterfaceBase): # events events = self.create_common_events(ret) - if self.CS.low_speed_alert: + if self.CS.lkas_disabled: + events.add(EventName.lkasDisabled) + elif self.CS.low_speed_alert: events.add(EventName.belowSteerSpeed) ret.events = events.to_msg() @@ -95,6 +97,6 @@ class CarInterface(CarInterfaceBase): return self.CS.out def apply(self, c): - can_sends = self.CC.update(c, self.CS, self.frame) + ret = self.CC.update(c, self.CS, self.frame) self.frame += 1 - return can_sends + return ret diff --git a/selfdrive/car/mazda/values.py b/selfdrive/car/mazda/values.py index 58e1dd703..1fcf18428 100644 --- a/selfdrive/car/mazda/values.py +++ b/selfdrive/car/mazda/values.py @@ -1,5 +1,3 @@ -# flake8: noqa - from selfdrive.car import dbc_dict from cereal import car Ecu = car.CarParams.Ecu @@ -21,7 +19,8 @@ class CAR: CX9 = "MAZDA CX-9" MAZDA3 = "MAZDA 3" MAZDA6 = "MAZDA 6" - CX9_2021 = "MAZDA CX-9 2021" # No Steer Lockout + CX9_2021 = "MAZDA CX-9 2021" + CX5_2022 = "MAZDA CX-5 2022" class LKAS_LIMITS: STEER_THRESHOLD = 15 @@ -37,6 +36,26 @@ class Buttons: FW_VERSIONS = { + CAR.CX5_2022 : { + (Ecu.eps, 0x730, None): [ + b'KSD5-3210X-C-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'PX2G-188K2-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x764, None): [ + b'K131-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.esp, 0x760, None): [ + b'KSD5-437K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x706, None): [ + b'GSH7-67XK2-S\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.transmission, 0x7e1, None): [ + b'PYB2-21PS1-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], + }, CAR.CX5: { (Ecu.eps, 0x730, None): [ b'KJ01-3210X-G-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', @@ -50,9 +69,11 @@ FW_VERSIONS = { b'PYFC-188K2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PYFD-188K2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PYNF-188K2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX2F-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PX2G-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PX2H-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PX2H-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PX2H-188K2-G\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PX2K-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PX38-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PX42-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', @@ -65,6 +86,7 @@ FW_VERSIONS = { b'K131-67XK2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'K131-67XK2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'K131-67XK2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'K131-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.esp, 0x760, None): [ b'K123-437K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', @@ -78,7 +100,9 @@ FW_VERSIONS = { b'B61L-67XK2-T\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'B61L-67XK2-V\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'GSH7-67XK2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-M\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'GSH7-67XK2-N\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'GSH7-67XK2-R\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.transmission, 0x7e1, None): [ b'PA66-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', @@ -87,10 +111,12 @@ FW_VERSIONS = { b'PX68-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PYB1-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PYB1-21PS1-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYB1-21PS1-G\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PYB2-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PYB2-21PS1-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PYB2-21PS1-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PYB2-21PS1-G\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYB2-21PS1-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PYNC-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'SH9T-21PS1-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], @@ -110,16 +136,19 @@ FW_VERSIONS = { b'PYD7-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PYD8-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PYFM-188K2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYFM-188K2-H\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x764, None): [ b'K123-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'K131-67XK2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'K131-67XK2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'TK80-67XK2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'TK80-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.esp, 0x760, None): [ b'TA0B-437K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'TK79-437K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'TK79-437K2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'TM53-437K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'TN40-437K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], @@ -133,6 +162,7 @@ FW_VERSIONS = { b'PXM7-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PXM7-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PYFM-21PS1-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYFM-21PS1-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PYD5-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PYD5-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PYD6-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', @@ -145,10 +175,12 @@ FW_VERSIONS = { b'BHN1-3210X-J-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'K070-3210X-C-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'KR11-3210X-K-00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + ], (Ecu.engine, 0x7e0, None): [ b'P5JD-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PY2P-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYJW-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PYKC-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PYKE-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], @@ -163,11 +195,13 @@ FW_VERSIONS = { (Ecu.fwdCamera, 0x706, None): [ b'B61L-67XK2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'B61L-67XK2-P\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'B61L-67XK2-Q\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'B61L-67XK2-T\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.transmission, 0x7e1, None): [ b'PY2S-21PS1-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'P52G-21PS1-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', + b'PYKA-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PYKE-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', b'PYKE-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00', ], @@ -233,10 +267,8 @@ DBC = { CAR.MAZDA3: dbc_dict('mazda_2017', None), CAR.MAZDA6: dbc_dict('mazda_2017', None), CAR.CX9_2021: dbc_dict('mazda_2017', None), + CAR.CX5_2022: dbc_dict('mazda_2017', None), } # Gen 1 hardware: same CAN messages and same camera -GEN1 = set([CAR.CX5, CAR.CX9, CAR.CX9_2021, CAR.MAZDA3, CAR.MAZDA6]) - -# Cars with a steering lockout -STEER_LOCKOUT_CAR = set([CAR.CX5, CAR.CX9, CAR.MAZDA3, CAR.MAZDA6]) +GEN1 = {CAR.CX5, CAR.CX9, CAR.CX9_2021, CAR.MAZDA3, CAR.MAZDA6, CAR.CX5_2022} diff --git a/selfdrive/car/mock/interface.py b/selfdrive/car/mock/interface.py index 999e735c7..b2e315a5f 100755 --- a/selfdrive/car/mock/interface.py +++ b/selfdrive/car/mock/interface.py @@ -20,7 +20,6 @@ class CarInterface(CarInterfaceBase): cloudlog.debug("Using Mock Car Interface") - # TODO: subscribe to phone sensor self.sensor = messaging.sub_sock('sensorEvents') self.gps = messaging.sub_sock('gpsLocationExternal') @@ -88,4 +87,5 @@ class CarInterface(CarInterfaceBase): def apply(self, c): # in mock no carcontrols - return [] + actuators = car.CarControl.Actuators.new_message() + return actuators, [] diff --git a/selfdrive/car/nissan/carcontroller.py b/selfdrive/car/nissan/carcontroller.py index 41ba9f659..8b30c1124 100644 --- a/selfdrive/car/nissan/carcontroller.py +++ b/selfdrive/car/nissan/carcontroller.py @@ -18,22 +18,20 @@ class CarController(): self.packer = CANPacker(dbc_name) - def update(self, enabled, CS, frame, actuators, cruise_cancel, hud_alert, + def update(self, c, enabled, CS, frame, actuators, cruise_cancel, hud_alert, left_line, right_line, left_lane_depart, right_lane_depart): - """ Controls thread """ - # Send CAN commands. can_sends = [] ### STEER ### - acc_active = bool(CS.out.cruiseState.enabled) + acc_active = CS.out.cruiseState.enabled lkas_hud_msg = CS.lkas_hud_msg lkas_hud_info_msg = CS.lkas_hud_info_msg apply_angle = actuators.steeringAngleDeg - steer_hud_alert = 1 if hud_alert in [VisualAlert.steerRequired, VisualAlert.ldw] else 0 + steer_hud_alert = 1 if hud_alert in (VisualAlert.steerRequired, VisualAlert.ldw) else 0 - if enabled: + if c.active: # # windup slower if self.last_angle * apply_angle > 0. and abs(apply_angle) > abs(self.last_angle): angle_rate_lim = interp(CS.out.vEgo, CarControllerParams.ANGLE_DELTA_BP, CarControllerParams.ANGLE_DELTA_V) @@ -64,14 +62,14 @@ class CarController(): # send acc cancel cmd if drive is disabled but pcm is still on, or if the system can't be activated cruise_cancel = 1 - if self.CP.carFingerprint in [CAR.ROGUE, CAR.XTRAIL, CAR.ALTIMA] and cruise_cancel: + if self.CP.carFingerprint in (CAR.ROGUE, CAR.XTRAIL, CAR.ALTIMA) and cruise_cancel: can_sends.append(nissancan.create_acc_cancel_cmd(self.packer, self.car_fingerprint, CS.cruise_throttle_msg, frame)) # TODO: Find better way to cancel! # For some reason spamming the cancel button is unreliable on the Leaf # We now cancel by making propilot think the seatbelt is unlatched, # this generates a beep and a warning message every time you disengage - if self.CP.carFingerprint in [CAR.LEAF, CAR.LEAF_IC] and frame % 2 == 0: + if self.CP.carFingerprint in (CAR.LEAF, CAR.LEAF_IC) and frame % 2 == 0: can_sends.append(nissancan.create_cancel_msg(self.packer, CS.cancel_msg, cruise_cancel)) can_sends.append(nissancan.create_steering_control( @@ -87,4 +85,7 @@ class CarController(): self.packer, lkas_hud_info_msg, steer_hud_alert )) - return can_sends + new_actuators = actuators.copy() + new_actuators.steeringAngleDeg = apply_angle + + return new_actuators, can_sends diff --git a/selfdrive/car/nissan/carstate.py b/selfdrive/car/nissan/carstate.py index 05191feed..6b030e9b4 100644 --- a/selfdrive/car/nissan/carstate.py +++ b/selfdrive/car/nissan/carstate.py @@ -23,16 +23,16 @@ class CarState(CarStateBase): def update(self, cp, cp_adas, cp_cam): ret = car.CarState.new_message() - if self.CP.carFingerprint in [CAR.ROGUE, CAR.XTRAIL, CAR.ALTIMA]: + if self.CP.carFingerprint in (CAR.ROGUE, CAR.XTRAIL, CAR.ALTIMA): ret.gas = cp.vl["GAS_PEDAL"]["GAS_PEDAL"] - elif self.CP.carFingerprint in [CAR.LEAF, CAR.LEAF_IC]: + elif self.CP.carFingerprint in (CAR.LEAF, CAR.LEAF_IC): ret.gas = cp.vl["CRUISE_THROTTLE"]["GAS_PEDAL"] ret.gasPressed = bool(ret.gas > 3) - if self.CP.carFingerprint in [CAR.ROGUE, CAR.XTRAIL, CAR.ALTIMA]: + if self.CP.carFingerprint in (CAR.ROGUE, CAR.XTRAIL, CAR.ALTIMA): ret.brakePressed = bool(cp.vl["DOORS_LIGHTS"]["USER_BRAKE_PRESSED"]) - elif self.CP.carFingerprint in [CAR.LEAF, CAR.LEAF_IC]: + elif self.CP.carFingerprint in (CAR.LEAF, CAR.LEAF_IC): ret.brakePressed = bool(cp.vl["CRUISE_THROTTLE"]["USER_BRAKE_PRESSED"]) ret.wheelSpeeds = self.get_wheel_speeds( @@ -51,10 +51,10 @@ class CarState(CarStateBase): else: ret.cruiseState.enabled = bool(cp_adas.vl["CRUISE_STATE"]["CRUISE_ENABLED"]) - if self.CP.carFingerprint in [CAR.ROGUE, CAR.XTRAIL]: + if self.CP.carFingerprint in (CAR.ROGUE, CAR.XTRAIL): ret.seatbeltUnlatched = cp.vl["HUD"]["SEATBELT_DRIVER_LATCHED"] == 0 ret.cruiseState.available = bool(cp_cam.vl["PRO_PILOT"]["CRUISE_ON"]) - elif self.CP.carFingerprint in [CAR.LEAF, CAR.LEAF_IC]: + elif self.CP.carFingerprint in (CAR.LEAF, CAR.LEAF_IC): if self.CP.carFingerprint == CAR.LEAF: ret.seatbeltUnlatched = cp.vl["SEATBELT"]["SEATBELT_DRIVER_LATCHED"] == 0 elif self.CP.carFingerprint == CAR.LEAF_IC: @@ -70,7 +70,7 @@ class CarState(CarStateBase): speed = cp_adas.vl["PROPILOT_HUD"]["SET_SPEED"] if speed != 255: - if self.CP.carFingerprint in [CAR.LEAF, CAR.LEAF_IC]: + if self.CP.carFingerprint in (CAR.LEAF, CAR.LEAF_IC): conversion = CV.MPH_TO_MS if cp.vl["HUD_SETTINGS"]["SPEED_MPH"] else CV.KPH_TO_MS else: conversion = CV.MPH_TO_MS if cp.vl["HUD"]["SPEED_MPH"] else CV.KPH_TO_MS @@ -108,7 +108,7 @@ class CarState(CarStateBase): self.cruise_throttle_msg = copy.copy(cp.vl["CRUISE_THROTTLE"]) - if self.CP.carFingerprint in [CAR.LEAF, CAR.LEAF_IC]: + if self.CP.carFingerprint in (CAR.LEAF, CAR.LEAF_IC): self.cancel_msg = copy.copy(cp.vl["CANCEL_MSG"]) if self.CP.carFingerprint != CAR.ALTIMA: @@ -119,27 +119,26 @@ class CarState(CarStateBase): @staticmethod def get_can_parser(CP): - # this function generates lists for signal, messages and initial values signals = [ - # sig_name, sig_address, default - ("WHEEL_SPEED_FL", "WHEEL_SPEEDS_FRONT", 0), - ("WHEEL_SPEED_FR", "WHEEL_SPEEDS_FRONT", 0), - ("WHEEL_SPEED_RL", "WHEEL_SPEEDS_REAR", 0), - ("WHEEL_SPEED_RR", "WHEEL_SPEEDS_REAR", 0), + # sig_name, sig_address + ("WHEEL_SPEED_FL", "WHEEL_SPEEDS_FRONT"), + ("WHEEL_SPEED_FR", "WHEEL_SPEEDS_FRONT"), + ("WHEEL_SPEED_RL", "WHEEL_SPEEDS_REAR"), + ("WHEEL_SPEED_RR", "WHEEL_SPEEDS_REAR"), - ("STEER_ANGLE", "STEER_ANGLE_SENSOR", 0), + ("STEER_ANGLE", "STEER_ANGLE_SENSOR"), - ("DOOR_OPEN_FR", "DOORS_LIGHTS", 1), - ("DOOR_OPEN_FL", "DOORS_LIGHTS", 1), - ("DOOR_OPEN_RR", "DOORS_LIGHTS", 1), - ("DOOR_OPEN_RL", "DOORS_LIGHTS", 1), + ("DOOR_OPEN_FR", "DOORS_LIGHTS"), + ("DOOR_OPEN_FL", "DOORS_LIGHTS"), + ("DOOR_OPEN_RR", "DOORS_LIGHTS"), + ("DOOR_OPEN_RL", "DOORS_LIGHTS"), - ("RIGHT_BLINKER", "LIGHTS", 0), - ("LEFT_BLINKER", "LIGHTS", 0), + ("RIGHT_BLINKER", "LIGHTS"), + ("LEFT_BLINKER", "LIGHTS"), - ("ESP_DISABLED", "ESP", 0), + ("ESP_DISABLED", "ESP"), - ("GEAR_SHIFTER", "GEARBOX", 0), + ("GEAR_SHIFTER", "GEARBOX"), ] checks = [ @@ -153,28 +152,28 @@ class CarState(CarStateBase): ("LIGHTS", 10), ] - if CP.carFingerprint in [CAR.ROGUE, CAR.XTRAIL, CAR.ALTIMA]: + if CP.carFingerprint in (CAR.ROGUE, CAR.XTRAIL, CAR.ALTIMA): signals += [ - ("USER_BRAKE_PRESSED", "DOORS_LIGHTS", 1), + ("USER_BRAKE_PRESSED", "DOORS_LIGHTS"), - ("GAS_PEDAL", "GAS_PEDAL", 0), - ("SEATBELT_DRIVER_LATCHED", "HUD", 0), - ("SPEED_MPH", "HUD", 0), + ("GAS_PEDAL", "GAS_PEDAL"), + ("SEATBELT_DRIVER_LATCHED", "HUD"), + ("SPEED_MPH", "HUD"), - ("PROPILOT_BUTTON", "CRUISE_THROTTLE", 0), - ("CANCEL_BUTTON", "CRUISE_THROTTLE", 0), - ("GAS_PEDAL_INVERTED", "CRUISE_THROTTLE", 0), - ("SET_BUTTON", "CRUISE_THROTTLE", 0), - ("RES_BUTTON", "CRUISE_THROTTLE", 0), - ("FOLLOW_DISTANCE_BUTTON", "CRUISE_THROTTLE", 0), - ("NO_BUTTON_PRESSED", "CRUISE_THROTTLE", 0), - ("GAS_PEDAL", "CRUISE_THROTTLE", 0), - ("USER_BRAKE_PRESSED", "CRUISE_THROTTLE", 0), - ("NEW_SIGNAL_2", "CRUISE_THROTTLE", 0), - ("GAS_PRESSED_INVERTED", "CRUISE_THROTTLE", 0), - ("unsure1", "CRUISE_THROTTLE", 0), - ("unsure2", "CRUISE_THROTTLE", 0), - ("unsure3", "CRUISE_THROTTLE", 0), + ("PROPILOT_BUTTON", "CRUISE_THROTTLE"), + ("CANCEL_BUTTON", "CRUISE_THROTTLE"), + ("GAS_PEDAL_INVERTED", "CRUISE_THROTTLE"), + ("SET_BUTTON", "CRUISE_THROTTLE"), + ("RES_BUTTON", "CRUISE_THROTTLE"), + ("FOLLOW_DISTANCE_BUTTON", "CRUISE_THROTTLE"), + ("NO_BUTTON_PRESSED", "CRUISE_THROTTLE"), + ("GAS_PEDAL", "CRUISE_THROTTLE"), + ("USER_BRAKE_PRESSED", "CRUISE_THROTTLE"), + ("NEW_SIGNAL_2", "CRUISE_THROTTLE"), + ("GAS_PRESSED_INVERTED", "CRUISE_THROTTLE"), + ("unsure1", "CRUISE_THROTTLE"), + ("unsure2", "CRUISE_THROTTLE"), + ("unsure3", "CRUISE_THROTTLE"), ] checks += [ @@ -183,19 +182,19 @@ class CarState(CarStateBase): ("HUD", 25), ] - elif CP.carFingerprint in [CAR.LEAF, CAR.LEAF_IC]: + elif CP.carFingerprint in (CAR.LEAF, CAR.LEAF_IC): signals += [ - ("USER_BRAKE_PRESSED", "CRUISE_THROTTLE", 1), - ("GAS_PEDAL", "CRUISE_THROTTLE", 0), - ("CRUISE_AVAILABLE", "CRUISE_THROTTLE", 0), - ("SPEED_MPH", "HUD_SETTINGS", 0), - ("SEATBELT_DRIVER_LATCHED", "SEATBELT", 0), + ("USER_BRAKE_PRESSED", "CRUISE_THROTTLE"), + ("GAS_PEDAL", "CRUISE_THROTTLE"), + ("CRUISE_AVAILABLE", "CRUISE_THROTTLE"), + ("SPEED_MPH", "HUD_SETTINGS"), + ("SEATBELT_DRIVER_LATCHED", "SEATBELT"), # Copy other values, we use this to cancel - ("CANCEL_SEATBELT", "CANCEL_MSG", 0), - ("NEW_SIGNAL_1", "CANCEL_MSG", 0), - ("NEW_SIGNAL_2", "CANCEL_MSG", 0), - ("NEW_SIGNAL_3", "CANCEL_MSG", 0), + ("CANCEL_SEATBELT", "CANCEL_MSG"), + ("NEW_SIGNAL_1", "CANCEL_MSG"), + ("NEW_SIGNAL_2", "CANCEL_MSG"), + ("NEW_SIGNAL_3", "CANCEL_MSG"), ] checks += [ ("BRAKE_PEDAL", 100), @@ -207,9 +206,9 @@ class CarState(CarStateBase): if CP.carFingerprint == CAR.ALTIMA: signals += [ - ("LKAS_ENABLED", "LKAS_SETTINGS", 0), - ("CRUISE_ENABLED", "CRUISE_STATE", 0), - ("SET_SPEED", "PROPILOT_HUD", 0), + ("LKAS_ENABLED", "LKAS_SETTINGS"), + ("CRUISE_ENABLED", "CRUISE_STATE"), + ("SET_SPEED", "PROPILOT_HUD"), ] checks += [ ("CRUISE_STATE", 10), @@ -218,12 +217,8 @@ class CarState(CarStateBase): ] return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 1) - signals += [ - ("STEER_TORQUE_DRIVER", "STEER_TORQUE_SENSOR", 0), - ] - checks += [ - ("STEER_TORQUE_SENSOR", 100), - ] + signals.append(("STEER_TORQUE_DRIVER", "STEER_TORQUE_SENSOR")) + checks.append(("STEER_TORQUE_SENSOR", 100)) return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 0) @@ -233,14 +228,14 @@ class CarState(CarStateBase): if CP.carFingerprint == CAR.ALTIMA: signals = [ - ("DESIRED_ANGLE", "LKAS", 0), - ("SET_0x80_2", "LKAS", 0), - ("MAX_TORQUE", "LKAS", 0), - ("SET_0x80", "LKAS", 0), - ("COUNTER", "LKAS", 0), - ("LKA_ACTIVE", "LKAS", 0), + ("DESIRED_ANGLE", "LKAS"), + ("SET_0x80_2", "LKAS"), + ("MAX_TORQUE", "LKAS"), + ("SET_0x80", "LKAS"), + ("COUNTER", "LKAS"), + ("LKA_ACTIVE", "LKAS"), - ("CRUISE_ON", "PRO_PILOT", 0), + ("CRUISE_ON", "PRO_PILOT"), ] checks = [ ("LKAS", 100), @@ -248,85 +243,85 @@ class CarState(CarStateBase): ] else: signals = [ - # sig_name, sig_address, default - ("LKAS_ENABLED", "LKAS_SETTINGS", 0), + # sig_name, sig_address + ("LKAS_ENABLED", "LKAS_SETTINGS"), - ("CRUISE_ENABLED", "CRUISE_STATE", 0), + ("CRUISE_ENABLED", "CRUISE_STATE"), - ("DESIRED_ANGLE", "LKAS", 0), - ("SET_0x80_2", "LKAS", 0), - ("MAX_TORQUE", "LKAS", 0), - ("SET_0x80", "LKAS", 0), - ("COUNTER", "LKAS", 0), - ("LKA_ACTIVE", "LKAS", 0), + ("DESIRED_ANGLE", "LKAS"), + ("SET_0x80_2", "LKAS"), + ("MAX_TORQUE", "LKAS"), + ("SET_0x80", "LKAS"), + ("COUNTER", "LKAS"), + ("LKA_ACTIVE", "LKAS"), # Below are the HUD messages. We copy the stock message and modify - ("LARGE_WARNING_FLASHING", "PROPILOT_HUD", 0), - ("SIDE_RADAR_ERROR_FLASHING1", "PROPILOT_HUD", 0), - ("SIDE_RADAR_ERROR_FLASHING2", "PROPILOT_HUD", 0), - ("LEAD_CAR", "PROPILOT_HUD", 0), - ("LEAD_CAR_ERROR", "PROPILOT_HUD", 0), - ("FRONT_RADAR_ERROR", "PROPILOT_HUD", 0), - ("FRONT_RADAR_ERROR_FLASHING", "PROPILOT_HUD", 0), - ("SIDE_RADAR_ERROR_FLASHING3", "PROPILOT_HUD", 0), - ("LKAS_ERROR_FLASHING", "PROPILOT_HUD", 0), - ("SAFETY_SHIELD_ACTIVE", "PROPILOT_HUD", 0), - ("RIGHT_LANE_GREEN_FLASH", "PROPILOT_HUD", 0), - ("LEFT_LANE_GREEN_FLASH", "PROPILOT_HUD", 0), - ("FOLLOW_DISTANCE", "PROPILOT_HUD", 0), - ("AUDIBLE_TONE", "PROPILOT_HUD", 0), - ("SPEED_SET_ICON", "PROPILOT_HUD", 0), - ("SMALL_STEERING_WHEEL_ICON", "PROPILOT_HUD", 0), - ("unknown59", "PROPILOT_HUD", 0), - ("unknown55", "PROPILOT_HUD", 0), - ("unknown26", "PROPILOT_HUD", 0), - ("unknown28", "PROPILOT_HUD", 0), - ("unknown31", "PROPILOT_HUD", 0), - ("SET_SPEED", "PROPILOT_HUD", 0), - ("unknown43", "PROPILOT_HUD", 0), - ("unknown08", "PROPILOT_HUD", 0), - ("unknown05", "PROPILOT_HUD", 0), - ("unknown02", "PROPILOT_HUD", 0), + ("LARGE_WARNING_FLASHING", "PROPILOT_HUD"), + ("SIDE_RADAR_ERROR_FLASHING1", "PROPILOT_HUD"), + ("SIDE_RADAR_ERROR_FLASHING2", "PROPILOT_HUD"), + ("LEAD_CAR", "PROPILOT_HUD"), + ("LEAD_CAR_ERROR", "PROPILOT_HUD"), + ("FRONT_RADAR_ERROR", "PROPILOT_HUD"), + ("FRONT_RADAR_ERROR_FLASHING", "PROPILOT_HUD"), + ("SIDE_RADAR_ERROR_FLASHING3", "PROPILOT_HUD"), + ("LKAS_ERROR_FLASHING", "PROPILOT_HUD"), + ("SAFETY_SHIELD_ACTIVE", "PROPILOT_HUD"), + ("RIGHT_LANE_GREEN_FLASH", "PROPILOT_HUD"), + ("LEFT_LANE_GREEN_FLASH", "PROPILOT_HUD"), + ("FOLLOW_DISTANCE", "PROPILOT_HUD"), + ("AUDIBLE_TONE", "PROPILOT_HUD"), + ("SPEED_SET_ICON", "PROPILOT_HUD"), + ("SMALL_STEERING_WHEEL_ICON", "PROPILOT_HUD"), + ("unknown59", "PROPILOT_HUD"), + ("unknown55", "PROPILOT_HUD"), + ("unknown26", "PROPILOT_HUD"), + ("unknown28", "PROPILOT_HUD"), + ("unknown31", "PROPILOT_HUD"), + ("SET_SPEED", "PROPILOT_HUD"), + ("unknown43", "PROPILOT_HUD"), + ("unknown08", "PROPILOT_HUD"), + ("unknown05", "PROPILOT_HUD"), + ("unknown02", "PROPILOT_HUD"), - ("NA_HIGH_ACCEL_TEMP", "PROPILOT_HUD_INFO_MSG", 0), - ("SIDE_RADAR_NA_HIGH_CABIN_TEMP", "PROPILOT_HUD_INFO_MSG", 0), - ("SIDE_RADAR_MALFUNCTION", "PROPILOT_HUD_INFO_MSG", 0), - ("LKAS_MALFUNCTION", "PROPILOT_HUD_INFO_MSG", 0), - ("FRONT_RADAR_MALFUNCTION", "PROPILOT_HUD_INFO_MSG", 0), - ("SIDE_RADAR_NA_CLEAN_REAR_CAMERA", "PROPILOT_HUD_INFO_MSG", 0), - ("NA_POOR_ROAD_CONDITIONS", "PROPILOT_HUD_INFO_MSG", 0), - ("CURRENTLY_UNAVAILABLE", "PROPILOT_HUD_INFO_MSG", 0), - ("SAFETY_SHIELD_OFF", "PROPILOT_HUD_INFO_MSG", 0), - ("FRONT_COLLISION_NA_FRONT_RADAR_OBSTRUCTION", "PROPILOT_HUD_INFO_MSG", 0), - ("PEDAL_MISSAPPLICATION_SYSTEM_ACTIVATED", "PROPILOT_HUD_INFO_MSG", 0), - ("SIDE_IMPACT_NA_RADAR_OBSTRUCTION", "PROPILOT_HUD_INFO_MSG", 0), - ("WARNING_DO_NOT_ENTER", "PROPILOT_HUD_INFO_MSG", 0), - ("SIDE_IMPACT_SYSTEM_OFF", "PROPILOT_HUD_INFO_MSG", 0), - ("SIDE_IMPACT_MALFUNCTION", "PROPILOT_HUD_INFO_MSG", 0), - ("FRONT_COLLISION_MALFUNCTION", "PROPILOT_HUD_INFO_MSG", 0), - ("SIDE_RADAR_MALFUNCTION2", "PROPILOT_HUD_INFO_MSG", 0), - ("LKAS_MALFUNCTION2", "PROPILOT_HUD_INFO_MSG", 0), - ("FRONT_RADAR_MALFUNCTION2", "PROPILOT_HUD_INFO_MSG", 0), - ("PROPILOT_NA_MSGS", "PROPILOT_HUD_INFO_MSG", 0), - ("BOTTOM_MSG", "PROPILOT_HUD_INFO_MSG", 0), - ("HANDS_ON_WHEEL_WARNING", "PROPILOT_HUD_INFO_MSG", 0), - ("WARNING_STEP_ON_BRAKE_NOW", "PROPILOT_HUD_INFO_MSG", 0), - ("PROPILOT_NA_FRONT_CAMERA_OBSTRUCTED", "PROPILOT_HUD_INFO_MSG", 0), - ("PROPILOT_NA_HIGH_CABIN_TEMP", "PROPILOT_HUD_INFO_MSG", 0), - ("WARNING_PROPILOT_MALFUNCTION", "PROPILOT_HUD_INFO_MSG", 0), - ("ACC_UNAVAILABLE_HIGH_CABIN_TEMP", "PROPILOT_HUD_INFO_MSG", 0), - ("ACC_NA_FRONT_CAMERA_IMPARED", "PROPILOT_HUD_INFO_MSG", 0), - ("unknown07", "PROPILOT_HUD_INFO_MSG", 0), - ("unknown10", "PROPILOT_HUD_INFO_MSG", 0), - ("unknown15", "PROPILOT_HUD_INFO_MSG", 0), - ("unknown23", "PROPILOT_HUD_INFO_MSG", 0), - ("unknown19", "PROPILOT_HUD_INFO_MSG", 0), - ("unknown31", "PROPILOT_HUD_INFO_MSG", 0), - ("unknown32", "PROPILOT_HUD_INFO_MSG", 0), - ("unknown46", "PROPILOT_HUD_INFO_MSG", 0), - ("unknown61", "PROPILOT_HUD_INFO_MSG", 0), - ("unknown55", "PROPILOT_HUD_INFO_MSG", 0), - ("unknown50", "PROPILOT_HUD_INFO_MSG", 0), + ("NA_HIGH_ACCEL_TEMP", "PROPILOT_HUD_INFO_MSG"), + ("SIDE_RADAR_NA_HIGH_CABIN_TEMP", "PROPILOT_HUD_INFO_MSG"), + ("SIDE_RADAR_MALFUNCTION", "PROPILOT_HUD_INFO_MSG"), + ("LKAS_MALFUNCTION", "PROPILOT_HUD_INFO_MSG"), + ("FRONT_RADAR_MALFUNCTION", "PROPILOT_HUD_INFO_MSG"), + ("SIDE_RADAR_NA_CLEAN_REAR_CAMERA", "PROPILOT_HUD_INFO_MSG"), + ("NA_POOR_ROAD_CONDITIONS", "PROPILOT_HUD_INFO_MSG"), + ("CURRENTLY_UNAVAILABLE", "PROPILOT_HUD_INFO_MSG"), + ("SAFETY_SHIELD_OFF", "PROPILOT_HUD_INFO_MSG"), + ("FRONT_COLLISION_NA_FRONT_RADAR_OBSTRUCTION", "PROPILOT_HUD_INFO_MSG"), + ("PEDAL_MISSAPPLICATION_SYSTEM_ACTIVATED", "PROPILOT_HUD_INFO_MSG"), + ("SIDE_IMPACT_NA_RADAR_OBSTRUCTION", "PROPILOT_HUD_INFO_MSG"), + ("WARNING_DO_NOT_ENTER", "PROPILOT_HUD_INFO_MSG"), + ("SIDE_IMPACT_SYSTEM_OFF", "PROPILOT_HUD_INFO_MSG"), + ("SIDE_IMPACT_MALFUNCTION", "PROPILOT_HUD_INFO_MSG"), + ("FRONT_COLLISION_MALFUNCTION", "PROPILOT_HUD_INFO_MSG"), + ("SIDE_RADAR_MALFUNCTION2", "PROPILOT_HUD_INFO_MSG"), + ("LKAS_MALFUNCTION2", "PROPILOT_HUD_INFO_MSG"), + ("FRONT_RADAR_MALFUNCTION2", "PROPILOT_HUD_INFO_MSG"), + ("PROPILOT_NA_MSGS", "PROPILOT_HUD_INFO_MSG"), + ("BOTTOM_MSG", "PROPILOT_HUD_INFO_MSG"), + ("HANDS_ON_WHEEL_WARNING", "PROPILOT_HUD_INFO_MSG"), + ("WARNING_STEP_ON_BRAKE_NOW", "PROPILOT_HUD_INFO_MSG"), + ("PROPILOT_NA_FRONT_CAMERA_OBSTRUCTED", "PROPILOT_HUD_INFO_MSG"), + ("PROPILOT_NA_HIGH_CABIN_TEMP", "PROPILOT_HUD_INFO_MSG"), + ("WARNING_PROPILOT_MALFUNCTION", "PROPILOT_HUD_INFO_MSG"), + ("ACC_UNAVAILABLE_HIGH_CABIN_TEMP", "PROPILOT_HUD_INFO_MSG"), + ("ACC_NA_FRONT_CAMERA_IMPARED", "PROPILOT_HUD_INFO_MSG"), + ("unknown07", "PROPILOT_HUD_INFO_MSG"), + ("unknown10", "PROPILOT_HUD_INFO_MSG"), + ("unknown15", "PROPILOT_HUD_INFO_MSG"), + ("unknown23", "PROPILOT_HUD_INFO_MSG"), + ("unknown19", "PROPILOT_HUD_INFO_MSG"), + ("unknown31", "PROPILOT_HUD_INFO_MSG"), + ("unknown32", "PROPILOT_HUD_INFO_MSG"), + ("unknown46", "PROPILOT_HUD_INFO_MSG"), + ("unknown61", "PROPILOT_HUD_INFO_MSG"), + ("unknown55", "PROPILOT_HUD_INFO_MSG"), + ("unknown50", "PROPILOT_HUD_INFO_MSG"), ] checks = [ @@ -344,21 +339,12 @@ class CarState(CarStateBase): signals = [] checks = [] - if CP.carFingerprint in [CAR.ROGUE, CAR.XTRAIL]: - signals += [ - ("CRUISE_ON", "PRO_PILOT", 0), - ] - checks += [ - ("PRO_PILOT", 100), - ] + if CP.carFingerprint in (CAR.ROGUE, CAR.XTRAIL): + signals.append(("CRUISE_ON", "PRO_PILOT")) + checks.append(("PRO_PILOT", 100)) elif CP.carFingerprint == CAR.ALTIMA: - signals += [ - ("STEER_TORQUE_DRIVER", "STEER_TORQUE_SENSOR", 0), - ] - checks += [ - ("STEER_TORQUE_SENSOR", 100), - ] + signals.append(("STEER_TORQUE_DRIVER", "STEER_TORQUE_SENSOR")) + checks.append(("STEER_TORQUE_SENSOR", 100)) return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 0) - return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 1) diff --git a/selfdrive/car/nissan/interface.py b/selfdrive/car/nissan/interface.py index 18ae885f8..c32fb1378 100644 --- a/selfdrive/car/nissan/interface.py +++ b/selfdrive/car/nissan/interface.py @@ -16,17 +16,17 @@ class CarInterface(CarInterfaceBase): ret.carName = "nissan" ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.nissan)] - ret.steerLimitAlert = False + ret.steerLimitTimer = 1.0 ret.steerRateCost = 0.5 ret.steerActuatorDelay = 0.1 - if candidate in [CAR.ROGUE, CAR.XTRAIL]: + if candidate in (CAR.ROGUE, CAR.XTRAIL): ret.mass = 1610 + STD_CARGO_KG ret.wheelbase = 2.705 ret.centerToFront = ret.wheelbase * 0.44 ret.steerRatio = 17 - elif candidate in [CAR.LEAF, CAR.LEAF_IC]: + elif candidate in (CAR.LEAF, CAR.LEAF_IC): ret.mass = 1610 + STD_CARGO_KG ret.wheelbase = 2.705 ret.centerToFront = ret.wheelbase * 0.44 @@ -78,9 +78,10 @@ class CarInterface(CarInterfaceBase): return self.CS.out def apply(self, c): - can_sends = self.CC.update(c.enabled, self.CS, self.frame, c.actuators, - c.cruiseControl.cancel, c.hudControl.visualAlert, - c.hudControl.leftLaneVisible, c.hudControl.rightLaneVisible, - c.hudControl.leftLaneDepart, c.hudControl.rightLaneDepart) + hud_control = c.hudControl + ret = self.CC.update(c, c.enabled, self.CS, self.frame, c.actuators, + c.cruiseControl.cancel, hud_control.visualAlert, + hud_control.leftLaneVisible, hud_control.rightLaneVisible, + hud_control.leftLaneDepart, hud_control.rightLaneDepart) self.frame += 1 - return can_sends + return ret diff --git a/selfdrive/car/nissan/values.py b/selfdrive/car/nissan/values.py index 22bd4a129..f7001d141 100644 --- a/selfdrive/car/nissan/values.py +++ b/selfdrive/car/nissan/values.py @@ -1,5 +1,3 @@ -# flake8: noqa - from selfdrive.car import dbc_dict from cereal import car Ecu = car.CarParams.Ecu @@ -71,7 +69,7 @@ FW_VERSIONS = { (Ecu.gateway, 0x18dad0f1, None): [ b'284U29HE0A', ], - }, + }, CAR.LEAF_IC: { (Ecu.fwdCamera, 0x707, None): [ b'5SH1BDB\x04\x18\x00\x00\x00\x00\x00_-?\x04\x91\xf2\x00\x00\x00\x80', diff --git a/selfdrive/car/subaru/carcontroller.py b/selfdrive/car/subaru/carcontroller.py index 6163d7329..afc91f475 100644 --- a/selfdrive/car/subaru/carcontroller.py +++ b/selfdrive/car/subaru/carcontroller.py @@ -8,35 +8,35 @@ class CarController(): def __init__(self, dbc_name, CP, VM): self.apply_steer_last = 0 self.es_distance_cnt = -1 - self.es_accel_cnt = -1 self.es_lkas_cnt = -1 self.cruise_button_prev = 0 self.steer_rate_limited = False + self.p = CarControllerParams(CP) self.packer = CANPacker(DBC[CP.carFingerprint]['pt']) - def update(self, enabled, CS, frame, actuators, pcm_cancel_cmd, visual_alert, left_line, right_line, left_lane_depart, right_lane_depart): + def update(self, c, enabled, CS, frame, actuators, pcm_cancel_cmd, visual_alert, left_line, right_line, left_lane_depart, right_lane_depart): can_sends = [] # *** steering *** - if (frame % CarControllerParams.STEER_STEP) == 0: + if (frame % self.p.STEER_STEP) == 0: - apply_steer = int(round(actuators.steer * CarControllerParams.STEER_MAX)) + apply_steer = int(round(actuators.steer * self.p.STEER_MAX)) # limits due to driver torque new_steer = int(round(apply_steer)) - apply_steer = apply_std_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, CarControllerParams) + apply_steer = apply_std_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, self.p) self.steer_rate_limited = new_steer != apply_steer - if not enabled: + if not c.active: apply_steer = 0 if CS.CP.carFingerprint in PREGLOBAL_CARS: - can_sends.append(subarucan.create_preglobal_steering_control(self.packer, apply_steer, frame, CarControllerParams.STEER_STEP)) + can_sends.append(subarucan.create_preglobal_steering_control(self.packer, apply_steer, frame, self.p.STEER_STEP)) else: - can_sends.append(subarucan.create_steering_control(self.packer, apply_steer, frame, CarControllerParams.STEER_STEP)) + can_sends.append(subarucan.create_steering_control(self.packer, apply_steer, frame, self.p.STEER_STEP)) self.apply_steer_last = apply_steer @@ -44,7 +44,7 @@ class CarController(): # *** alerts and pcm cancel *** if CS.CP.carFingerprint in PREGLOBAL_CARS: - if self.es_accel_cnt != CS.es_accel_msg["Counter"]: + if self.es_distance_cnt != CS.es_distance_msg["Counter"]: # 1 = main, 2 = set shallow, 3 = set deep, 4 = resume shallow, 5 = resume deep # disengage ACC when OP is disengaged if pcm_cancel_cmd: @@ -60,8 +60,8 @@ class CarController(): cruise_button = 0 self.cruise_button_prev = cruise_button - can_sends.append(subarucan.create_es_throttle_control(self.packer, cruise_button, CS.es_accel_msg)) - self.es_accel_cnt = CS.es_accel_msg["Counter"] + can_sends.append(subarucan.create_preglobal_es_distance(self.packer, cruise_button, CS.es_distance_msg)) + self.es_distance_cnt = CS.es_distance_msg["Counter"] else: if self.es_distance_cnt != CS.es_distance_msg["Counter"]: @@ -72,4 +72,7 @@ class CarController(): can_sends.append(subarucan.create_es_lkas(self.packer, CS.es_lkas_msg, enabled, visual_alert, left_line, right_line, left_lane_depart, right_lane_depart)) self.es_lkas_cnt = CS.es_lkas_msg["Counter"] - return can_sends + new_actuators = actuators.copy() + new_actuators.steer = self.apply_steer_last / self.p.STEER_MAX + + return new_actuators, can_sends diff --git a/selfdrive/car/subaru/carstate.py b/selfdrive/car/subaru/carstate.py index 1f56f09ff..1eefb1858 100644 --- a/selfdrive/car/subaru/carstate.py +++ b/selfdrive/car/subaru/carstate.py @@ -65,41 +65,39 @@ class CarState(CarStateBase): ret.steerError = cp.vl["Steering_Torque"]["Steer_Error_1"] == 1 if self.car_fingerprint in PREGLOBAL_CARS: - self.cruise_button = cp_cam.vl["ES_CruiseThrottle"]["Cruise_Button"] + self.cruise_button = cp_cam.vl["ES_Distance"]["Cruise_Button"] self.ready = not cp_cam.vl["ES_DashStatus"]["Not_Ready_Startup"] - self.es_accel_msg = copy.copy(cp_cam.vl["ES_CruiseThrottle"]) else: ret.steerWarning = cp.vl["Steering_Torque"]["Steer_Warning"] == 1 ret.cruiseState.nonAdaptive = cp_cam.vl["ES_DashStatus"]["Conventional_Cruise"] == 1 - self.es_distance_msg = copy.copy(cp_cam.vl["ES_Distance"]) self.es_lkas_msg = copy.copy(cp_cam.vl["ES_LKAS_State"]) + self.es_distance_msg = copy.copy(cp_cam.vl["ES_Distance"]) return ret @staticmethod def get_can_parser(CP): - # this function generates lists for signal, messages and initial values signals = [ - # sig_name, sig_address, default - ("Steer_Torque_Sensor", "Steering_Torque", 0), - ("Steering_Angle", "Steering_Torque", 0), - ("Steer_Error_1", "Steering_Torque", 0), - ("Cruise_On", "CruiseControl", 0), - ("Cruise_Activated", "CruiseControl", 0), - ("Brake_Pedal", "Brake_Pedal", 0), - ("Throttle_Pedal", "Throttle", 0), - ("LEFT_BLINKER", "Dashlights", 0), - ("RIGHT_BLINKER", "Dashlights", 0), - ("SEATBELT_FL", "Dashlights", 0), - ("FL", "Wheel_Speeds", 0), - ("FR", "Wheel_Speeds", 0), - ("RL", "Wheel_Speeds", 0), - ("RR", "Wheel_Speeds", 0), - ("DOOR_OPEN_FR", "BodyInfo", 1), - ("DOOR_OPEN_FL", "BodyInfo", 1), - ("DOOR_OPEN_RR", "BodyInfo", 1), - ("DOOR_OPEN_RL", "BodyInfo", 1), - ("Gear", "Transmission", 0), + # sig_name, sig_address + ("Steer_Torque_Sensor", "Steering_Torque"), + ("Steering_Angle", "Steering_Torque"), + ("Steer_Error_1", "Steering_Torque"), + ("Cruise_On", "CruiseControl"), + ("Cruise_Activated", "CruiseControl"), + ("Brake_Pedal", "Brake_Pedal"), + ("Throttle_Pedal", "Throttle"), + ("LEFT_BLINKER", "Dashlights"), + ("RIGHT_BLINKER", "Dashlights"), + ("SEATBELT_FL", "Dashlights"), + ("FL", "Wheel_Speeds"), + ("FR", "Wheel_Speeds"), + ("RL", "Wheel_Speeds"), + ("RR", "Wheel_Speeds"), + ("DOOR_OPEN_FR", "BodyInfo"), + ("DOOR_OPEN_FL", "BodyInfo"), + ("DOOR_OPEN_RR", "BodyInfo"), + ("DOOR_OPEN_RL", "BodyInfo"), + ("Gear", "Transmission"), ] checks = [ @@ -115,20 +113,18 @@ class CarState(CarStateBase): if CP.enableBsm: signals += [ - ("L_ADJACENT", "BSD_RCTA", 0), - ("R_ADJACENT", "BSD_RCTA", 0), - ("L_APPROACHING", "BSD_RCTA", 0), - ("R_APPROACHING", "BSD_RCTA", 0), - ] - checks += [ - ("BSD_RCTA", 17), + ("L_ADJACENT", "BSD_RCTA"), + ("R_ADJACENT", "BSD_RCTA"), + ("L_APPROACHING", "BSD_RCTA"), + ("R_APPROACHING", "BSD_RCTA"), ] + checks.append(("BSD_RCTA", 17)) if CP.carFingerprint not in PREGLOBAL_CARS: signals += [ - ("Steer_Warning", "Steering_Torque", 0), - ("Brake", "Brake_Status", 0), - ("UNITS", "Dashlights", 0), + ("Steer_Warning", "Steering_Torque"), + ("Brake", "Brake_Status"), + ("UNITS", "Dashlights"), ] checks += [ @@ -138,13 +134,9 @@ class CarState(CarStateBase): ("CruiseControl", 20), ] else: - signals += [ - ("UNITS", "Dash_State2", 0), - ] + signals.append(("UNITS", "Dash_State2")) - checks += [ - ("Dash_State2", 1), - ] + checks.append(("Dash_State2", 1)) if CP.carFingerprint == CAR.FORESTER_PREGLOBAL: checks += [ @@ -153,7 +145,7 @@ class CarState(CarStateBase): ("CruiseControl", 50), ] - if CP.carFingerprint in [CAR.LEGACY_PREGLOBAL, CAR.OUTBACK_PREGLOBAL, CAR.OUTBACK_PREGLOBAL_2018]: + if CP.carFingerprint in (CAR.LEGACY_PREGLOBAL, CAR.OUTBACK_PREGLOBAL, CAR.OUTBACK_PREGLOBAL_2018): checks += [ ("Dashlights", 10), ("CruiseControl", 50), @@ -165,70 +157,70 @@ class CarState(CarStateBase): def get_cam_can_parser(CP): if CP.carFingerprint in PREGLOBAL_CARS: signals = [ - ("Cruise_Set_Speed", "ES_DashStatus", 0), - ("Not_Ready_Startup", "ES_DashStatus", 0), + ("Cruise_Set_Speed", "ES_DashStatus"), + ("Not_Ready_Startup", "ES_DashStatus"), - ("Throttle_Cruise", "ES_CruiseThrottle", 0), - ("Signal1", "ES_CruiseThrottle", 0), - ("Cruise_Activated", "ES_CruiseThrottle", 0), - ("Signal2", "ES_CruiseThrottle", 0), - ("Brake_On", "ES_CruiseThrottle", 0), - ("Distance_Swap", "ES_CruiseThrottle", 0), - ("Standstill", "ES_CruiseThrottle", 0), - ("Signal3", "ES_CruiseThrottle", 0), - ("Close_Distance", "ES_CruiseThrottle", 0), - ("Signal4", "ES_CruiseThrottle", 0), - ("Standstill_2", "ES_CruiseThrottle", 0), - ("Cruise_Fault", "ES_CruiseThrottle", 0), - ("Signal5", "ES_CruiseThrottle", 0), - ("Counter", "ES_CruiseThrottle", 0), - ("Signal6", "ES_CruiseThrottle", 0), - ("Cruise_Button", "ES_CruiseThrottle", 0), - ("Signal7", "ES_CruiseThrottle", 0), + ("Cruise_Throttle", "ES_Distance"), + ("Signal1", "ES_Distance"), + ("Car_Follow", "ES_Distance"), + ("Signal2", "ES_Distance"), + ("Brake_On", "ES_Distance"), + ("Distance_Swap", "ES_Distance"), + ("Standstill", "ES_Distance"), + ("Signal3", "ES_Distance"), + ("Close_Distance", "ES_Distance"), + ("Signal4", "ES_Distance"), + ("Standstill_2", "ES_Distance"), + ("Cruise_Fault", "ES_Distance"), + ("Signal5", "ES_Distance"), + ("Counter", "ES_Distance"), + ("Signal6", "ES_Distance"), + ("Cruise_Button", "ES_Distance"), + ("Signal7", "ES_Distance"), ] checks = [ ("ES_DashStatus", 20), - ("ES_CruiseThrottle", 20), + ("ES_Distance", 20), ] else: signals = [ - ("Cruise_Set_Speed", "ES_DashStatus", 0), - ("Conventional_Cruise", "ES_DashStatus", 0), + ("Cruise_Set_Speed", "ES_DashStatus"), + ("Conventional_Cruise", "ES_DashStatus"), - ("Counter", "ES_Distance", 0), - ("Signal1", "ES_Distance", 0), - ("Cruise_Fault", "ES_Distance", 0), - ("Cruise_Throttle", "ES_Distance", 0), - ("Signal2", "ES_Distance", 0), - ("Car_Follow", "ES_Distance", 0), - ("Signal3", "ES_Distance", 0), - ("Cruise_Brake_Active", "ES_Distance", 0), - ("Distance_Swap", "ES_Distance", 0), - ("Cruise_EPB", "ES_Distance", 0), - ("Signal4", "ES_Distance", 0), - ("Close_Distance", "ES_Distance", 0), - ("Signal5", "ES_Distance", 0), - ("Cruise_Cancel", "ES_Distance", 0), - ("Cruise_Set", "ES_Distance", 0), - ("Cruise_Resume", "ES_Distance", 0), - ("Signal6", "ES_Distance", 0), + ("Counter", "ES_Distance"), + ("Signal1", "ES_Distance"), + ("Cruise_Fault", "ES_Distance"), + ("Cruise_Throttle", "ES_Distance"), + ("Signal2", "ES_Distance"), + ("Car_Follow", "ES_Distance"), + ("Signal3", "ES_Distance"), + ("Cruise_Brake_Active", "ES_Distance"), + ("Distance_Swap", "ES_Distance"), + ("Cruise_EPB", "ES_Distance"), + ("Signal4", "ES_Distance"), + ("Close_Distance", "ES_Distance"), + ("Signal5", "ES_Distance"), + ("Cruise_Cancel", "ES_Distance"), + ("Cruise_Set", "ES_Distance"), + ("Cruise_Resume", "ES_Distance"), + ("Signal6", "ES_Distance"), - ("Counter", "ES_LKAS_State", 0), - ("LKAS_Alert_Msg", "ES_LKAS_State", 0), - ("Signal1", "ES_LKAS_State", 0), - ("LKAS_ACTIVE", "ES_LKAS_State", 0), - ("LKAS_Dash_State", "ES_LKAS_State", 0), - ("Signal2", "ES_LKAS_State", 0), - ("Backward_Speed_Limit_Menu", "ES_LKAS_State", 0), - ("LKAS_Left_Line_Enable", "ES_LKAS_State", 0), - ("LKAS_Left_Line_Light_Blink", "ES_LKAS_State", 0), - ("LKAS_Right_Line_Enable", "ES_LKAS_State", 0), - ("LKAS_Right_Line_Light_Blink", "ES_LKAS_State", 0), - ("LKAS_Left_Line_Visible", "ES_LKAS_State", 0), - ("LKAS_Right_Line_Visible", "ES_LKAS_State", 0), - ("LKAS_Alert", "ES_LKAS_State", 0), - ("Signal3", "ES_LKAS_State", 0), + ("Counter", "ES_LKAS_State"), + ("LKAS_Alert_Msg", "ES_LKAS_State"), + ("Signal1", "ES_LKAS_State"), + ("LKAS_ACTIVE", "ES_LKAS_State"), + ("LKAS_Dash_State", "ES_LKAS_State"), + ("Signal2", "ES_LKAS_State"), + ("Backward_Speed_Limit_Menu", "ES_LKAS_State"), + ("LKAS_Left_Line_Enable", "ES_LKAS_State"), + ("LKAS_Left_Line_Light_Blink", "ES_LKAS_State"), + ("LKAS_Right_Line_Enable", "ES_LKAS_State"), + ("LKAS_Right_Line_Light_Blink", "ES_LKAS_State"), + ("LKAS_Left_Line_Visible", "ES_LKAS_State"), + ("LKAS_Right_Line_Visible", "ES_LKAS_State"), + ("LKAS_Alert", "ES_LKAS_State"), + ("Signal3", "ES_LKAS_State"), ] checks = [ diff --git a/selfdrive/car/subaru/interface.py b/selfdrive/car/subaru/interface.py index 86bba542c..8c6d18864 100644 --- a/selfdrive/car/subaru/interface.py +++ b/selfdrive/car/subaru/interface.py @@ -45,6 +45,16 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0., 20.], [0., 20.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.2, 0.3], [0.02, 0.03]] + if candidate == CAR.IMPREZA_2020: + ret.mass = 1480. + STD_CARGO_KG + ret.wheelbase = 2.67 + ret.centerToFront = ret.wheelbase * 0.5 + ret.steerRatio = 17 # learned, 14 stock + ret.steerActuatorDelay = 0.1 + ret.lateralTuning.pid.kf = 0.00005 + ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0., 14., 23.], [0., 14., 23.]] + ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.045, 0.042, 0.20], [0.04, 0.035, 0.045]] + if candidate == CAR.FORESTER: ret.mass = 1568. + STD_CARGO_KG ret.wheelbase = 2.67 @@ -55,7 +65,7 @@ class CarInterface(CarInterfaceBase): ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0., 14., 23.], [0., 14., 23.]] ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.01, 0.065, 0.2], [0.001, 0.015, 0.025]] - if candidate in [CAR.FORESTER_PREGLOBAL, CAR.OUTBACK_PREGLOBAL_2018]: + if candidate in (CAR.FORESTER_PREGLOBAL, CAR.OUTBACK_PREGLOBAL_2018): ret.safetyConfigs[0].safetyParam = 1 # Outback 2018-2019 and Forester have reversed driver torque signal ret.mass = 1568 + STD_CARGO_KG ret.wheelbase = 2.67 @@ -112,8 +122,9 @@ class CarInterface(CarInterfaceBase): return self.CS.out def apply(self, c): - can_sends = self.CC.update(c.enabled, self.CS, self.frame, c.actuators, - c.cruiseControl.cancel, c.hudControl.visualAlert, - c.hudControl.leftLaneVisible, c.hudControl.rightLaneVisible, c.hudControl.leftLaneDepart, c.hudControl.rightLaneDepart) + hud_control = c.hudControl + ret = self.CC.update(c, c.enabled, self.CS, self.frame, c.actuators, + c.cruiseControl.cancel, hud_control.visualAlert, + hud_control.leftLaneVisible, hud_control.rightLaneVisible, hud_control.leftLaneDepart, hud_control.rightLaneDepart) self.frame += 1 - return can_sends + return ret diff --git a/selfdrive/car/subaru/subarucan.py b/selfdrive/car/subaru/subarucan.py index 6485de790..86ec5e8bd 100644 --- a/selfdrive/car/subaru/subarucan.py +++ b/selfdrive/car/subaru/subarucan.py @@ -80,11 +80,11 @@ def create_preglobal_steering_control(packer, apply_steer, frame, steer_step): return packer.make_can_msg("ES_LKAS", 0, values) -def create_es_throttle_control(packer, cruise_button, es_accel_msg): +def create_preglobal_es_distance(packer, cruise_button, es_distance_msg): - values = copy.copy(es_accel_msg) + values = copy.copy(es_distance_msg) values["Cruise_Button"] = cruise_button - values["Checksum"] = subaru_preglobal_checksum(packer, values, "ES_CruiseThrottle") + values["Checksum"] = subaru_preglobal_checksum(packer, values, "ES_Distance") - return packer.make_can_msg("ES_CruiseThrottle", 0, values) + return packer.make_can_msg("ES_Distance", 0, values) diff --git a/selfdrive/car/subaru/values.py b/selfdrive/car/subaru/values.py index 39f8e5e59..4e1745366 100644 --- a/selfdrive/car/subaru/values.py +++ b/selfdrive/car/subaru/values.py @@ -1,21 +1,24 @@ -# flake8: noqa - from selfdrive.car import dbc_dict from cereal import car Ecu = car.CarParams.Ecu class CarControllerParams: - STEER_MAX = 2047 # max_steer 4095 - STEER_STEP = 2 # how often we update the steer cmd - STEER_DELTA_UP = 50 # torque increase per refresh, 0.8s to max - STEER_DELTA_DOWN = 70 # torque decrease per refresh - STEER_DRIVER_ALLOWANCE = 60 # allowed driver torque before start limiting - STEER_DRIVER_MULTIPLIER = 10 # weight driver torque heavily - STEER_DRIVER_FACTOR = 1 # from dbc + def __init__(self, CP): + if CP.carFingerprint == CAR.IMPREZA_2020: + self.STEER_MAX = 1439 + else: + self.STEER_MAX = 2047 + self.STEER_STEP = 2 # how often we update the steer cmd + self.STEER_DELTA_UP = 50 # torque increase per refresh, 0.8s to max + self.STEER_DELTA_DOWN = 70 # torque decrease per refresh + self.STEER_DRIVER_ALLOWANCE = 60 # allowed driver torque before start limiting + self.STEER_DRIVER_MULTIPLIER = 10 # weight driver torque heavily + self.STEER_DRIVER_FACTOR = 1 # from dbc class CAR: ASCENT = "SUBARU ASCENT LIMITED 2019" IMPREZA = "SUBARU IMPREZA LIMITED 2019" + IMPREZA_2020 = "SUBARU IMPREZA SPORT 2020" FORESTER = "SUBARU FORESTER 2019" FORESTER_PREGLOBAL = "SUBARU FORESTER 2017 - 2018" LEGACY_PREGLOBAL = "SUBARU LEGACY 2015 - 2018" @@ -23,54 +26,338 @@ class CAR: OUTBACK_PREGLOBAL_2018 = "SUBARU OUTBACK 2018 - 2019" FINGERPRINTS = { - CAR.ASCENT: [{ - # SUBARU ASCENT LIMITED 2019 - 2: 8, 64: 8, 65: 8, 72: 8, 73: 8, 280: 8, 281: 8, 290: 8, 312: 8, 313: 8, 314: 8, 315: 8, 316: 8, 326: 8, 544: 8, 545: 8, 546: 8, 552: 8, 554: 8, 557: 8, 576: 8, 577: 8, 722: 8, 801: 8, 802: 8, 805: 8, 808: 8, 811: 8, 816: 8, 826: 8, 837: 8, 838: 8, 839: 8, 842: 8, 912: 8, 915: 8, 940: 8, 1614: 8, 1617: 8, 1632: 8, 1650: 8, 1657: 8, 1658: 8, 1677: 8, 1722: 8, 1743: 8, 1759: 8, 1785: 5, 1786: 5, 1787: 5, 1788: 8 - }], CAR.IMPREZA: [{ 2: 8, 64: 8, 65: 8, 72: 8, 73: 8, 280: 8, 281: 8, 290: 8, 312: 8, 313: 8, 314: 8, 315: 8, 316: 8, 326: 8, 372: 8, 544: 8, 545: 8, 546: 8, 552: 8, 554: 8, 557: 8, 576: 8, 577: 8, 722: 8, 801: 8, 802: 8, 805: 8, 808: 8, 811: 8, 816: 8, 826: 8, 827: 8, 837: 8, 838: 8, 839: 8, 842: 8, 912: 8, 915: 8, 940: 8, 1614: 8, 1617: 8, 1632: 8, 1650: 8, 1657: 8, 1658: 8, 1677: 8, 1697: 8, 1722: 8, 1743: 8, 1759: 8, 1786: 5, 1787: 5, 1788: 8, 1809: 8, 1813: 8, 1817: 8, 1821: 8, 1840: 8, 1848: 8, 1924: 8, 1932: 8, 1952: 8, 1960: 8 }], + CAR.IMPREZA_2020: [{ + 2: 8, 64: 8, 65: 8, 72: 8, 73: 8, 280: 8, 281: 8, 282: 8, 290: 8, 312: 8, 313: 8, 314: 8, 315: 8, 316: 8, 326: 8, 372: 8, 544: 8, 545: 8, 546: 8, 552: 8, 554: 8, 557: 8, 576: 8, 577: 8, 722: 8, 801: 8, 802: 8, 803: 8, 805: 8, 808: 8, 816: 8, 826: 8, 837: 8, 838: 8, 839: 8, 842: 8, 912: 8, 915: 8, 940: 8, 1617: 8, 1632: 8, 1650: 8, 1677: 8, 1697: 8, 1722: 8, 1743: 8, 1759: 8, 1786: 5, 1787: 5, 1788: 8, 1809: 8, 1813: 8, 1817: 8, 1821: 8, 1840: 8, 1848: 8, 1924: 8, 1932: 8, 1952: 8, 1960: 8, 1968: 8, 1976: 8, 2015: 8, 2016: 8, 2024: 8 + }, + { + 2: 8, 64: 8, 65: 8, 72: 8, 73: 8, 280: 8, 281: 8, 282: 8, 290: 8, 312: 8, 313: 8, 314: 8, 315: 8, 316: 8, 326: 8, 544: 8, 545: 8, 546: 8, 554: 8, 557: 8, 576: 8, 577: 8, 801: 8, 802: 8, 803: 8, 805: 8, 808: 8, 816: 8, 826: 8, 837: 8, 838: 8, 839: 8, 842: 8, 912: 8, 915: 8, 940: 8, 1614: 8, 1617: 8, 1632: 8, 1657: 8, 1658: 8, 1677: 8, 1697: 8, 1743: 8, 1759: 8, 1786: 5, 1787: 5, 1788: 8, 1809: 8, 1813: 8, 1817: 8, 1821: 8, 1840: 8, 1848: 8, 1924: 8, 1932: 8, 1952: 8, 1960: 8 + }], CAR.FORESTER: [{ - # Forester 2019-2020 2: 8, 64: 8, 65: 8, 72: 8, 73: 8, 280: 8, 281: 8, 282: 8, 290: 8, 312: 8, 313: 8, 314: 8, 315: 8, 316: 8, 326: 8, 372: 8, 544: 8, 545: 8, 546: 8, 552: 8, 554: 8, 557: 8, 576: 8, 577: 8, 722: 8, 801: 8, 802: 8, 803: 8, 805: 8, 808: 8, 811: 8, 816: 8, 826: 8, 837: 8, 838: 8, 839: 8, 842: 8, 912: 8, 915: 8, 940: 8, 961: 8, 984: 8, 1614: 8, 1617: 8, 1632: 8, 1650: 8, 1651: 8, 1657: 8, 1658: 8, 1677: 8, 1697: 8, 1698: 8, 1722: 8, 1743: 8, 1759: 8, 1787: 5, 1788: 8, 1809: 8, 1813: 8, 1817: 8, 1821: 8, 1840: 8, 1848: 8, 1924: 8, 1932: 8, 1952: 8, 1960: 8 }], - CAR.OUTBACK_PREGLOBAL: [{ - # OUTBACK PREMIUM 2.5i 2015 - 2: 8, 208: 8, 209: 4, 210: 8, 211: 7, 212: 8, 320: 8, 321: 8, 324: 8, 328: 8, 329: 8, 336: 2, 338: 8, 342: 8, 346: 8, 352: 8, 353: 8, 354: 8, 356: 8, 358: 8, 359: 8, 392: 8, 640: 8, 642: 8, 644: 8, 864: 8, 865: 8, 866: 8, 872: 8, 880: 8, 881: 8, 882: 8, 884: 8, 977: 8, 1632: 8, 1745: 8, 1786: 5, 1882: 8, 2015: 8, 2016: 8, 2024: 8, 604: 8, 885: 8, 1788: 8, 316: 8, 1614: 8, 1640: 8, 1657: 8, 1658: 8, 1672: 8, 1743: 8, 1785: 5, 1787: 5 +} + +FW_VERSIONS = { + CAR.ASCENT: { + (Ecu.esp, 0x7b0, None): [ + b'\xa5 \x19\x02\x00', + b'\xa5 !\002\000', + b'\xf1\x82\xa5 \x19\x02\x00', + ], + (Ecu.eps, 0x746, None): [ + b'\x85\xc0\xd0\x00', + b'\005\xc0\xd0\000', + b'\x95\xc0\xd0\x00', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\x00\x00d\xb9\x1f@ \x10', + b'\000\000e~\037@ \'', + b'\x00\x00e@\x1f@ $', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xbb,\xa0t\a', + b'\xf1\x82\xbb,\xa0t\x87', + b'\xf1\x82\xbb,\xa0t\a', + b'\xf1\x82\xd9,\xa0@\a', + b'\xf1\x82\xd1,\xa0q\x07', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\x00\xfe\xf7\x00\x00', + b'\001\xfe\xf9\000\000', + b'\x01\xfe\xf7\x00\x00', + ], }, - # OUTBACK PREMIUM 3.6i 2015 - { - 2: 8, 208: 8, 209: 4, 210: 8, 211: 7, 212: 8, 320: 8, 321: 8, 324: 8, 328: 8, 329: 8, 336: 2, 338: 8, 342: 8, 392: 8, 604: 8, 640: 8, 642: 8, 644: 8, 864: 8, 865: 8, 866: 8, 872: 8, 880: 8, 881: 8, 882: 8, 884: 8, 977: 8, 1632: 8, 1745: 8, 1779: 8, 1786: 5 + CAR.IMPREZA: { + (Ecu.esp, 0x7b0, None): [ + b'\x7a\x94\x3f\x90\x00', + b'\xa2 \x185\x00', + b'\xa2 \x193\x00', + b'z\x94.\x90\x00', + b'z\x94\b\x90\x01', + b'\xa2 \x19`\x00', + b'z\x94\f\x90\001', + b'z\x9c\x19\x80\x01', + b'z\x94\x08\x90\x00', + ], + (Ecu.eps, 0x746, None): [ + b'\x7a\xc0\x0c\x00', + b'z\xc0\b\x00', + b'\x8a\xc0\x00\x00', + b'z\xc0\x04\x00', + b'z\xc0\x00\x00', + b'\x8a\xc0\x10\x00', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\x00\x00\x64\xb5\x1f\x40\x20\x0e', + b'\x00\x00d\xdc\x1f@ \x0e', + b'\x00\x00e\x1c\x1f@ \x14', + b'\x00\x00d)\x1f@ \a', + b'\x00\x00e+\x1f@ \x14', + b'\000\000e+\000\000\000\000', + b'\000\000dd\037@ \016', + b'\000\000e\002\037@ \024', + b'\x00\x00d)\x00\x00\x00\x00', + b'\x00\x00c\xf4\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xaa\x61\x66\x73\x07', + b'\xbeacr\a', + b'\xc5!`r\a', + b'\xaa!ds\a', + b'\xaa!`u\a', + b'\xaa!dq\a', + b'\xaa!dt\a', + b'\xf1\x00\xa2\x10\t', + b'\xc5!ar\a', + b'\xbe!as\a', + b'\xc5!ds\a', + b'\xc5!`s\a', + b'\xaa!au\a', + b'\xbe!at\a', + b'\xaa\x00Bu\x07', + b'\xc5!dr\x07', + b'\xaa!aw\x07', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xe3\xe5\x46\x31\x00', + b'\xe4\xe5\x061\x00', + b'\xe5\xf5\x04\x00\x00', + b'\xe3\xf5G\x00\x00', + b'\xe3\xf5\a\x00\x00', + b'\xe3\xf5C\x00\x00', + b'\xe5\xf5B\x00\x00', + b'\xe5\xf5$\000\000', + b'\xe4\xf5\a\000\000', + b'\xe3\xf5F\000\000', + b'\xe4\xf5\002\000\000', + b'\xe3\xd0\x081\x00', + b'\xe3\xf5\x06\x00\x00', + ], }, - # OUTBACK LIMITED 2.5i 2018 - { - 2: 8, 208: 8, 209: 4, 210: 8, 211: 7, 212: 8, 316: 8, 320: 8, 321: 8, 324: 8, 328: 8, 329: 8, 336: 2, 338: 8, 342: 8, 352: 8, 353: 8, 354: 8, 356: 8, 358: 8, 359: 8, 392: 8, 554: 8, 604: 8, 640: 8, 642: 8, 644: 8, 805: 8, 864: 8, 865: 8, 866: 8, 872: 8, 880: 8, 881: 8, 882: 8, 884: 8, 885: 8, 977: 8, 1614: 8, 1632: 8, 1657: 8, 1658: 8, 1672: 8, 1722: 8, 1736: 8, 1743: 8, 1745: 8, 1785: 5, 1786: 5, 1787: 5, 1788: 8 - }], - CAR.OUTBACK_PREGLOBAL_2018: [{ - # OUTBACK LIMITED 3.6R 2019 - 2: 8, 208: 8, 209: 4, 210: 8, 211: 7, 212: 8, 316: 8, 320: 8, 321: 8, 324: 8, 328: 8, 329: 8, 336: 2, 338: 8, 342: 8, 352: 8, 353: 8, 354: 8, 356: 8, 358: 8, 359: 8, 392: 8, 554: 8, 604: 8, 640: 8, 642: 8, 644: 8, 805: 8, 864: 8, 865: 8, 866: 8, 872: 8, 880: 8, 881: 8, 882: 8, 884: 8, 885: 8, 886: 2, 977: 8, 1614: 8, 1632: 8, 1657: 8, 1658: 8, 1672: 8, 1736: 8, 1743: 8, 1745: 8, 1785: 5, 1786: 5, 1787: 5, 1788: 8, 1862: 8, 1870: 8, 1920: 8, 1927: 8, 1928: 8, 1935: 8, 1968: 8, 1976: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8 - }], - CAR.FORESTER_PREGLOBAL: [{ - # FORESTER PREMIUM 2.5i 2017 - 2: 8, 112: 8, 117: 8, 128: 8, 208: 8, 209: 4, 210: 8, 211: 7, 212: 8, 320: 8, 321: 8, 324: 8, 328: 8, 329: 8, 336: 2, 338: 8, 340: 7, 342: 8, 352: 8, 353: 8, 354: 8, 355: 8, 356: 8, 554: 8, 604: 8, 640: 8, 641: 8, 642: 8, 805: 8, 864: 8, 865: 8, 866: 8, 872: 8, 880: 8, 881: 8, 882: 8, 884: 8, 885: 8, 886: 1, 888: 8, 977: 8, 1398: 8, 1632: 8, 1743: 8, 1744: 8, 1745: 8, 1785: 5, 1786: 5, 1787: 5, 1788: 8, 1882: 8, 1895: 8, 1903: 8, 1986: 8, 1994: 8, 2015: 8, 2016: 8, 2024: 8, 644:8, 890:8, 1736:8 - }], - CAR.LEGACY_PREGLOBAL: [{ - # LEGACY 2.5i 2017 - 2: 8, 208: 8, 209: 4, 210: 8, 211: 7, 212: 8, 320: 8, 321: 8, 324: 8, 328: 8, 329: 8, 336: 2, 338: 8, 342: 8, 392: 8, 604: 8, 640: 8, 642: 8, 864: 8, 865: 8, 866: 8, 872: 8, 880: 8, 881: 8, 882: 8, 884: 8, 885: 8, 977: 8, 1632: 8, 1640: 8, 1736: 8, 1745: 8, 1785: 5, 1786: 5, 1787: 5, 1788: 8, 352: 8, 353: 8, 354: 8, 356: 8, 358: 8, 359: 8, 644: 8 + CAR.IMPREZA_2020: { + (Ecu.esp, 0x7b0, None): [ + b'\xa2 \0314\000', + b'\xa2 \0313\000', + b'\xa2 !i\000', + b'\xa2 !`\000', + ], + (Ecu.eps, 0x746, None): [ + b'\x9a\xc0\000\000', + b'\n\xc0\004\000', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\000\000eb\037@ \"', + b'\000\000e\x8f\037@ )', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xca!ap\a', + b'\xca!`p\a', + b'\xca!`0\a', + b'\xcc\"f0\a', + b'\xcc!fp\a', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xe6\xf5\004\000\000', + b'\xe6\xf5$\000\000', + b'\xe7\xf6B0\000', + b'\xe7\xf5D0\000', + ], }, - # LEGACY 2018 - { - 2: 8, 208: 8, 209: 4, 210: 8, 211: 7, 212: 8, 316: 8, 320: 8, 321: 8, 324: 8, 328: 8, 329: 8, 336: 2, 338: 8, 342: 8, 392: 8, 604: 8, 640: 8, 642: 8, 864: 8, 865: 8, 866: 8, 872: 8, 880: 8, 881: 8, 882: 8, 884: 8, 885: 8, 977: 8, 1614: 8, 1632: 8, 1640: 8, 1657: 8, 1658: 8, 1672: 8, 1722: 8, 1743: 8, 1745: 8, 1778: 8, 1785: 5, 1786: 5, 1787: 5, 1788: 8, 2015: 8, 2016: 8, 2024: 8 + CAR.FORESTER: { + (Ecu.esp, 0x7b0, None): [ + b'\xa3 \030\024\000', + b'\xa3 \024\000', + b'\xa3 \031\024\000', + b'\xa3 \024\001', + ], + (Ecu.eps, 0x746, None): [ + b'\x8d\xc0\004\000', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\000\000e!\037@ \021', + b'\000\000e\x97\037@ 0', + b'\000\000e`\037@ ', + b'\xf1\x00\xac\x02\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xb6\"`A\a', + b'\xcf"`0\a', + b'\xcb\"`@\a', + b'\xcb\"`p\a', + b'\xf1\x00\xa2\x10\n', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\032\xf6B0\000', + b'\032\xf6F`\000', + b'\032\xf6b`\000', + b'\032\xf6B`\000', + b'\xf1\x00\xa4\x10@', + ], + }, + CAR.FORESTER_PREGLOBAL: { + (Ecu.esp, 0x7b0, None): [ + b'\x7d\x97\x14\x40', + b'\xf1\x00\xbb\x0c\x04', + ], + (Ecu.eps, 0x746, None): [ + b'}\xc0\x10\x00', + b'm\xc0\x10\x00', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\x00\x00\x64\x35\x1f\x40\x20\x09', + b'\x00\x00c\xe9\x1f@ \x03', + b'\x00\x00d\xd3\x1f@ \t' + ], + (Ecu.engine, 0x7e0, None): [ + b'\xba"@p\a', + b'\xa7)\xa0q\a', + b'\xf1\x82\xa7)\xa0q\a', + b'\xba"@@\a', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xdc\xf2\x60\x60\x00', + b'\xdc\xf2@`\x00', + b'\xda\xfd\xe0\x80\x00', + b'\xdc\xf2`\x81\000', + b'\xdc\xf2`\x80\x00', + ], + }, + CAR.LEGACY_PREGLOBAL: { + (Ecu.esp, 0x7b0, None): [ + b'k\x97D\x00', + b'[\xba\xc4\x03', + b'{\x97D\x00', + b'[\x97D\000', + ], + (Ecu.eps, 0x746, None): [ + b'[\xb0\x00\x01', + b'K\xb0\x00\x01', + b'k\xb0\x00\x00', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\x00\x00c\xb7\x1f@\x10\x16', + b'\x00\x00c\x94\x1f@\x10\x08', + b'\x00\x00c\xec\x1f@ \x04', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xab*@r\a', + b'\xa0+@p\x07', + b'\xb4"@0\x07', + b'\xa0"@q\a', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xbe\xf2\x00p\x00', + b'\xbf\xfb\xc0\x80\x00', + b'\xbd\xf2\x00`\x00', + b'\xbf\xf2\000\x80\000', + ], + }, + CAR.OUTBACK_PREGLOBAL: { + (Ecu.esp, 0x7b0, None): [ + b'{\x9a\xac\x00', + b'k\x97\xac\x00', + b'\x5b\xf7\xbc\x03', + b'[\xf7\xac\x03', + b'{\x97\xac\x00', + b'k\x9a\xac\000', + b'[\xba\xac\x03', + b'[\xf7\xac\000', + ], + (Ecu.eps, 0x746, None): [ + b'k\xb0\x00\x00', + b'[\xb0\x00\x00', + b'\x4b\xb0\x00\x02', + b'K\xb0\x00\x00', + b'{\xb0\x00\x01', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\x00\x00c\xec\x1f@ \x04', + b'\x00\x00c\xd1\x1f@\x10\x17', + b'\xf1\x00\xf0\xe0\x0e', + b'\x00\x00c\x94\x00\x00\x00\x00', + b'\x00\x00c\x94\x1f@\x10\b', + b'\x00\x00c\xb7\x1f@\x10\x16', + b'\000\000c\x90\037@\020\016', + b'\x00\x00c\xec\x37@\x04', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xb4+@p\a', + b'\xab\"@@\a', + b'\xa0\x62\x41\x71\x07', + b'\xa0*@q\a', + b'\xab*@@\a', + b'\xb4"@0\a', + b'\xb4"@p\a', + b'\xab"@s\a', + b'\xab+@@\a', + b'\xb4"@r\a', + b'\xa0+@@\x07', + b'\xa0\"@\x80\a', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xbd\xfb\xe0\x80\x00', + b'\xbe\xf2@\x80\x00', + b'\xbf\xe2\x40\x80\x00', + b'\xbf\xf2@\x80\x00', + b'\xbe\xf2@p\x00', + b'\xbd\xf2@`\x00', + b'\xbd\xf2@\x81\000', + b'\xbe\xfb\xe0p\000', + b'\xbf\xfb\xe0b\x00', + ], + }, + CAR.OUTBACK_PREGLOBAL_2018: { + (Ecu.esp, 0x7b0, None): [ + b'\x8b\x97\xac\x00', + b'\x8b\x9a\xac\x00', + b'\x9b\x97\xac\x00', + b'\x8b\x97\xbc\x00', + b'\x8b\x99\xac\x00', + b'\x9b\x9a\xac\000', + b'\x9b\x97\xbe\x10', + ], + (Ecu.eps, 0x746, None): [ + b'{\xb0\x00\x00', + b'{\xb0\x00\x01', + ], + (Ecu.fwdCamera, 0x787, None): [ + b'\x00\x00df\x1f@ \n', + b'\x00\x00d\xfe\x1f@ \x15', + b'\x00\x00d\x95\x00\x00\x00\x00', + b'\x00\x00d\x95\x1f@ \x0f', + b'\x00\x00d\xfe\x00\x00\x00\x00', + b'\x00\x00e\x19\x1f@ \x15', + ], + (Ecu.engine, 0x7e0, None): [ + b'\xb5"@p\a', + b'\xb5+@@\a', + b'\xb5"@P\a', + b'\xc4"@0\a', + b'\xb5b@1\x07', + b'\xb5q\xe0@\a', + b'\xc4+@0\a', + b'\xc4b@p\a', + ], + (Ecu.transmission, 0x7e1, None): [ + b'\xbc\xf2@\x81\x00', + b'\xbc\xfb\xe0\x80\x00', + b'\xbc\xf2@\x80\x00', + b'\xbb\xf2@`\x00', + b'\xbc\xe2@\x80\x00', + b'\xbc\xfb\xe0`\x00', + b'\xbc\xaf\xe0`\x00', + b'\xbb\xfb\xe0`\000', + ], }, - # LEGACY 2018 - { - 2: 8, 208: 8, 209: 4, 210: 8, 211: 7, 212: 8, 316: 8, 320: 8, 321: 8, 324: 8, 328: 8, 329: 8, 336: 2, 338: 8, 342: 8, 352: 8, 353: 8, 354: 8, 356: 8, 358: 8, 359: 8, 392: 8, 554: 8, 604: 8, 640: 8, 642: 8, 805: 8, 864: 8, 865: 8, 866: 8, 872: 8, 880: 8, 881: 8, 882: 8, 884: 8, 885: 8, 977: 8, 1614: 8, 1632: 8, 1640: 8, 1657: 8, 1658: 8, 1672: 8, 1722: 8, 1743: 8, 1745: 8, 1785: 5, 1786: 5, 1787: 5, 1788: 8, 2015: 8, 2016: 8, 2024: 8 - }], } STEER_THRESHOLD = { CAR.ASCENT: 80, CAR.IMPREZA: 80, + CAR.IMPREZA_2020: 80, CAR.FORESTER: 80, CAR.FORESTER_PREGLOBAL: 75, CAR.LEGACY_PREGLOBAL: 75, @@ -81,6 +368,7 @@ STEER_THRESHOLD = { DBC = { CAR.ASCENT: dbc_dict('subaru_global_2017_generated', None), CAR.IMPREZA: dbc_dict('subaru_global_2017_generated', None), + CAR.IMPREZA_2020: dbc_dict('subaru_global_2017_generated', None), CAR.FORESTER: dbc_dict('subaru_global_2017_generated', None), CAR.FORESTER_PREGLOBAL: dbc_dict('subaru_forester_2017_generated', None), CAR.LEGACY_PREGLOBAL: dbc_dict('subaru_outback_2015_generated', None), diff --git a/selfdrive/car/tesla/carcontroller.py b/selfdrive/car/tesla/carcontroller.py index 7e6a2f2e9..03f09f240 100644 --- a/selfdrive/car/tesla/carcontroller.py +++ b/selfdrive/car/tesla/carcontroller.py @@ -12,12 +12,12 @@ class CarController(): self.pt_packer = CANPacker(DBC[CP.carFingerprint]['pt']) self.tesla_can = TeslaCAN(self.packer, self.pt_packer) - def update(self, enabled, CS, frame, actuators, cruise_cancel): + def update(self, c, enabled, CS, frame, actuators, cruise_cancel): can_sends = [] # Temp disable steering on a hands_on_fault, and allow for user override hands_on_fault = (CS.steer_warning == "EAC_ERROR_HANDS_ON" and CS.hands_on_level >= 3) - lkas_enabled = enabled and (not hands_on_fault) + lkas_enabled = c.active and (not hands_on_fault) if lkas_enabled: apply_angle = actuators.steeringAngleDeg @@ -37,7 +37,7 @@ class CarController(): can_sends.append(self.tesla_can.create_steering_control(apply_angle, lkas_enabled, frame)) # Longitudinal control (40Hz) - if self.CP.openpilotLongitudinalControl and ((frame % 5) in [0, 2]): + if self.CP.openpilotLongitudinalControl and ((frame % 5) in (0, 2)): target_accel = actuators.accel target_speed = max(CS.out.vEgo + (target_accel * CarControllerParams.ACCEL_TO_SPEED_MULTIPLIER), 0) max_accel = 0 if target_accel < 0 else target_accel @@ -62,4 +62,7 @@ class CarController(): # TODO: HUD control - return can_sends + new_actuators = actuators.copy() + new_actuators.steeringAngleDeg = apply_angle + + return new_actuators, can_sends diff --git a/selfdrive/car/tesla/carstate.py b/selfdrive/car/tesla/carstate.py index 0a45b6f2b..51ae43ad1 100644 --- a/selfdrive/car/tesla/carstate.py +++ b/selfdrive/car/tesla/carstate.py @@ -50,7 +50,7 @@ class CarState(CarStateBase): cruise_state = self.can_define.dv["DI_state"]["DI_cruiseState"].get(int(cp.vl["DI_state"]["DI_cruiseState"]), None) speed_units = self.can_define.dv["DI_state"]["DI_speedUnits"].get(int(cp.vl["DI_state"]["DI_speedUnits"]), None) - acc_enabled = (cruise_state in ["ENABLED", "STANDSTILL", "OVERRIDE", "PRE_FAULT", "PRE_CANCEL"]) + acc_enabled = (cruise_state in ("ENABLED", "STANDSTILL", "OVERRIDE", "PRE_FAULT", "PRE_CANCEL")) ret.cruiseState.enabled = acc_enabled if speed_units == "KPH": @@ -96,64 +96,64 @@ class CarState(CarStateBase): @staticmethod def get_can_parser(CP): signals = [ - # sig_name, sig_address, default - ("ESP_vehicleSpeed", "ESP_B", 0), - ("DI_pedalPos", "DI_torque1", 0), - ("DI_brakePedal", "DI_torque2", 0), - ("StW_AnglHP", "STW_ANGLHP_STAT", 0), - ("StW_AnglHP_Spd", "STW_ANGLHP_STAT", 0), - ("EPAS_handsOnLevel", "EPAS_sysStatus", 0), - ("EPAS_torsionBarTorque", "EPAS_sysStatus", 0), - ("EPAS_internalSAS", "EPAS_sysStatus", 0), - ("EPAS_eacStatus", "EPAS_sysStatus", 1), - ("EPAS_eacErrorCode", "EPAS_sysStatus", 0), - ("DI_cruiseState", "DI_state", 0), - ("DI_digitalSpeed", "DI_state", 0), - ("DI_speedUnits", "DI_state", 0), - ("DI_gear", "DI_torque2", 0), - ("DOOR_STATE_FL", "GTW_carState", 1), - ("DOOR_STATE_FR", "GTW_carState", 1), - ("DOOR_STATE_RL", "GTW_carState", 1), - ("DOOR_STATE_RR", "GTW_carState", 1), - ("DOOR_STATE_FrontTrunk", "GTW_carState", 1), - ("BOOT_STATE", "GTW_carState", 1), - ("BC_indicatorLStatus", "GTW_carState", 1), - ("BC_indicatorRStatus", "GTW_carState", 1), - ("SDM_bcklDrivStatus", "SDM1", 0), - ("driverBrakeStatus", "BrakeMessage", 0), + # sig_name, sig_address + ("ESP_vehicleSpeed", "ESP_B"), + ("DI_pedalPos", "DI_torque1"), + ("DI_brakePedal", "DI_torque2"), + ("StW_AnglHP", "STW_ANGLHP_STAT"), + ("StW_AnglHP_Spd", "STW_ANGLHP_STAT"), + ("EPAS_handsOnLevel", "EPAS_sysStatus"), + ("EPAS_torsionBarTorque", "EPAS_sysStatus"), + ("EPAS_internalSAS", "EPAS_sysStatus"), + ("EPAS_eacStatus", "EPAS_sysStatus"), + ("EPAS_eacErrorCode", "EPAS_sysStatus"), + ("DI_cruiseState", "DI_state"), + ("DI_digitalSpeed", "DI_state"), + ("DI_speedUnits", "DI_state"), + ("DI_gear", "DI_torque2"), + ("DOOR_STATE_FL", "GTW_carState"), + ("DOOR_STATE_FR", "GTW_carState"), + ("DOOR_STATE_RL", "GTW_carState"), + ("DOOR_STATE_RR", "GTW_carState"), + ("DOOR_STATE_FrontTrunk", "GTW_carState"), + ("BOOT_STATE", "GTW_carState"), + ("BC_indicatorLStatus", "GTW_carState"), + ("BC_indicatorRStatus", "GTW_carState"), + ("SDM_bcklDrivStatus", "SDM1"), + ("driverBrakeStatus", "BrakeMessage"), # We copy this whole message when spamming cancel - ("SpdCtrlLvr_Stat", "STW_ACTN_RQ", 0), - ("VSL_Enbl_Rq", "STW_ACTN_RQ", 0), - ("SpdCtrlLvrStat_Inv", "STW_ACTN_RQ", 0), - ("DTR_Dist_Rq", "STW_ACTN_RQ", 0), - ("TurnIndLvr_Stat", "STW_ACTN_RQ", 0), - ("HiBmLvr_Stat", "STW_ACTN_RQ", 0), - ("WprWashSw_Psd", "STW_ACTN_RQ", 0), - ("WprWash_R_Sw_Posn_V2", "STW_ACTN_RQ", 0), - ("StW_Lvr_Stat", "STW_ACTN_RQ", 0), - ("StW_Cond_Flt", "STW_ACTN_RQ", 0), - ("StW_Cond_Psd", "STW_ACTN_RQ", 0), - ("HrnSw_Psd", "STW_ACTN_RQ", 0), - ("StW_Sw00_Psd", "STW_ACTN_RQ", 0), - ("StW_Sw01_Psd", "STW_ACTN_RQ", 0), - ("StW_Sw02_Psd", "STW_ACTN_RQ", 0), - ("StW_Sw03_Psd", "STW_ACTN_RQ", 0), - ("StW_Sw04_Psd", "STW_ACTN_RQ", 0), - ("StW_Sw05_Psd", "STW_ACTN_RQ", 0), - ("StW_Sw06_Psd", "STW_ACTN_RQ", 0), - ("StW_Sw07_Psd", "STW_ACTN_RQ", 0), - ("StW_Sw08_Psd", "STW_ACTN_RQ", 0), - ("StW_Sw09_Psd", "STW_ACTN_RQ", 0), - ("StW_Sw10_Psd", "STW_ACTN_RQ", 0), - ("StW_Sw11_Psd", "STW_ACTN_RQ", 0), - ("StW_Sw12_Psd", "STW_ACTN_RQ", 0), - ("StW_Sw13_Psd", "STW_ACTN_RQ", 0), - ("StW_Sw14_Psd", "STW_ACTN_RQ", 0), - ("StW_Sw15_Psd", "STW_ACTN_RQ", 0), - ("WprSw6Posn", "STW_ACTN_RQ", 0), - ("MC_STW_ACTN_RQ", "STW_ACTN_RQ", 0), - ("CRC_STW_ACTN_RQ", "STW_ACTN_RQ", 0), + ("SpdCtrlLvr_Stat", "STW_ACTN_RQ"), + ("VSL_Enbl_Rq", "STW_ACTN_RQ"), + ("SpdCtrlLvrStat_Inv", "STW_ACTN_RQ"), + ("DTR_Dist_Rq", "STW_ACTN_RQ"), + ("TurnIndLvr_Stat", "STW_ACTN_RQ"), + ("HiBmLvr_Stat", "STW_ACTN_RQ"), + ("WprWashSw_Psd", "STW_ACTN_RQ"), + ("WprWash_R_Sw_Posn_V2", "STW_ACTN_RQ"), + ("StW_Lvr_Stat", "STW_ACTN_RQ"), + ("StW_Cond_Flt", "STW_ACTN_RQ"), + ("StW_Cond_Psd", "STW_ACTN_RQ"), + ("HrnSw_Psd", "STW_ACTN_RQ"), + ("StW_Sw00_Psd", "STW_ACTN_RQ"), + ("StW_Sw01_Psd", "STW_ACTN_RQ"), + ("StW_Sw02_Psd", "STW_ACTN_RQ"), + ("StW_Sw03_Psd", "STW_ACTN_RQ"), + ("StW_Sw04_Psd", "STW_ACTN_RQ"), + ("StW_Sw05_Psd", "STW_ACTN_RQ"), + ("StW_Sw06_Psd", "STW_ACTN_RQ"), + ("StW_Sw07_Psd", "STW_ACTN_RQ"), + ("StW_Sw08_Psd", "STW_ACTN_RQ"), + ("StW_Sw09_Psd", "STW_ACTN_RQ"), + ("StW_Sw10_Psd", "STW_ACTN_RQ"), + ("StW_Sw11_Psd", "STW_ACTN_RQ"), + ("StW_Sw12_Psd", "STW_ACTN_RQ"), + ("StW_Sw13_Psd", "STW_ACTN_RQ"), + ("StW_Sw14_Psd", "STW_ACTN_RQ"), + ("StW_Sw15_Psd", "STW_ACTN_RQ"), + ("WprSw6Posn", "STW_ACTN_RQ"), + ("MC_STW_ACTN_RQ", "STW_ACTN_RQ"), + ("CRC_STW_ACTN_RQ", "STW_ACTN_RQ"), ] checks = [ @@ -175,8 +175,8 @@ class CarState(CarStateBase): @staticmethod def get_cam_can_parser(CP): signals = [ - # sig_name, sig_address, default - ("DAS_accState", "DAS_control", 0), + # sig_name, sig_address + ("DAS_accState", "DAS_control"), ] checks = [ # sig_address, frequency diff --git a/selfdrive/car/tesla/interface.py b/selfdrive/car/tesla/interface.py index 45dc0a723..03012bc52 100755 --- a/selfdrive/car/tesla/interface.py +++ b/selfdrive/car/tesla/interface.py @@ -25,7 +25,6 @@ class CarInterface(CarInterfaceBase): ret.longitudinalTuning.kiBP = [0] ret.longitudinalTuning.kiV = [0] ret.stopAccel = 0.0 - ret.startAccel = 0.0 ret.longitudinalActuatorDelayUpperBound = 0.5 # s ret.radarTimeStep = (1.0 / 8) # 8Hz @@ -41,10 +40,11 @@ class CarInterface(CarInterfaceBase): ret.openpilotLongitudinalControl = False ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.tesla, 0)] + ret.steerLimitTimer = 1.0 ret.steerActuatorDelay = 0.1 ret.steerRateCost = 0.5 - if candidate in [CAR.AP2_MODELS, CAR.AP1_MODELS]: + if candidate in (CAR.AP2_MODELS, CAR.AP1_MODELS): ret.mass = 2100. + STD_CARGO_KG ret.wheelbase = 2.959 ret.centerToFront = ret.wheelbase * 0.5 @@ -71,6 +71,6 @@ class CarInterface(CarInterfaceBase): return self.CS.out def apply(self, c): - can_sends = self.CC.update(c.enabled, self.CS, self.frame, c.actuators, c.cruiseControl.cancel) + ret = self.CC.update(c, c.enabled, self.CS, self.frame, c.actuators, c.cruiseControl.cancel) self.frame += 1 - return can_sends + return ret diff --git a/selfdrive/car/tesla/radar_interface.py b/selfdrive/car/tesla/radar_interface.py index f5ad12ba7..a09f53e75 100755 --- a/selfdrive/car/tesla/radar_interface.py +++ b/selfdrive/car/tesla/radar_interface.py @@ -11,9 +11,9 @@ NUM_POINTS = len(RADAR_MSGS_A) def get_radar_can_parser(CP): # Status messages signals = [ - ('RADC_HWFail', 'TeslaRadarSguInfo', 0), - ('RADC_SGUFail', 'TeslaRadarSguInfo', 0), - ('RADC_SensorDirty', 'TeslaRadarSguInfo', 0), + ('RADC_HWFail', 'TeslaRadarSguInfo'), + ('RADC_SGUFail', 'TeslaRadarSguInfo'), + ('RADC_SensorDirty', 'TeslaRadarSguInfo'), ] checks = [ @@ -29,16 +29,16 @@ def get_radar_can_parser(CP): # There is a bunch more info in the messages, # but these are the only things actually used in openpilot signals.extend([ - ('LongDist', msg_id_a, 255), - ('LongSpeed', msg_id_a, 0), - ('LatDist', msg_id_a, 0), - ('LongAccel', msg_id_a, 0), - ('Meas', msg_id_a, 0), - ('Tracked', msg_id_a, 0), - ('Index', msg_id_a, 0), + ('LongDist', msg_id_a), + ('LongSpeed', msg_id_a), + ('LatDist', msg_id_a), + ('LongAccel', msg_id_a), + ('Meas', msg_id_a), + ('Tracked', msg_id_a), + ('Index', msg_id_a), - ('LatSpeed', msg_id_b, 0), - ('Index2', msg_id_b, 0), + ('LatSpeed', msg_id_b), + ('Index2', msg_id_b), ]) checks.extend([ diff --git a/selfdrive/car/tesla/values.py b/selfdrive/car/tesla/values.py index 90bc45c7a..616933789 100644 --- a/selfdrive/car/tesla/values.py +++ b/selfdrive/car/tesla/values.py @@ -1,5 +1,3 @@ -# flake8: noqa - from collections import namedtuple from selfdrive.car import dbc_dict from cereal import car diff --git a/selfdrive/car/tests/test_car_interfaces.py b/selfdrive/car/tests/test_car_interfaces.py index 93dc05c83..930619ee6 100755 --- a/selfdrive/car/tests/test_car_interfaces.py +++ b/selfdrive/car/tests/test_car_interfaces.py @@ -59,7 +59,7 @@ class TestCarInterfaces(unittest.TestCase): car_interface.apply(CC) # Test radar interface - RadarInterface = importlib.import_module('selfdrive.car.%s.radar_interface' % car_params.carName).RadarInterface + RadarInterface = importlib.import_module(f'selfdrive.car.{car_params.carName}.radar_interface').RadarInterface radar_interface = RadarInterface(car_params) assert radar_interface diff --git a/selfdrive/car/toyota/carcontroller.py b/selfdrive/car/toyota/carcontroller.py index 1997e6c11..87ba0055f 100644 --- a/selfdrive/car/toyota/carcontroller.py +++ b/selfdrive/car/toyota/carcontroller.py @@ -19,19 +19,19 @@ class CarController(): self.steer_rate_limited = False self.packer = CANPacker(dbc_name) + self.gas = 0 + self.accel = 0 def update(self, enabled, active, CS, frame, actuators, pcm_cancel_cmd, hud_alert, left_line, right_line, lead, left_lane_depart, right_lane_depart): - # *** compute control surfaces *** - # gas and brake - if CS.CP.enableGasInterceptor and enabled: + if CS.CP.enableGasInterceptor and active: MAX_INTERCEPTOR_GAS = 0.5 # RAV4 has very sensitive gas pedal - if CS.CP.carFingerprint in [CAR.RAV4, CAR.RAV4H, CAR.HIGHLANDER, CAR.HIGHLANDERH]: + if CS.CP.carFingerprint in (CAR.RAV4, CAR.RAV4H, CAR.HIGHLANDER, CAR.HIGHLANDERH): PEDAL_SCALE = interp(CS.out.vEgo, [0.0, MIN_ACC_SPEED, MIN_ACC_SPEED + PEDAL_TRANSITION], [0.15, 0.3, 0.0]) - elif CS.CP.carFingerprint in [CAR.COROLLA]: + elif CS.CP.carFingerprint in (CAR.COROLLA,): PEDAL_SCALE = interp(CS.out.vEgo, [0.0, MIN_ACC_SPEED, MIN_ACC_SPEED + PEDAL_TRANSITION], [0.3, 0.4, 0.0]) else: PEDAL_SCALE = interp(CS.out.vEgo, [0.0, MIN_ACC_SPEED, MIN_ACC_SPEED + PEDAL_TRANSITION], [0.4, 0.5, 0.0]) @@ -49,7 +49,7 @@ class CarController(): self.steer_rate_limited = new_steer != apply_steer # Cut steering while we're in a known fault state (2s) - if not enabled or CS.steer_state in [9, 25]: + if not active or CS.steer_state in (9, 25): apply_steer = 0 apply_steer_req = 0 else: @@ -89,26 +89,28 @@ class CarController(): # we can spam can to cancel the system even if we are using lat only control if (frame % 3 == 0 and CS.CP.openpilotLongitudinalControl) or pcm_cancel_cmd: - lead = lead or CS.out.vEgo < 12. # at low speed we always assume the lead is present do ACC can be engaged + lead = lead or CS.out.vEgo < 12. # at low speed we always assume the lead is present so ACC can be engaged # Lexus IS uses a different cancellation message - if pcm_cancel_cmd and CS.CP.carFingerprint in [CAR.LEXUS_IS, CAR.LEXUS_RC]: + if pcm_cancel_cmd and CS.CP.carFingerprint in (CAR.LEXUS_IS, CAR.LEXUS_RC): can_sends.append(create_acc_cancel_command(self.packer)) elif CS.CP.openpilotLongitudinalControl: can_sends.append(create_accel_command(self.packer, pcm_accel_cmd, pcm_cancel_cmd, self.standstill_req, lead, CS.acc_type)) + self.accel = pcm_accel_cmd else: can_sends.append(create_accel_command(self.packer, 0, pcm_cancel_cmd, False, lead, CS.acc_type)) - if frame % 2 == 0 and CS.CP.enableGasInterceptor: + if frame % 2 == 0 and CS.CP.enableGasInterceptor and CS.CP.openpilotLongitudinalControl: # send exactly zero if gas cmd is zero. Interceptor will send the max between read value and gas cmd. # This prevents unexpected pedal range rescaling can_sends.append(create_gas_interceptor_command(self.packer, interceptor_gas_cmd, frame // 2)) + self.gas = interceptor_gas_cmd - # ui mesg is at 100Hz but we send asap if: + # ui mesg is at 1Hz but we send asap if: # - there is something to display # - there is something to stop displaying fcw_alert = hud_alert == VisualAlert.fcw - steer_alert = hud_alert in [VisualAlert.steerRequired, VisualAlert.ldw] + steer_alert = hud_alert in (VisualAlert.steerRequired, VisualAlert.ldw) send_ui = False if ((fcw_alert or steer_alert) and not self.alert_active) or \ @@ -120,15 +122,19 @@ class CarController(): send_ui = True if (frame % 100 == 0 or send_ui): - can_sends.append(create_ui_command(self.packer, steer_alert, pcm_cancel_cmd, left_line, right_line, left_lane_depart, right_lane_depart)) + can_sends.append(create_ui_command(self.packer, steer_alert, pcm_cancel_cmd, left_line, right_line, left_lane_depart, right_lane_depart, enabled)) if frame % 100 == 0 and CS.CP.enableDsu: can_sends.append(create_fcw_command(self.packer, fcw_alert)) - #*** static msgs *** - + # *** static msgs *** for (addr, cars, bus, fr_step, vl) in STATIC_DSU_MSGS: if frame % fr_step == 0 and CS.CP.enableDsu and CS.CP.carFingerprint in cars: can_sends.append(make_can_msg(addr, vl, bus)) - return can_sends + new_actuators = actuators.copy() + new_actuators.steer = apply_steer / CarControllerParams.STEER_MAX + new_actuators.accel = self.accel + new_actuators.gas = self.gas + + return new_actuators, can_sends diff --git a/selfdrive/car/toyota/carstate.py b/selfdrive/car/toyota/carstate.py index 7ce5907b9..d73460ef3 100644 --- a/selfdrive/car/toyota/carstate.py +++ b/selfdrive/car/toyota/carstate.py @@ -6,7 +6,7 @@ from opendbc.can.can_define import CANDefine from selfdrive.car.interfaces import CarStateBase from opendbc.can.parser import CANParser from selfdrive.config import Conversions as CV -from selfdrive.car.toyota.values import CAR, DBC, STEER_THRESHOLD, NO_STOP_TIMER_CAR, TSS2_CAR +from selfdrive.car.toyota.values import ToyotaFlags, CAR, DBC, STEER_THRESHOLD, NO_STOP_TIMER_CAR, TSS2_CAR, EPS_SCALE class CarState(CarStateBase): @@ -14,6 +14,7 @@ class CarState(CarStateBase): super().__init__(CP) can_define = CANDefine(DBC[CP.carFingerprint]["pt"]) self.shifter_values = can_define.dv["GEAR_PACKET"]["GEAR"] + self.eps_torque_scale = EPS_SCALE[CP.carFingerprint] / 100. # On cars with cp.vl["STEER_TORQUE_SENSOR"]["STEER_ANGLE"] # the signal is zeroed to where the steering angle is at start. @@ -28,9 +29,9 @@ class CarState(CarStateBase): def update(self, cp, cp_cam): ret = car.CarState.new_message() - ret.doorOpen = any([cp.vl["SEATS_DOORS"]["DOOR_OPEN_FL"], cp.vl["SEATS_DOORS"]["DOOR_OPEN_FR"], - cp.vl["SEATS_DOORS"]["DOOR_OPEN_RL"], cp.vl["SEATS_DOORS"]["DOOR_OPEN_RR"]]) - ret.seatbeltUnlatched = cp.vl["SEATS_DOORS"]["SEATBELT_DRIVER_UNLATCHED"] != 0 + ret.doorOpen = any([cp.vl["BODY_CONTROL_STATE"]["DOOR_OPEN_FL"], cp.vl["BODY_CONTROL_STATE"]["DOOR_OPEN_FR"], + cp.vl["BODY_CONTROL_STATE"]["DOOR_OPEN_RL"], cp.vl["BODY_CONTROL_STATE"]["DOOR_OPEN_RR"]]) + ret.seatbeltUnlatched = cp.vl["BODY_CONTROL_STATE"]["SEATBELT_DRIVER_UNLATCHED"] != 0 ret.brakePressed = cp.vl["BRAKE_MODULE"]["BRAKE_PRESSED"] != 0 ret.brakeHoldActive = cp.vl["ESP_CONTROL"]["BRAKE_HOLD_ACTIVE"] == 1 @@ -38,7 +39,9 @@ class CarState(CarStateBase): ret.gas = (cp.vl["GAS_SENSOR"]["INTERCEPTOR_GAS"] + cp.vl["GAS_SENSOR"]["INTERCEPTOR_GAS2"]) / 2. ret.gasPressed = ret.gas > 15 else: - ret.gas = cp.vl["GAS_PEDAL"]["GAS_PEDAL"] + # TODO: find a new, common signal + msg = "GAS_PEDAL_HYBRID" if (self.CP.flags & ToyotaFlags.HYBRID) else "GAS_PEDAL" + ret.gas = cp.vl[msg]["GAS_PEDAL"] ret.gasPressed = cp.vl["PCM_CRUISE"]["GAS_RELEASED"] == 0 ret.wheelSpeeds = self.get_wheel_speeds( @@ -61,7 +64,7 @@ class CarState(CarStateBase): if self.accurate_steer_angle_seen: # Offset seems to be invalid for large steering angles - if abs(ret.steeringAngleDeg) < 90: + if abs(ret.steeringAngleDeg) < 90 and cp.can_valid: self.angle_offset.update(torque_sensor_angle_deg - ret.steeringAngleDeg) if self.angle_offset.initialized: @@ -72,16 +75,16 @@ class CarState(CarStateBase): can_gear = int(cp.vl["GEAR_PACKET"]["GEAR"]) ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(can_gear, None)) - ret.leftBlinker = cp.vl["STEERING_LEVERS"]["TURN_SIGNALS"] == 1 - ret.rightBlinker = cp.vl["STEERING_LEVERS"]["TURN_SIGNALS"] == 2 + ret.leftBlinker = cp.vl["BLINKERS_STATE"]["TURN_SIGNALS"] == 1 + ret.rightBlinker = cp.vl["BLINKERS_STATE"]["TURN_SIGNALS"] == 2 ret.steeringTorque = cp.vl["STEER_TORQUE_SENSOR"]["STEER_TORQUE_DRIVER"] - ret.steeringTorqueEps = cp.vl["STEER_TORQUE_SENSOR"]["STEER_TORQUE_EPS"] + ret.steeringTorqueEps = cp.vl["STEER_TORQUE_SENSOR"]["STEER_TORQUE_EPS"] * self.eps_torque_scale # we could use the override bit from dbc, but it's triggered at too high torque values ret.steeringPressed = abs(ret.steeringTorque) > STEER_THRESHOLD - ret.steerWarning = cp.vl["EPS_STATUS"]["LKA_STATE"] not in [1, 5] + ret.steerWarning = cp.vl["EPS_STATUS"]["LKA_STATE"] not in (1, 5) - if self.CP.carFingerprint in [CAR.LEXUS_IS, CAR.LEXUS_RC]: + if self.CP.carFingerprint in (CAR.LEXUS_IS, CAR.LEXUS_RC): ret.cruiseState.available = cp.vl["DSU_CRUISE"]["MAIN_ON"] != 0 ret.cruiseState.speed = cp.vl["DSU_CRUISE"]["SET_SPEED"] * CV.KPH_TO_MS else: @@ -95,7 +98,7 @@ class CarState(CarStateBase): # these cars are identified by an ACC_TYPE value of 2. # TODO: it is possible to avoid the lockout and gain stop and go if you # send your own ACC_CONTROL msg on startup with ACC_TYPE set to 1 - if (self.CP.carFingerprint not in TSS2_CAR and self.CP.carFingerprint not in [CAR.LEXUS_IS, CAR.LEXUS_RC]) or \ + if (self.CP.carFingerprint not in TSS2_CAR and self.CP.carFingerprint not in (CAR.LEXUS_IS, CAR.LEXUS_RC)) or \ (self.CP.carFingerprint in TSS2_CAR and self.acc_type == 1): self.low_speed_lockout = cp.vl["PCM_CRUISE_2"]["LOW_SPEED_LOCKOUT"] == 2 @@ -107,7 +110,7 @@ class CarState(CarStateBase): else: ret.cruiseState.standstill = self.pcm_acc_status == 7 ret.cruiseState.enabled = bool(cp.vl["PCM_CRUISE"]["CRUISE_ACTIVE"]) - ret.cruiseState.nonAdaptive = cp.vl["PCM_CRUISE"]["CRUISE_STATE"] in [1, 2, 3, 4, 5, 6] + ret.cruiseState.nonAdaptive = cp.vl["PCM_CRUISE"]["CRUISE_STATE"] in (1, 2, 3, 4, 5, 6) ret.genericToggle = bool(cp.vl["LIGHT_STALK"]["AUTO_HIGH_BEAM"]) ret.stockAeb = bool(cp_cam.vl["PRE_COLLISION"]["PRECOLLISION_ACTIVE"] and cp_cam.vl["PRE_COLLISION"]["FORCE"] < -1e-5) @@ -124,87 +127,88 @@ class CarState(CarStateBase): @staticmethod def get_can_parser(CP): - signals = [ - # sig_name, sig_address, default - ("STEER_ANGLE", "STEER_ANGLE_SENSOR", 0), - ("GEAR", "GEAR_PACKET", 0), - ("BRAKE_PRESSED", "BRAKE_MODULE", 0), - ("GAS_PEDAL", "GAS_PEDAL", 0), - ("WHEEL_SPEED_FL", "WHEEL_SPEEDS", 0), - ("WHEEL_SPEED_FR", "WHEEL_SPEEDS", 0), - ("WHEEL_SPEED_RL", "WHEEL_SPEEDS", 0), - ("WHEEL_SPEED_RR", "WHEEL_SPEEDS", 0), - ("DOOR_OPEN_FL", "SEATS_DOORS", 1), - ("DOOR_OPEN_FR", "SEATS_DOORS", 1), - ("DOOR_OPEN_RL", "SEATS_DOORS", 1), - ("DOOR_OPEN_RR", "SEATS_DOORS", 1), - ("SEATBELT_DRIVER_UNLATCHED", "SEATS_DOORS", 1), - ("TC_DISABLED", "ESP_CONTROL", 1), - ("BRAKE_HOLD_ACTIVE", "ESP_CONTROL", 1), - ("STEER_FRACTION", "STEER_ANGLE_SENSOR", 0), - ("STEER_RATE", "STEER_ANGLE_SENSOR", 0), - ("CRUISE_ACTIVE", "PCM_CRUISE", 0), - ("CRUISE_STATE", "PCM_CRUISE", 0), - ("GAS_RELEASED", "PCM_CRUISE", 1), - ("STEER_TORQUE_DRIVER", "STEER_TORQUE_SENSOR", 0), - ("STEER_TORQUE_EPS", "STEER_TORQUE_SENSOR", 0), - ("STEER_ANGLE", "STEER_TORQUE_SENSOR", 0), - ("TURN_SIGNALS", "STEERING_LEVERS", 3), # 3 is no blinkers - ("LKA_STATE", "EPS_STATUS", 0), - ("AUTO_HIGH_BEAM", "LIGHT_STALK", 0), + # sig_name, sig_address + ("STEER_ANGLE", "STEER_ANGLE_SENSOR"), + ("GEAR", "GEAR_PACKET"), + ("BRAKE_PRESSED", "BRAKE_MODULE"), + ("WHEEL_SPEED_FL", "WHEEL_SPEEDS"), + ("WHEEL_SPEED_FR", "WHEEL_SPEEDS"), + ("WHEEL_SPEED_RL", "WHEEL_SPEEDS"), + ("WHEEL_SPEED_RR", "WHEEL_SPEEDS"), + ("DOOR_OPEN_FL", "BODY_CONTROL_STATE"), + ("DOOR_OPEN_FR", "BODY_CONTROL_STATE"), + ("DOOR_OPEN_RL", "BODY_CONTROL_STATE"), + ("DOOR_OPEN_RR", "BODY_CONTROL_STATE"), + ("SEATBELT_DRIVER_UNLATCHED", "BODY_CONTROL_STATE"), + ("TC_DISABLED", "ESP_CONTROL"), + ("BRAKE_HOLD_ACTIVE", "ESP_CONTROL"), + ("STEER_FRACTION", "STEER_ANGLE_SENSOR"), + ("STEER_RATE", "STEER_ANGLE_SENSOR"), + ("CRUISE_ACTIVE", "PCM_CRUISE"), + ("CRUISE_STATE", "PCM_CRUISE"), + ("GAS_RELEASED", "PCM_CRUISE"), + ("STEER_TORQUE_DRIVER", "STEER_TORQUE_SENSOR"), + ("STEER_TORQUE_EPS", "STEER_TORQUE_SENSOR"), + ("STEER_ANGLE", "STEER_TORQUE_SENSOR"), + ("TURN_SIGNALS", "BLINKERS_STATE"), + ("LKA_STATE", "EPS_STATUS"), + ("AUTO_HIGH_BEAM", "LIGHT_STALK"), ] checks = [ ("GEAR_PACKET", 1), ("LIGHT_STALK", 1), - ("STEERING_LEVERS", 0.15), - ("SEATS_DOORS", 3), + ("BLINKERS_STATE", 0.15), + ("BODY_CONTROL_STATE", 3), ("ESP_CONTROL", 3), ("EPS_STATUS", 25), ("BRAKE_MODULE", 40), - ("GAS_PEDAL", 33), ("WHEEL_SPEEDS", 80), ("STEER_ANGLE_SENSOR", 80), ("PCM_CRUISE", 33), ("STEER_TORQUE_SENSOR", 50), ] - if CP.carFingerprint in [CAR.LEXUS_IS, CAR.LEXUS_RC]: - signals.append(("MAIN_ON", "DSU_CRUISE", 0)) - signals.append(("SET_SPEED", "DSU_CRUISE", 0)) + if CP.flags & ToyotaFlags.HYBRID: + signals.append(("GAS_PEDAL", "GAS_PEDAL_HYBRID")) + checks.append(("GAS_PEDAL_HYBRID", 33)) + else: + signals.append(("GAS_PEDAL", "GAS_PEDAL")) + checks.append(("GAS_PEDAL", 33)) + + if CP.carFingerprint in (CAR.LEXUS_IS, CAR.LEXUS_RC): + signals.append(("MAIN_ON", "DSU_CRUISE")) + signals.append(("SET_SPEED", "DSU_CRUISE")) checks.append(("DSU_CRUISE", 5)) else: - signals.append(("MAIN_ON", "PCM_CRUISE_2", 0)) - signals.append(("SET_SPEED", "PCM_CRUISE_2", 0)) - signals.append(("LOW_SPEED_LOCKOUT", "PCM_CRUISE_2", 0)) + signals.append(("MAIN_ON", "PCM_CRUISE_2")) + signals.append(("SET_SPEED", "PCM_CRUISE_2")) + signals.append(("LOW_SPEED_LOCKOUT", "PCM_CRUISE_2")) checks.append(("PCM_CRUISE_2", 33)) # add gas interceptor reading if we are using it if CP.enableGasInterceptor: - signals.append(("INTERCEPTOR_GAS", "GAS_SENSOR", 0)) - signals.append(("INTERCEPTOR_GAS2", "GAS_SENSOR", 0)) + signals.append(("INTERCEPTOR_GAS", "GAS_SENSOR")) + signals.append(("INTERCEPTOR_GAS2", "GAS_SENSOR")) checks.append(("GAS_SENSOR", 50)) if CP.enableBsm: signals += [ - ("L_ADJACENT", "BSM", 0), - ("L_APPROACHING", "BSM", 0), - ("R_ADJACENT", "BSM", 0), - ("R_APPROACHING", "BSM", 0), - ] - checks += [ - ("BSM", 1) + ("L_ADJACENT", "BSM"), + ("L_APPROACHING", "BSM"), + ("R_ADJACENT", "BSM"), + ("R_APPROACHING", "BSM"), ] + checks.append(("BSM", 1)) return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 0) @staticmethod def get_cam_can_parser(CP): - signals = [ - ("FORCE", "PRE_COLLISION", 0), - ("PRECOLLISION_ACTIVE", "PRE_COLLISION", 0), + ("FORCE", "PRE_COLLISION"), + ("PRECOLLISION_ACTIVE", "PRE_COLLISION"), ] # use steering message to check if panda is connected to frc @@ -214,7 +218,7 @@ class CarState(CarStateBase): ] if CP.carFingerprint in TSS2_CAR: - signals.append(("ACC_TYPE", "ACC_CONTROL", 0)) + signals.append(("ACC_TYPE", "ACC_CONTROL")) checks.append(("ACC_CONTROL", 33)) return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 2) diff --git a/selfdrive/car/toyota/interface.py b/selfdrive/car/toyota/interface.py old mode 100755 new mode 100644 index f9d6b586f..65c2faaca --- a/selfdrive/car/toyota/interface.py +++ b/selfdrive/car/toyota/interface.py @@ -2,7 +2,7 @@ from cereal import car from selfdrive.config import Conversions as CV from selfdrive.car.toyota.tunes import LatTunes, LongTunes, set_long_tune, set_lat_tune -from selfdrive.car.toyota.values import Ecu, CAR, TSS2_CAR, NO_DSU_CAR, MIN_ACC_SPEED, CarControllerParams +from selfdrive.car.toyota.values import Ecu, CAR, ToyotaFlags, TSS2_CAR, NO_DSU_CAR, MIN_ACC_SPEED, EPS_SCALE, CarControllerParams from selfdrive.car import STD_CARGO_KG, scale_rot_inertia, scale_tire_stiffness, gen_empty_fingerprint, get_safety_config from selfdrive.car.interfaces import CarInterfaceBase @@ -20,17 +20,15 @@ class CarInterface(CarInterfaceBase): ret.carName = "toyota" ret.safetyConfigs = [get_safety_config(car.CarParams.SafetyModel.toyota)] + ret.safetyConfigs[0].safetyParam = EPS_SCALE[candidate] ret.steerActuatorDelay = 0.12 # Default delay, Prius has larger delay ret.steerLimitTimer = 0.4 - ret.stoppingControl = False # Toyota starts braking more when it thinks you want to stop - # Most cars use this default safety param - ret.safetyConfigs[0].safetyParam = 73 + stop_and_go = False if candidate == CAR.PRIUS: - ret.safetyConfigs[0].safetyParam = 66 # see conversion factor for STEER_TORQUE_EPS in dbc file stop_and_go = True ret.wheelbase = 2.70 ret.steerRatio = 15.74 # unknown end-to-end spec @@ -40,7 +38,15 @@ class CarInterface(CarInterfaceBase): set_lat_tune(ret.lateralTuning, LatTunes.INDI_PRIUS) ret.steerActuatorDelay = 0.3 - elif candidate in [CAR.RAV4, CAR.RAV4H]: + elif candidate == CAR.PRIUS_V: + stop_and_go = True + ret.wheelbase = 2.78 + ret.steerRatio = 17.4 + tire_stiffness_factor = 0.5533 + ret.mass = 4387. * CV.LB_TO_KG + STD_CARGO_KG + set_lat_tune(ret.lateralTuning, LatTunes.LQR_RAV4) + + elif candidate in (CAR.RAV4, CAR.RAV4H): stop_and_go = True if (candidate in CAR.RAV4H) else False ret.wheelbase = 2.65 ret.steerRatio = 16.88 # 14.5 is spec end-to-end @@ -49,49 +55,22 @@ class CarInterface(CarInterfaceBase): set_lat_tune(ret.lateralTuning, LatTunes.LQR_RAV4) elif candidate == CAR.COROLLA: - ret.safetyConfigs[0].safetyParam = 88 - stop_and_go = False ret.wheelbase = 2.70 ret.steerRatio = 18.27 tire_stiffness_factor = 0.444 # not optimized yet ret.mass = 2860. * CV.LB_TO_KG + STD_CARGO_KG # mean between normal and hybrid set_lat_tune(ret.lateralTuning, LatTunes.PID_A) - elif candidate == CAR.LEXUS_RX: - stop_and_go = True - ret.wheelbase = 2.79 - ret.steerRatio = 14.8 - tire_stiffness_factor = 0.5533 - ret.mass = 4387. * CV.LB_TO_KG + STD_CARGO_KG - set_lat_tune(ret.lateralTuning, LatTunes.PID_B) - - elif candidate == CAR.LEXUS_RXH: + elif candidate in (CAR.LEXUS_RX, CAR.LEXUS_RXH, CAR.LEXUS_RX_TSS2, CAR.LEXUS_RXH_TSS2): stop_and_go = True ret.wheelbase = 2.79 ret.steerRatio = 16. # 14.8 is spec end-to-end - tire_stiffness_factor = 0.444 # not optimized yet + ret.wheelSpeedFactor = 1.035 + tire_stiffness_factor = 0.5533 ret.mass = 4481. * CV.LB_TO_KG + STD_CARGO_KG # mean between min and max set_lat_tune(ret.lateralTuning, LatTunes.PID_C) - elif candidate == CAR.LEXUS_RX_TSS2: - stop_and_go = True - ret.wheelbase = 2.79 - ret.steerRatio = 14.8 - tire_stiffness_factor = 0.5533 # not optimized yet - ret.mass = 4387. * CV.LB_TO_KG + STD_CARGO_KG - set_lat_tune(ret.lateralTuning, LatTunes.PID_D) - ret.wheelSpeedFactor = 1.035 - - elif candidate == CAR.LEXUS_RXH_TSS2: - stop_and_go = True - ret.wheelbase = 2.79 - ret.steerRatio = 16.0 # 14.8 is spec end-to-end - tire_stiffness_factor = 0.444 # not optimized yet - ret.mass = 4481.0 * CV.LB_TO_KG + STD_CARGO_KG # mean between min and max - set_lat_tune(ret.lateralTuning, LatTunes.PID_E) - ret.wheelSpeedFactor = 1.035 - - elif candidate in [CAR.CHR, CAR.CHRH]: + elif candidate in (CAR.CHR, CAR.CHRH): stop_and_go = True ret.wheelbase = 2.63906 ret.steerRatio = 13.6 @@ -99,7 +78,7 @@ class CarInterface(CarInterfaceBase): ret.mass = 3300. * CV.LB_TO_KG + STD_CARGO_KG set_lat_tune(ret.lateralTuning, LatTunes.PID_F) - elif candidate in [CAR.CAMRY, CAR.CAMRYH, CAR.CAMRY_TSS2, CAR.CAMRYH_TSS2]: + elif candidate in (CAR.CAMRY, CAR.CAMRYH, CAR.CAMRY_TSS2, CAR.CAMRYH_TSS2): stop_and_go = True ret.wheelbase = 2.82448 ret.steerRatio = 13.7 @@ -107,7 +86,7 @@ class CarInterface(CarInterfaceBase): ret.mass = 3400. * CV.LB_TO_KG + STD_CARGO_KG # mean between normal and hybrid set_lat_tune(ret.lateralTuning, LatTunes.PID_C) - elif candidate in [CAR.HIGHLANDER_TSS2, CAR.HIGHLANDERH_TSS2]: + elif candidate in (CAR.HIGHLANDER_TSS2, CAR.HIGHLANDERH_TSS2): stop_and_go = True ret.wheelbase = 2.84988 # 112.2 in = 2.84988 m ret.steerRatio = 16.0 @@ -115,7 +94,7 @@ class CarInterface(CarInterfaceBase): ret.mass = 4700. * CV.LB_TO_KG + STD_CARGO_KG # 4260 + 4-5 people set_lat_tune(ret.lateralTuning, LatTunes.PID_G) - elif candidate in [CAR.HIGHLANDER, CAR.HIGHLANDERH]: + elif candidate in (CAR.HIGHLANDER, CAR.HIGHLANDERH): stop_and_go = True ret.wheelbase = 2.78 ret.steerRatio = 16.0 @@ -123,15 +102,14 @@ class CarInterface(CarInterfaceBase): ret.mass = 4607. * CV.LB_TO_KG + STD_CARGO_KG # mean between normal and hybrid limited set_lat_tune(ret.lateralTuning, LatTunes.PID_G) - elif candidate in [CAR.AVALON, CAR.AVALON_2019, CAR.AVALONH_2019]: - stop_and_go = False + elif candidate in (CAR.AVALON, CAR.AVALON_2019, CAR.AVALONH_2019, CAR.AVALON_TSS2): ret.wheelbase = 2.82 ret.steerRatio = 14.8 # Found at https://pressroom.toyota.com/releases/2016+avalon+product+specs.download tire_stiffness_factor = 0.7983 ret.mass = 3505. * CV.LB_TO_KG + STD_CARGO_KG # mean between normal and hybrid set_lat_tune(ret.lateralTuning, LatTunes.PID_H) - elif candidate in [CAR.RAV4_TSS2, CAR.RAV4H_TSS2]: + elif candidate in (CAR.RAV4_TSS2, CAR.RAV4H_TSS2): stop_and_go = True ret.wheelbase = 2.68986 ret.steerRatio = 14.3 @@ -146,7 +124,7 @@ class CarInterface(CarInterfaceBase): set_lat_tune(ret.lateralTuning, LatTunes.PID_I) break - elif candidate in [CAR.COROLLA_TSS2, CAR.COROLLAH_TSS2]: + elif candidate in (CAR.COROLLA_TSS2, CAR.COROLLAH_TSS2): stop_and_go = True ret.wheelbase = 2.67 # Average between 2.70 for sedan and 2.64 for hatchback ret.steerRatio = 13.9 @@ -154,20 +132,12 @@ class CarInterface(CarInterfaceBase): ret.mass = 3060. * CV.LB_TO_KG + STD_CARGO_KG set_lat_tune(ret.lateralTuning, LatTunes.PID_D) - elif candidate in [CAR.LEXUS_ES_TSS2, CAR.LEXUS_ESH_TSS2]: + elif candidate in (CAR.LEXUS_ES_TSS2, CAR.LEXUS_ESH_TSS2, CAR.LEXUS_ESH): stop_and_go = True ret.wheelbase = 2.8702 ret.steerRatio = 16.0 # not optimized tire_stiffness_factor = 0.444 # not optimized yet - ret.mass = 3704. * CV.LB_TO_KG + STD_CARGO_KG - set_lat_tune(ret.lateralTuning, LatTunes.PID_D) - - elif candidate == CAR.LEXUS_ESH: - stop_and_go = True - ret.wheelbase = 2.8190 - ret.steerRatio = 16.06 - tire_stiffness_factor = 0.444 # not optimized yet - ret.mass = 3682. * CV.LB_TO_KG + STD_CARGO_KG + ret.mass = 3677. * CV.LB_TO_KG + STD_CARGO_KG # mean between min and max set_lat_tune(ret.lateralTuning, LatTunes.PID_D) elif candidate == CAR.SIENNA: @@ -178,26 +148,14 @@ class CarInterface(CarInterfaceBase): ret.mass = 4590. * CV.LB_TO_KG + STD_CARGO_KG set_lat_tune(ret.lateralTuning, LatTunes.PID_J) - elif candidate == CAR.LEXUS_IS: - ret.safetyConfigs[0].safetyParam = 77 - stop_and_go = False + elif candidate in (CAR.LEXUS_IS, CAR.LEXUS_RC): ret.wheelbase = 2.79908 ret.steerRatio = 13.3 tire_stiffness_factor = 0.444 ret.mass = 3736.8 * CV.LB_TO_KG + STD_CARGO_KG set_lat_tune(ret.lateralTuning, LatTunes.PID_L) - elif candidate == CAR.LEXUS_RC: - ret.safetyConfigs[0].safetyParam = 77 - stop_and_go = False - ret.wheelbase = 2.73050 - ret.steerRatio = 13.3 - tire_stiffness_factor = 0.444 - ret.mass = 3736.8 * CV.LB_TO_KG + STD_CARGO_KG - set_lat_tune(ret.lateralTuning, LatTunes.PID_L) - elif candidate == CAR.LEXUS_CTH: - ret.safetyConfigs[0].safetyParam = 100 stop_and_go = True ret.wheelbase = 2.60 ret.steerRatio = 18.6 @@ -205,7 +163,7 @@ class CarInterface(CarInterfaceBase): ret.mass = 3108 * CV.LB_TO_KG + STD_CARGO_KG # mean between min and max set_lat_tune(ret.lateralTuning, LatTunes.PID_M) - elif candidate in [CAR.LEXUS_NXH, CAR.LEXUS_NX, CAR.LEXUS_NX_TSS2]: + elif candidate in (CAR.LEXUS_NXH, CAR.LEXUS_NX, CAR.LEXUS_NX_TSS2): stop_and_go = True ret.wheelbase = 2.66 ret.steerRatio = 14.7 @@ -259,21 +217,18 @@ class CarInterface(CarInterfaceBase): # if the smartDSU is detected, openpilot can send ACC_CMD (and the smartDSU will block it from the DSU) or not (the DSU is "connected") ret.openpilotLongitudinalControl = smartDsu or ret.enableDsu or candidate in TSS2_CAR + if 0x245 in fingerprint[0]: + ret.flags |= ToyotaFlags.HYBRID.value + # min speed to enable ACC. if car can do stop and go, then set enabling speed # to a negative value, so it won't matter. ret.minEnableSpeed = -1. if (stop_and_go or ret.enableGasInterceptor) else MIN_ACC_SPEED - # removing the DSU disables AEB and it's considered a community maintained feature - # intercepting the DSU is a community feature since it requires unofficial hardware - ret.communityFeature = ret.enableGasInterceptor or ret.enableDsu or smartDsu - if ret.enableGasInterceptor: set_long_tune(ret.longitudinalTuning, LongTunes.PEDAL) - elif candidate in [CAR.COROLLA_TSS2, CAR.COROLLAH_TSS2, CAR.RAV4_TSS2, CAR.RAV4H_TSS2, CAR.LEXUS_NX_TSS2, - CAR.HIGHLANDER_TSS2, CAR.HIGHLANDERH_TSS2, CAR.PRIUS_TSS2]: + elif candidate in TSS2_CAR: set_long_tune(ret.longitudinalTuning, LongTunes.TSS2) ret.stoppingDecelRate = 0.3 # reach stopping target smoothly - ret.startingAccelRate = 6.0 # release brakes fast else: set_long_tune(ret.longitudinalTuning, LongTunes.TSS) @@ -312,12 +267,12 @@ class CarInterface(CarInterfaceBase): # pass in a car.CarControl # to be called @ 100hz def apply(self, c): - - can_sends = self.CC.update(c.enabled, c.active, self.CS, self.frame, - c.actuators, c.cruiseControl.cancel, - c.hudControl.visualAlert, c.hudControl.leftLaneVisible, - c.hudControl.rightLaneVisible, c.hudControl.leadVisible, - c.hudControl.leftLaneDepart, c.hudControl.rightLaneDepart) + hud_control = c.hudControl + ret = self.CC.update(c.enabled, c.active, self.CS, self.frame, + c.actuators, c.cruiseControl.cancel, + hud_control.visualAlert, hud_control.leftLaneVisible, + hud_control.rightLaneVisible, hud_control.leadVisible, + hud_control.leftLaneDepart, hud_control.rightLaneDepart) self.frame += 1 - return can_sends + return ret diff --git a/selfdrive/car/toyota/radar_interface.py b/selfdrive/car/toyota/radar_interface.py index a7d2ec37b..590840851 100755 --- a/selfdrive/car/toyota/radar_interface.py +++ b/selfdrive/car/toyota/radar_interface.py @@ -4,6 +4,7 @@ from cereal import car from selfdrive.car.toyota.values import NO_DSU_CAR, DBC, TSS2_CAR from selfdrive.car.interfaces import RadarInterfaceBase + def _create_radar_can_parser(car_fingerprint): if car_fingerprint in TSS2_CAR: RADAR_A_MSGS = list(range(0x180, 0x190)) @@ -16,11 +17,10 @@ def _create_radar_can_parser(car_fingerprint): msg_b_n = len(RADAR_B_MSGS) signals = list(zip(['LONG_DIST'] * msg_a_n + ['NEW_TRACK'] * msg_a_n + ['LAT_DIST'] * msg_a_n + - ['REL_SPEED'] * msg_a_n + ['VALID'] * msg_a_n + ['SCORE'] * msg_b_n, - RADAR_A_MSGS * 5 + RADAR_B_MSGS, - [255] * msg_a_n + [1] * msg_a_n + [0] * msg_a_n + [0] * msg_a_n + [0] * msg_a_n + [0] * msg_b_n)) + ['REL_SPEED'] * msg_a_n + ['VALID'] * msg_a_n + ['SCORE'] * msg_b_n, + RADAR_A_MSGS * 5 + RADAR_B_MSGS)) - checks = list(zip(RADAR_A_MSGS + RADAR_B_MSGS, [20]*(msg_a_n + msg_b_n))) + checks = list(zip(RADAR_A_MSGS + RADAR_B_MSGS, [20] * (msg_a_n + msg_b_n))) return CANParser(DBC[car_fingerprint]['radar'], signals, checks, 1) diff --git a/selfdrive/car/toyota/toyotacan.py b/selfdrive/car/toyota/toyotacan.py index 5a78e3c7b..ca5812679 100644 --- a/selfdrive/car/toyota/toyotacan.py +++ b/selfdrive/car/toyota/toyotacan.py @@ -67,19 +67,34 @@ def create_fcw_command(packer, fcw): return packer.make_can_msg("ACC_HUD", 0, values) -def create_ui_command(packer, steer, chime, left_line, right_line, left_lane_depart, right_lane_depart): +def create_ui_command(packer, steer, chime, left_line, right_line, left_lane_depart, right_lane_depart, enabled): values = { - "RIGHT_LINE": 3 if right_lane_depart else 1 if right_line else 2, - "LEFT_LINE": 3 if left_lane_depart else 1 if left_line else 2, - "BARRIERS" : 3 if left_lane_depart else 2 if right_lane_depart else 0, - "SET_ME_X0C": 0x0c, - "SET_ME_X2C": 0x2c, - "SET_ME_X38": 0x38, - "SET_ME_X02": 0x02, - "SET_ME_X01": 1, - "SET_ME_X01_2": 1, - "REPEATED_BEEPS": 0, "TWO_BEEPS": chime, "LDA_ALERT": steer, + "RIGHT_LINE": 3 if right_lane_depart else 1 if right_line else 2, + "LEFT_LINE": 3 if left_lane_depart else 1 if left_line else 2, + "BARRIERS" : 1 if enabled else 0, + + # static signals + "SET_ME_X02": 2, + "SET_ME_X01": 1, + "LKAS_STATUS": 1, + "REPEATED_BEEPS": 0, + "LANE_SWAY_FLD": 7, + "LANE_SWAY_BUZZER": 0, + "LANE_SWAY_WARNING": 0, + "LDA_FRONT_CAMERA_BLOCKED": 0, + "TAKE_CONTROL": 0, + "LANE_SWAY_SENSITIVITY": 2, + "LANE_SWAY_TOGGLE": 1, + "LDA_ON_MESSAGE": 0, + "LDA_SPEED_TOO_LOW": 0, + "LDA_SA_TOGGLE": 1, + "LDA_SENSITIVITY": 2, + "LDA_UNAVAILABLE": 0, + "LDA_MALFUNCTION": 0, + "LDA_UNAVAILABLE_QUIET": 0, + "ADJUSTING_CAMERA": 0, + "LDW_EXIST": 1, } return packer.make_can_msg("LKAS_HUD", 0, values) diff --git a/selfdrive/car/toyota/tunes.py b/selfdrive/car/toyota/tunes.py index 15c8bbfcc..f26fc72a0 100644 --- a/selfdrive/car/toyota/tunes.py +++ b/selfdrive/car/toyota/tunes.py @@ -80,10 +80,6 @@ def set_lat_tune(tune, name): tune.pid.kpV = [0.2] tune.pid.kiV = [0.05] tune.pid.kf = 0.00003 - elif name == LatTunes.PID_B: - tune.pid.kpV = [0.6] - tune.pid.kiV = [0.05] - tune.pid.kf = 0.00006 elif name == LatTunes.PID_C: tune.pid.kpV = [0.6] tune.pid.kiV = [0.1] @@ -92,10 +88,6 @@ def set_lat_tune(tune, name): tune.pid.kpV = [0.6] tune.pid.kiV = [0.1] tune.pid.kf = 0.00007818594 - elif name == LatTunes.PID_E: - tune.pid.kpV = [0.6] - tune.pid.kiV = [0.15] - tune.pid.kf = 0.00007818594 elif name == LatTunes.PID_F: tune.pid.kpV = [0.723] tune.pid.kiV = [0.0428] diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 692de379b..99937561a 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -1,4 +1,5 @@ -# flake8: noqa +from collections import defaultdict +from enum import IntFlag from cereal import car from selfdrive.car import dbc_dict @@ -18,12 +19,18 @@ class CarControllerParams: STEER_DELTA_DOWN = 25 # always lower than 45 otherwise the Rav4 faults (Prius seems ok with 50) STEER_ERROR_MAX = 350 # max delta between torque cmd and torque motor + +class ToyotaFlags(IntFlag): + HYBRID = 1 + + class CAR: # Toyota ALPHARD_TSS2 = "TOYOTA ALPHARD 2020" AVALON = "TOYOTA AVALON 2016" AVALON_2019 = "TOYOTA AVALON 2019" AVALONH_2019 = "TOYOTA AVALON HYBRID 2019" + AVALON_TSS2 = "TOYOTA AVALON 2022" CAMRY = "TOYOTA CAMRY 2018" CAMRYH = "TOYOTA CAMRY HYBRID 2018" CAMRY_TSS2 = "TOYOTA CAMRY 2021" # TSS 2.5 @@ -39,6 +46,7 @@ class CAR: HIGHLANDERH = "TOYOTA HIGHLANDER HYBRID 2018" HIGHLANDERH_TSS2 = "TOYOTA HIGHLANDER HYBRID 2020" PRIUS = "TOYOTA PRIUS 2017" + PRIUS_V = "TOYOTA PRIUS v 2017" PRIUS_TSS2 = "TOYOTA PRIUS TSS2 2021" RAV4 = "TOYOTA RAV4 2017" RAV4H = "TOYOTA RAV4 HYBRID 2017" @@ -66,25 +74,24 @@ class CAR: STATIC_DSU_MSGS = [ (0x128, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.LEXUS_NXH, CAR.LEXUS_NX, CAR.RAV4, CAR.COROLLA, CAR.AVALON), 1, 3, b'\xf4\x01\x90\x83\x00\x37'), (0x128, (CAR.HIGHLANDER, CAR.HIGHLANDERH, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ESH), 1, 3, b'\x03\x00\x20\x00\x00\x52'), - (0x141, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.LEXUS_NXH, CAR.LEXUS_NX, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH, CAR.AVALON, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ESH, CAR.LEXUS_RX), 1, 2, b'\x00\x00\x00\x46'), - (0x160, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.LEXUS_NXH, CAR.LEXUS_NX, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH, CAR.AVALON, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ESH, CAR.LEXUS_RX), 1, 7, b'\x00\x00\x08\x12\x01\x31\x9c\x51'), - (0x161, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.LEXUS_NXH, CAR.LEXUS_NX, CAR.RAV4, CAR.COROLLA, CAR.AVALON, CAR.LEXUS_RX), 1, 7, b'\x00\x1e\x00\x00\x00\x80\x07'), + (0x141, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.LEXUS_NXH, CAR.LEXUS_NX, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH, CAR.AVALON, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ESH, CAR.LEXUS_RX, CAR.PRIUS_V), 1, 2, b'\x00\x00\x00\x46'), + (0x160, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.LEXUS_NXH, CAR.LEXUS_NX, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH, CAR.AVALON, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ESH, CAR.LEXUS_RX, CAR.PRIUS_V), 1, 7, b'\x00\x00\x08\x12\x01\x31\x9c\x51'), + (0x161, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.LEXUS_NXH, CAR.LEXUS_NX, CAR.RAV4, CAR.COROLLA, CAR.AVALON, CAR.LEXUS_RX, CAR.PRIUS_V), 1, 7, b'\x00\x1e\x00\x00\x00\x80\x07'), (0X161, (CAR.HIGHLANDERH, CAR.HIGHLANDER, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ESH), 1, 7, b'\x00\x1e\x00\xd4\x00\x00\x5b'), - (0x283, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.LEXUS_NXH, CAR.LEXUS_NX, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH, CAR.AVALON, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ESH, CAR.LEXUS_RX), 0, 3, b'\x00\x00\x00\x00\x00\x00\x8c'), + (0x283, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.LEXUS_NXH, CAR.LEXUS_NX, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH, CAR.AVALON, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ESH, CAR.LEXUS_RX, CAR.PRIUS_V), 0, 3, b'\x00\x00\x00\x00\x00\x00\x8c'), (0x2E6, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH), 0, 3, b'\xff\xf8\x00\x08\x7f\xe0\x00\x4e'), (0x2E7, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH), 0, 3, b'\xa8\x9c\x31\x9c\x00\x00\x00\x02'), (0x33E, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH), 0, 20, b'\x0f\xff\x26\x40\x00\x1f\x00'), - (0x344, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.LEXUS_NXH, CAR.LEXUS_NX, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH, CAR.AVALON, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ESH, CAR.LEXUS_RX), 0, 5, b'\x00\x00\x01\x00\x00\x00\x00\x50'), + (0x344, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.LEXUS_NXH, CAR.LEXUS_NX, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.HIGHLANDERH, CAR.AVALON, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ESH, CAR.LEXUS_RX, CAR.PRIUS_V), 0, 5, b'\x00\x00\x01\x00\x00\x00\x00\x50'), (0x365, (CAR.PRIUS, CAR.LEXUS_RXH, CAR.LEXUS_NXH, CAR.LEXUS_NX, CAR.HIGHLANDERH), 0, 20, b'\x00\x00\x00\x80\x03\x00\x08'), - (0x365, (CAR.RAV4, CAR.RAV4H, CAR.COROLLA, CAR.HIGHLANDER, CAR.AVALON, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ESH, CAR.LEXUS_RX), 0, 20, b'\x00\x00\x00\x80\xfc\x00\x08'), + (0x365, (CAR.RAV4, CAR.RAV4H, CAR.COROLLA, CAR.HIGHLANDER, CAR.AVALON, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ESH, CAR.LEXUS_RX, CAR.PRIUS_V), 0, 20, b'\x00\x00\x00\x80\xfc\x00\x08'), (0x366, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.LEXUS_NXH, CAR.LEXUS_NX, CAR.HIGHLANDERH), 0, 20, b'\x00\x00\x4d\x82\x40\x02\x00'), - (0x366, (CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.AVALON, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ESH, CAR.LEXUS_RX), 0, 20, b'\x00\x72\x07\xff\x09\xfe\x00'), + (0x366, (CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDER, CAR.AVALON, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ESH, CAR.LEXUS_RX, CAR.PRIUS_V), 0, 20, b'\x00\x72\x07\xff\x09\xfe\x00'), (0x470, (CAR.PRIUS, CAR.LEXUS_RXH), 1, 100, b'\x00\x00\x02\x7a'), - (0x470, (CAR.HIGHLANDER, CAR.HIGHLANDERH, CAR.RAV4H, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ESH), 1, 100, b'\x00\x00\x01\x79'), - (0x4CB, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.LEXUS_NXH, CAR.LEXUS_NX, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDERH, CAR.HIGHLANDER, CAR.AVALON, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ESH, CAR.LEXUS_RX), 0, 100, b'\x0c\x00\x00\x00\x00\x00\x00\x00'), + (0x470, (CAR.HIGHLANDER, CAR.HIGHLANDERH, CAR.RAV4H, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ESH, CAR.PRIUS_V), 1, 100, b'\x00\x00\x01\x79'), + (0x4CB, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.LEXUS_NXH, CAR.LEXUS_NX, CAR.RAV4, CAR.COROLLA, CAR.HIGHLANDERH, CAR.HIGHLANDER, CAR.AVALON, CAR.SIENNA, CAR.LEXUS_CTH, CAR.LEXUS_ESH, CAR.LEXUS_RX, CAR.PRIUS_V), 0, 100, b'\x0c\x00\x00\x00\x00\x00\x00\x00'), ] - FW_VERSIONS = { CAR.AVALON: { (Ecu.esp, 0x7b0, None): [ @@ -166,6 +173,23 @@ FW_VERSIONS = { b'8646F0702100\x00\x00\x00\x00', ], }, + CAR.AVALON_TSS2: { + (Ecu.esp, 0x7b0, None): [ + b'\x01F152607280\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B41110\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x700, None): [ + b'\x01896630742000\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F6201200\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F4104100\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', + ], + }, CAR.CAMRY: { (Ecu.engine, 0x700, None): [ b'\x018966306L3100\x00\x00\x00\x00', @@ -344,12 +368,14 @@ FW_VERSIONS = { b'\x018966306Q5000\x00\x00\x00\x00', b'\x018966306T3100\x00\x00\x00\x00', b'\x018966306T3200\x00\x00\x00\x00', + b'\x018966306T4000\x00\x00\x00\x00', b'\x018966306T4100\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x750, 0xf): [ b'\x018821F6201200\x00\x00\x00\x00', ], (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F0602100\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', b'\x028646F0602200\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', b'\x028646F3305200\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', b'\x028646F3305300\x00\x00\x00\x008646G5301200\x00\x00\x00\x00', @@ -376,6 +402,7 @@ FW_VERSIONS = { }, CAR.CHR: { (Ecu.engine, 0x700, None): [ + b'\x01896631021100\x00\x00\x00\x00', b'\x01896631017100\x00\x00\x00\x00', b'\x01896631017200\x00\x00\x00\x00', b'\x0189663F413100\x00\x00\x00\x00', @@ -526,6 +553,7 @@ FW_VERSIONS = { b'\x01896630ZG5100\x00\x00\x00\x00', b'\x01896630ZG5200\x00\x00\x00\x00', b'\x01896630ZG5300\x00\x00\x00\x00', + b'\x01896630ZP1000\x00\x00\x00\x00', b'\x01896630ZP2000\x00\x00\x00\x00', b'\x01896630ZQ5000\x00\x00\x00\x00', b'\x018966312L8000\x00\x00\x00\x00', @@ -536,6 +564,7 @@ FW_VERSIONS = { b'\x018966312P9200\x00\x00\x00\x00', b'\x018966312P9300\x00\x00\x00\x00', b'\x018966312Q2300\x00\x00\x00\x00', + b'\x018966312Q8000\x00\x00\x00\x00', b'\x018966312R0000\x00\x00\x00\x00', b'\x018966312R0100\x00\x00\x00\x00', b'\x018966312R1000\x00\x00\x00\x00', @@ -557,6 +586,7 @@ FW_VERSIONS = { b'\x03312N6000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00', b'\x03312N6100\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00', b'\x03312N6100\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00', + b'\x02312K4000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', ], (Ecu.eps, 0x7a1, None): [ b'\x018965B12350\x00\x00\x00\x00\x00\x00', @@ -568,6 +598,7 @@ FW_VERSIONS = { b'\x018965B1255000\x00\x00\x00\x00', b'8965B12361\x00\x00\x00\x00\x00\x00', b'8965B16011\x00\x00\x00\x00\x00\x00', + b'\x018965B12510\x00\x00\x00\x00\x00\x00' ], (Ecu.esp, 0x7b0, None): [ b'\x01F152602280\x00\x00\x00\x00\x00\x00', @@ -582,10 +613,13 @@ FW_VERSIONS = { b'\x01F152612B51\x00\x00\x00\x00\x00\x00', b'\x01F152612B60\x00\x00\x00\x00\x00\x00', b'\x01F152612B61\x00\x00\x00\x00\x00\x00', + b'\x01F152612B62\x00\x00\x00\x00\x00\x00', b'\x01F152612B71\x00\x00\x00\x00\x00\x00', + b'\x01F152612B81\x00\x00\x00\x00\x00\x00', b'\x01F152612B90\x00\x00\x00\x00\x00\x00', b'\x01F152612C00\x00\x00\x00\x00\x00\x00', b'F152602191\x00\x00\x00\x00\x00\x00', + b'\x01F152612862\x00\x00\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x750, 0xf): [ b'\x018821F3301100\x00\x00\x00\x00', @@ -613,6 +647,7 @@ FW_VERSIONS = { b'\x01896637624000\x00\x00\x00\x00', b'\x01896637626000\x00\x00\x00\x00', b'\x01896637648000\x00\x00\x00\x00', + b'\x01896637643000\x00\x00\x00\x00', b'\x02896630ZJ5000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x02896630ZN8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x02896630ZQ3000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', @@ -768,6 +803,7 @@ FW_VERSIONS = { b'\x01896630EB2100\x00\x00\x00\x00', b'\x01896630EB2200\x00\x00\x00\x00', b'\x01896630EC4000\x00\x00\x00\x00', + b'\x01896630ED9000\x00\x00\x00\x00', b'\x01896630EE1000\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x750, 0xf): [ @@ -788,15 +824,18 @@ FW_VERSIONS = { b'\x01F15264872300\x00\x00\x00\x00', b'\x01F15264872400\x00\x00\x00\x00', b'\x01F15264872500\x00\x00\x00\x00', + b'\x01F15264873500\x00\x00\x00\x00', b'\x01F152648C6300\x00\x00\x00\x00', ], (Ecu.engine, 0x700, None): [ + b'\x01896630E67000\x00\x00\x00\x00', b'\x01896630EA1000\x00\x00\x00\x00', b'\x01896630EE4000\x00\x00\x00\x00', b'\x01896630EA1000\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', b'\x02896630E66000\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'\x02896630E66100\x00\x00\x00\x00897CF4801001\x00\x00\x00\x00', ], (Ecu.fwdRadar, 0x750, 0xf): [ b'\x018821F3301400\x00\x00\x00\x00', @@ -947,6 +986,23 @@ FW_VERSIONS = { b'8646F4705200\x00\x00\x00\x00', ], }, + CAR.PRIUS_V: { + (Ecu.esp, 0x7b0, None): [ + b'F152647280\x00\x00\x00\x00\x00\x00', + ], + (Ecu.engine, 0x7e0, None): [ + b'\x0234781000\x00\x00\x00\x00\x00\x00\x00\x00A4701000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.dsu, 0x791, None): [ + b'881514705100\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'8821F4702300\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'8646F4703300\x00\x00\x00\x00', + ], + }, CAR.RAV4: { (Ecu.engine, 0x7e0, None): [ b'\x02342Q1000\x00\x00\x00\x00\x00\x00\x00\x0054212000\x00\x00\x00\x00\x00\x00\x00\x00', @@ -1499,20 +1555,21 @@ FW_VERSIONS = { }, CAR.LEXUS_RX_TSS2: { (Ecu.engine, 0x700, None): [ - b'\x01896630EC9000\x00\x00\x00\x00', - b'\x01896634D12000\x00\x00\x00\x00', - b'\x01896630EB0000\x00\x00\x00\x00', b'\x01896630EA9000\x00\x00\x00\x00', + b'\x01896630EB0000\x00\x00\x00\x00', + b'\x01896630EC9000\x00\x00\x00\x00', b'\x01896630ED0000\x00\x00\x00\x00', + b'\x01896630ED6000\x00\x00\x00\x00', b'\x018966348W5100\x00\x00\x00\x00', b'\x018966348W9000\x00\x00\x00\x00', + b'\x01896634D12000\x00\x00\x00\x00', b'\x01896634D12100\x00\x00\x00\x00', ], (Ecu.esp, 0x7b0, None): [ - b'\x01F152648801\x00\x00\x00\x00\x00\x00', b'\x01F15260E031\x00\x00\x00\x00\x00\x00', b'\x01F15260E041\x00\x00\x00\x00\x00\x00', b'\x01F152648781\x00\x00\x00\x00\x00\x00', + b'\x01F152648801\x00\x00\x00\x00\x00\x00', ], (Ecu.eps, 0x7a1, None): [ b'8965B48261\x00\x00\x00\x00\x00\x00', @@ -1524,8 +1581,9 @@ FW_VERSIONS = { b'\x018821F3301400\x00\x00\x00\x00', ], (Ecu.fwdCamera, 0x750, 0x6d): [ - b'\x028646F4810200\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', b'\x028646F4810100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00', + b'\x028646F4810200\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + b'\x028646F4810300\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', ], }, CAR.LEXUS_RXH_TSS2: { @@ -1552,6 +1610,7 @@ FW_VERSIONS = { }, CAR.PRIUS_TSS2: { (Ecu.engine, 0x700, None): [ + b'\x028966347B1000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x028966347C6000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x028966347C8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00', b'\x038966347C0000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710101\x00\x00\x00\x00', @@ -1564,6 +1623,7 @@ FW_VERSIONS = { b'F152647510\x00\x00\x00\x00\x00\x00', b'F152647520\x00\x00\x00\x00\x00\x00', b'F152647521\x00\x00\x00\x00\x00\x00', + b'F152647531\x00\x00\x00\x00\x00\x00', ], (Ecu.eps, 0x7a1, None): [ b'8965B47070\x00\x00\x00\x00\x00\x00', @@ -1584,63 +1644,79 @@ FW_VERSIONS = { (Ecu.fwdCamera, 0x750, 0x6d): [b'\x028646F6201400\x00\x00\x00\x008646G5301200\x00\x00\x00\x00',], }, CAR.ALPHARD_TSS2: { - (Ecu.engine, 0x7e0, None): [b'\x0235883000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00',], - (Ecu.eps, 0x7a1, None): [b'8965B58040\x00\x00\x00\x00\x00\x00',], - (Ecu.fwdRadar, 0x750, 0xf): [b'\x018821F3301400\x00\x00\x00\x00',], - (Ecu.fwdCamera, 0x750, 0x6d): [b'\x028646F5803200\x00\x00\x00\x008646G2601400\x00\x00\x00\x00',], + (Ecu.engine, 0x7e0, None): [ + b'\x0235870000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', + b'\x0235883000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00', + ], + (Ecu.eps, 0x7a1, None): [ + b'8965B58040\x00\x00\x00\x00\x00\x00', + b'8965B58052\x00\x00\x00\x00\x00\x00', + ], + (Ecu.fwdRadar, 0x750, 0xf): [ + b'\x018821F3301200\x00\x00\x00\x00', + b'\x018821F3301400\x00\x00\x00\x00', + ], + (Ecu.fwdCamera, 0x750, 0x6d): [ + b'\x028646F58010C0\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00', + b'\x028646F5803200\x00\x00\x00\x008646G2601400\x00\x00\x00\x00', + ], }, } STEER_THRESHOLD = 100 DBC = { - CAR.RAV4H: dbc_dict('toyota_rav4_hybrid_2017_pt_generated', 'toyota_adas'), - CAR.RAV4: dbc_dict('toyota_rav4_2017_pt_generated', 'toyota_adas'), - CAR.PRIUS: dbc_dict('toyota_prius_2017_pt_generated', 'toyota_adas'), - CAR.COROLLA: dbc_dict('toyota_corolla_2017_pt_generated', 'toyota_adas'), - CAR.LEXUS_RC: dbc_dict('lexus_is_2018_pt_generated', 'toyota_adas'), - CAR.LEXUS_RX: dbc_dict('lexus_rx_350_2016_pt_generated', 'toyota_adas'), - CAR.LEXUS_RXH: dbc_dict('lexus_rx_hybrid_2017_pt_generated', 'toyota_adas'), + CAR.RAV4H: dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), + CAR.RAV4: dbc_dict('toyota_new_mc_pt_generated', 'toyota_adas'), + CAR.PRIUS: dbc_dict('toyota_nodsu_pt_generated', 'toyota_adas'), + CAR.PRIUS_V: dbc_dict('toyota_new_mc_pt_generated', 'toyota_adas'), + CAR.COROLLA: dbc_dict('toyota_new_mc_pt_generated', 'toyota_adas'), + CAR.LEXUS_RC: dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), + CAR.LEXUS_RX: dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), + CAR.LEXUS_RXH: dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), CAR.LEXUS_RX_TSS2: dbc_dict('toyota_nodsu_pt_generated', 'toyota_tss2_adas'), - CAR.LEXUS_RXH_TSS2: dbc_dict('toyota_nodsu_hybrid_pt_generated', 'toyota_tss2_adas'), + CAR.LEXUS_RXH_TSS2: dbc_dict('toyota_nodsu_pt_generated', 'toyota_tss2_adas'), CAR.CHR: dbc_dict('toyota_nodsu_pt_generated', 'toyota_adas'), - CAR.CHRH: dbc_dict('toyota_nodsu_hybrid_pt_generated', 'toyota_adas'), + CAR.CHRH: dbc_dict('toyota_nodsu_pt_generated', 'toyota_adas'), CAR.CAMRY: dbc_dict('toyota_nodsu_pt_generated', 'toyota_adas'), - CAR.CAMRYH: dbc_dict('toyota_camry_hybrid_2018_pt_generated', 'toyota_adas'), + CAR.CAMRYH: dbc_dict('toyota_nodsu_pt_generated', 'toyota_adas'), CAR.CAMRY_TSS2: dbc_dict('toyota_nodsu_pt_generated', 'toyota_tss2_adas'), - CAR.CAMRYH_TSS2: dbc_dict('toyota_nodsu_hybrid_pt_generated', 'toyota_tss2_adas'), - CAR.HIGHLANDER: dbc_dict('toyota_highlander_2017_pt_generated', 'toyota_adas'), + CAR.CAMRYH_TSS2: dbc_dict('toyota_nodsu_pt_generated', 'toyota_tss2_adas'), + CAR.HIGHLANDER: dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), CAR.HIGHLANDER_TSS2: dbc_dict('toyota_nodsu_pt_generated', 'toyota_tss2_adas'), - CAR.HIGHLANDERH: dbc_dict('toyota_highlander_hybrid_2018_pt_generated', 'toyota_adas'), - CAR.HIGHLANDERH_TSS2: dbc_dict('toyota_nodsu_hybrid_pt_generated', 'toyota_tss2_adas'), - CAR.AVALON: dbc_dict('toyota_avalon_2017_pt_generated', 'toyota_adas'), + CAR.HIGHLANDERH: dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), + CAR.HIGHLANDERH_TSS2: dbc_dict('toyota_nodsu_pt_generated', 'toyota_tss2_adas'), + CAR.AVALON: dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), CAR.AVALON_2019: dbc_dict('toyota_nodsu_pt_generated', 'toyota_adas'), - CAR.AVALONH_2019: dbc_dict('toyota_nodsu_hybrid_pt_generated', 'toyota_adas'), + CAR.AVALONH_2019: dbc_dict('toyota_nodsu_pt_generated', 'toyota_adas'), + CAR.AVALON_TSS2: dbc_dict('toyota_nodsu_pt_generated', 'toyota_tss2_adas'), CAR.RAV4_TSS2: dbc_dict('toyota_nodsu_pt_generated', 'toyota_tss2_adas'), CAR.COROLLA_TSS2: dbc_dict('toyota_nodsu_pt_generated', 'toyota_tss2_adas'), - CAR.COROLLAH_TSS2: dbc_dict('toyota_nodsu_hybrid_pt_generated', 'toyota_tss2_adas'), + CAR.COROLLAH_TSS2: dbc_dict('toyota_nodsu_pt_generated', 'toyota_tss2_adas'), CAR.LEXUS_ES_TSS2: dbc_dict('toyota_nodsu_pt_generated', 'toyota_tss2_adas'), - CAR.LEXUS_ESH_TSS2: dbc_dict('toyota_nodsu_hybrid_pt_generated', 'toyota_tss2_adas'), - CAR.LEXUS_ESH: dbc_dict('lexus_ct200h_2018_pt_generated', 'toyota_adas'), - CAR.SIENNA: dbc_dict('toyota_sienna_xle_2018_pt_generated', 'toyota_adas'), - CAR.LEXUS_IS: dbc_dict('lexus_is_2018_pt_generated', 'toyota_adas'), - CAR.LEXUS_CTH: dbc_dict('lexus_ct200h_2018_pt_generated', 'toyota_adas'), - CAR.RAV4H_TSS2: dbc_dict('toyota_nodsu_hybrid_pt_generated', 'toyota_tss2_adas'), - CAR.LEXUS_NXH: dbc_dict('lexus_nx300h_2018_pt_generated', 'toyota_adas'), - CAR.LEXUS_NX: dbc_dict('lexus_nx300_2018_pt_generated', 'toyota_adas'), + CAR.LEXUS_ESH_TSS2: dbc_dict('toyota_nodsu_pt_generated', 'toyota_tss2_adas'), + CAR.LEXUS_ESH: dbc_dict('toyota_new_mc_pt_generated', 'toyota_adas'), + CAR.SIENNA: dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), + CAR.LEXUS_IS: dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), + CAR.LEXUS_CTH: dbc_dict('toyota_new_mc_pt_generated', 'toyota_adas'), + CAR.RAV4H_TSS2: dbc_dict('toyota_nodsu_pt_generated', 'toyota_tss2_adas'), + CAR.LEXUS_NXH: dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), + CAR.LEXUS_NX: dbc_dict('toyota_tnga_k_pt_generated', 'toyota_adas'), CAR.LEXUS_NX_TSS2: dbc_dict('toyota_nodsu_pt_generated', 'toyota_tss2_adas'), - CAR.PRIUS_TSS2: dbc_dict('toyota_nodsu_hybrid_pt_generated', 'toyota_tss2_adas'), - CAR.MIRAI: dbc_dict('toyota_nodsu_hybrid_pt_generated', 'toyota_tss2_adas'), + CAR.PRIUS_TSS2: dbc_dict('toyota_nodsu_pt_generated', 'toyota_tss2_adas'), + CAR.MIRAI: dbc_dict('toyota_nodsu_pt_generated', 'toyota_tss2_adas'), CAR.ALPHARD_TSS2: dbc_dict('toyota_nodsu_pt_generated', 'toyota_tss2_adas'), } +# These cars have non-standard EPS torque scale factors. All others are 73 +EPS_SCALE = defaultdict(lambda: 73, {CAR.PRIUS: 66, CAR.COROLLA: 88, CAR.LEXUS_IS: 77, CAR.LEXUS_RC: 77, CAR.LEXUS_CTH: 100, CAR.PRIUS_V: 100}) # Toyota/Lexus Safety Sense 2.0 and 2.5 -TSS2_CAR = set([CAR.RAV4_TSS2, CAR.COROLLA_TSS2, CAR.COROLLAH_TSS2, CAR.LEXUS_ES_TSS2, CAR.LEXUS_ESH_TSS2, CAR.RAV4H_TSS2, - CAR.LEXUS_RX_TSS2, CAR.LEXUS_RXH_TSS2, CAR.HIGHLANDER_TSS2, CAR.HIGHLANDERH_TSS2, CAR.PRIUS_TSS2, CAR.CAMRY_TSS2, CAR.CAMRYH_TSS2, - CAR.MIRAI, CAR.LEXUS_NX_TSS2, CAR.ALPHARD_TSS2]) +TSS2_CAR = {CAR.RAV4_TSS2, CAR.COROLLA_TSS2, CAR.COROLLAH_TSS2, CAR.LEXUS_ES_TSS2, CAR.LEXUS_ESH_TSS2, CAR.RAV4H_TSS2, + CAR.LEXUS_RX_TSS2, CAR.LEXUS_RXH_TSS2, CAR.HIGHLANDER_TSS2, CAR.HIGHLANDERH_TSS2, CAR.PRIUS_TSS2, CAR.CAMRY_TSS2, CAR.CAMRYH_TSS2, + CAR.MIRAI, CAR.LEXUS_NX_TSS2, CAR.ALPHARD_TSS2, CAR.AVALON_TSS2} -NO_DSU_CAR = TSS2_CAR | set([CAR.CHR, CAR.CHRH, CAR.CAMRY, CAR.CAMRYH]) +NO_DSU_CAR = TSS2_CAR | {CAR.CHR, CAR.CHRH, CAR.CAMRY, CAR.CAMRYH} # no resume button press required -NO_STOP_TIMER_CAR = TSS2_CAR | set([CAR.RAV4H, CAR.HIGHLANDERH, CAR.HIGHLANDER, CAR.SIENNA, CAR.LEXUS_ESH]) +NO_STOP_TIMER_CAR = TSS2_CAR | {CAR.PRIUS_V, CAR.RAV4H, CAR.HIGHLANDERH, CAR.HIGHLANDER, CAR.SIENNA, CAR.LEXUS_ESH} diff --git a/selfdrive/car/volkswagen/carcontroller.py b/selfdrive/car/volkswagen/carcontroller.py index 977818dbd..f85a81a53 100644 --- a/selfdrive/car/volkswagen/carcontroller.py +++ b/selfdrive/car/volkswagen/carcontroller.py @@ -21,7 +21,7 @@ class CarController(): self.steer_rate_limited = False - def update(self, enabled, CS, frame, ext_bus, actuators, visual_alert, left_lane_visible, right_lane_visible, left_lane_depart, right_lane_depart): + def update(self, c, enabled, CS, frame, ext_bus, actuators, visual_alert, left_lane_visible, right_lane_visible, left_lane_depart, right_lane_depart): """ Controls thread """ can_sends = [] @@ -39,7 +39,7 @@ class CarController(): # torque value. Do that anytime we happen to have 0 torque, or failing that, # when exceeding ~1/3 the 360 second timer. - if enabled and CS.out.vEgo > CS.CP.minSteerSpeed and not (CS.out.standstill or CS.out.steerError or CS.out.steerWarning): + if c.active and CS.out.vEgo > CS.CP.minSteerSpeed and not (CS.out.standstill or CS.out.steerError or CS.out.steerWarning): new_steer = int(round(actuators.steer * P.STEER_MAX)) apply_steer = apply_std_steer_torque_limits(new_steer, self.apply_steer_last, CS.out.steeringTorque, P) self.steer_rate_limited = new_steer != apply_steer @@ -72,7 +72,7 @@ class CarController(): # **** HUD Controls ***************************************************** # if frame % P.LDW_STEP == 0: - if visual_alert in [VisualAlert.steerRequired, VisualAlert.ldw]: + if visual_alert in (VisualAlert.steerRequired, VisualAlert.ldw): hud_alert = MQB_LDW_MESSAGES["laneAssistTakeOverSilent"] else: hud_alert = MQB_LDW_MESSAGES["none"] @@ -110,4 +110,7 @@ class CarController(): self.graButtonStatesToSend = None self.graMsgSentCount = 0 - return can_sends + new_actuators = actuators.copy() + new_actuators.steer = self.apply_steer_last / P.STEER_MAX + + return new_actuators, can_sends diff --git a/selfdrive/car/volkswagen/carstate.py b/selfdrive/car/volkswagen/carstate.py index 97e3094fa..1fe8b56b9 100644 --- a/selfdrive/car/volkswagen/carstate.py +++ b/selfdrive/car/volkswagen/carstate.py @@ -33,7 +33,7 @@ class CarState(CarStateBase): # Update steering angle, rate, yaw rate, and driver input torque. VW send # the sign/direction in a separate signal so they must be recombined. - ret.steeringAngleDeg = pt_cp.vl["LH_EPS_03"]["EPS_Berechneter_LW"] * (1, -1)[int(pt_cp.vl["LH_EPS_03"]["EPS_VZ_BLW"])] + ret.steeringAngleDeg = pt_cp.vl["LWI_01"]["LWI_Lenkradwinkel"] * (1, -1)[int(pt_cp.vl["LWI_01"]["LWI_VZ_Lenkradwinkel"])] ret.steeringRateDeg = pt_cp.vl["LWI_01"]["LWI_Lenkradw_Geschw"] * (1, -1)[int(pt_cp.vl["LWI_01"]["LWI_VZ_Lenkradw_Geschw"])] ret.steeringTorque = pt_cp.vl["LH_EPS_03"]["EPS_Lenkmoment"] * (1, -1)[int(pt_cp.vl["LH_EPS_03"]["EPS_VZ_Lenkmoment"])] ret.steeringPressed = abs(ret.steeringTorque) > CarControllerParams.STEER_DRIVER_ALLOWANCE @@ -41,8 +41,8 @@ class CarState(CarStateBase): # Verify EPS readiness to accept steering commands hca_status = self.hca_status_values.get(pt_cp.vl["LH_EPS_03"]["EPS_HCA_Status"]) - ret.steerError = hca_status in ["DISABLED", "FAULT"] - ret.steerWarning = hca_status in ["INITIALIZING", "REJECTED"] + ret.steerError = hca_status in ("DISABLED", "FAULT") + ret.steerWarning = hca_status in ("INITIALIZING", "REJECTED") # Update gas, brakes, and gearshift. ret.gas = pt_cp.vl["Motor_20"]["MO_Fahrpedalrohwert_01"] / 100.0 @@ -102,7 +102,7 @@ class CarState(CarStateBase): # ACC okay and enabled, but not currently engaged ret.cruiseState.available = True ret.cruiseState.enabled = False - elif self.tsk_status in [3, 4, 5]: + elif self.tsk_status in (3, 4, 5): # ACC okay and enabled, currently regulating speed (3) or driver accel override (4) or overrun coast-down (5) ret.cruiseState.available = True ret.cruiseState.enabled = True @@ -147,50 +147,49 @@ class CarState(CarStateBase): @staticmethod def get_can_parser(CP): - # this function generates lists for signal, messages and initial values signals = [ - # sig_name, sig_address, default - ("EPS_Berechneter_LW", "LH_EPS_03", 0), # Absolute steering angle - ("EPS_VZ_BLW", "LH_EPS_03", 0), # Steering angle sign - ("LWI_Lenkradw_Geschw", "LWI_01", 0), # Absolute steering rate - ("LWI_VZ_Lenkradw_Geschw", "LWI_01", 0), # Steering rate sign - ("ESP_VL_Radgeschw_02", "ESP_19", 0), # ABS wheel speed, front left - ("ESP_VR_Radgeschw_02", "ESP_19", 0), # ABS wheel speed, front right - ("ESP_HL_Radgeschw_02", "ESP_19", 0), # ABS wheel speed, rear left - ("ESP_HR_Radgeschw_02", "ESP_19", 0), # ABS wheel speed, rear right - ("ESP_Gierrate", "ESP_02", 0), # Absolute yaw rate - ("ESP_VZ_Gierrate", "ESP_02", 0), # Yaw rate sign - ("ZV_FT_offen", "Gateway_72", 0), # Door open, driver - ("ZV_BT_offen", "Gateway_72", 0), # Door open, passenger - ("ZV_HFS_offen", "Gateway_72", 0), # Door open, rear left - ("ZV_HBFS_offen", "Gateway_72", 0), # Door open, rear right - ("ZV_HD_offen", "Gateway_72", 0), # Trunk or hatch open - ("Comfort_Signal_Left", "Blinkmodi_02", 0), # Left turn signal including comfort blink interval - ("Comfort_Signal_Right", "Blinkmodi_02", 0), # Right turn signal including comfort blink interval - ("AB_Gurtschloss_FA", "Airbag_02", 0), # Seatbelt status, driver - ("AB_Gurtschloss_BF", "Airbag_02", 0), # Seatbelt status, passenger - ("ESP_Fahrer_bremst", "ESP_05", 0), # Brake pedal pressed - ("ESP_Bremsdruck", "ESP_05", 0), # Brake pressure applied - ("MO_Fahrpedalrohwert_01", "Motor_20", 0), # Accelerator pedal value - ("EPS_Lenkmoment", "LH_EPS_03", 0), # Absolute driver torque input - ("EPS_VZ_Lenkmoment", "LH_EPS_03", 0), # Driver torque input sign - ("EPS_HCA_Status", "LH_EPS_03", 3), # EPS HCA control status - ("ESP_Tastung_passiv", "ESP_21", 0), # Stability control disabled - ("ESP_Haltebestaetigung", "ESP_21", 0), # ESP hold confirmation - ("KBI_MFA_v_Einheit_02", "Einheiten_01", 0), # MPH vs KMH speed display - ("KBI_Handbremse", "Kombi_01", 0), # Manual handbrake applied - ("TSK_Status", "TSK_06", 0), # ACC engagement status from drivetrain coordinator - ("GRA_Hauptschalter", "GRA_ACC_01", 0), # ACC button, on/off - ("GRA_Abbrechen", "GRA_ACC_01", 0), # ACC button, cancel - ("GRA_Tip_Setzen", "GRA_ACC_01", 0), # ACC button, set - ("GRA_Tip_Hoch", "GRA_ACC_01", 0), # ACC button, increase or accel - ("GRA_Tip_Runter", "GRA_ACC_01", 0), # ACC button, decrease or decel - ("GRA_Tip_Wiederaufnahme", "GRA_ACC_01", 0), # ACC button, resume - ("GRA_Verstellung_Zeitluecke", "GRA_ACC_01", 0), # ACC button, time gap adj - ("GRA_Typ_Hauptschalter", "GRA_ACC_01", 0), # ACC main button type - ("GRA_Tip_Stufe_2", "GRA_ACC_01", 0), # unknown related to stalk type - ("GRA_ButtonTypeInfo", "GRA_ACC_01", 0), # unknown related to stalk type - ("COUNTER", "GRA_ACC_01", 0), # GRA_ACC_01 CAN message counter + # sig_name, sig_address + ("LWI_Lenkradwinkel", "LWI_01"), # Absolute steering angle + ("LWI_VZ_Lenkradwinkel", "LWI_01"), # Steering angle sign + ("LWI_Lenkradw_Geschw", "LWI_01"), # Absolute steering rate + ("LWI_VZ_Lenkradw_Geschw", "LWI_01"), # Steering rate sign + ("ESP_VL_Radgeschw_02", "ESP_19"), # ABS wheel speed, front left + ("ESP_VR_Radgeschw_02", "ESP_19"), # ABS wheel speed, front right + ("ESP_HL_Radgeschw_02", "ESP_19"), # ABS wheel speed, rear left + ("ESP_HR_Radgeschw_02", "ESP_19"), # ABS wheel speed, rear right + ("ESP_Gierrate", "ESP_02"), # Absolute yaw rate + ("ESP_VZ_Gierrate", "ESP_02"), # Yaw rate sign + ("ZV_FT_offen", "Gateway_72"), # Door open, driver + ("ZV_BT_offen", "Gateway_72"), # Door open, passenger + ("ZV_HFS_offen", "Gateway_72"), # Door open, rear left + ("ZV_HBFS_offen", "Gateway_72"), # Door open, rear right + ("ZV_HD_offen", "Gateway_72"), # Trunk or hatch open + ("Comfort_Signal_Left", "Blinkmodi_02"), # Left turn signal including comfort blink interval + ("Comfort_Signal_Right", "Blinkmodi_02"), # Right turn signal including comfort blink interval + ("AB_Gurtschloss_FA", "Airbag_02"), # Seatbelt status, driver + ("AB_Gurtschloss_BF", "Airbag_02"), # Seatbelt status, passenger + ("ESP_Fahrer_bremst", "ESP_05"), # Brake pedal pressed + ("ESP_Bremsdruck", "ESP_05"), # Brake pressure applied + ("MO_Fahrpedalrohwert_01", "Motor_20"), # Accelerator pedal value + ("EPS_Lenkmoment", "LH_EPS_03"), # Absolute driver torque input + ("EPS_VZ_Lenkmoment", "LH_EPS_03"), # Driver torque input sign + ("EPS_HCA_Status", "LH_EPS_03"), # EPS HCA control status + ("ESP_Tastung_passiv", "ESP_21"), # Stability control disabled + ("ESP_Haltebestaetigung", "ESP_21"), # ESP hold confirmation + ("KBI_MFA_v_Einheit_02", "Einheiten_01"), # MPH vs KMH speed display + ("KBI_Handbremse", "Kombi_01"), # Manual handbrake applied + ("TSK_Status", "TSK_06"), # ACC engagement status from drivetrain coordinator + ("GRA_Hauptschalter", "GRA_ACC_01"), # ACC button, on/off + ("GRA_Abbrechen", "GRA_ACC_01"), # ACC button, cancel + ("GRA_Tip_Setzen", "GRA_ACC_01"), # ACC button, set + ("GRA_Tip_Hoch", "GRA_ACC_01"), # ACC button, increase or accel + ("GRA_Tip_Runter", "GRA_ACC_01"), # ACC button, decrease or decel + ("GRA_Tip_Wiederaufnahme", "GRA_ACC_01"), # ACC button, resume + ("GRA_Verstellung_Zeitluecke", "GRA_ACC_01"), # ACC button, time gap adj + ("GRA_Typ_Hauptschalter", "GRA_ACC_01"), # ACC main button type + ("GRA_Tip_Stufe_2", "GRA_ACC_01"), # unknown related to stalk type + ("GRA_ButtonTypeInfo", "GRA_ACC_01"), # unknown related to stalk type + ("COUNTER", "GRA_ACC_01"), # GRA_ACC_01 CAN message counter ] checks = [ @@ -212,15 +211,15 @@ class CarState(CarStateBase): ] if CP.transmissionType == TransmissionType.automatic: - signals += [("GE_Fahrstufe", "Getriebe_11", 0)] # Auto trans gear selector position - checks += [("Getriebe_11", 20)] # From J743 Auto transmission control module + signals.append(("GE_Fahrstufe", "Getriebe_11")) # Auto trans gear selector position + checks.append(("Getriebe_11", 20)) # From J743 Auto transmission control module elif CP.transmissionType == TransmissionType.direct: - signals += [("GearPosition", "EV_Gearshift", 0)] # EV gear selector position - checks += [("EV_Gearshift", 10)] # From J??? unknown EV control module + signals.append(("GearPosition", "EV_Gearshift")) # EV gear selector position + checks.append(("EV_Gearshift", 10)) # From J??? unknown EV control module elif CP.transmissionType == TransmissionType.manual: - signals += [("MO_Kuppl_schalter", "Motor_14", 0), # Clutch switch - ("BCM1_Rueckfahrlicht_Schalter", "Gateway_72", 0)] # Reverse light from BCM - checks += [("Motor_14", 10)] # From J623 Engine control module + signals += [("MO_Kuppl_schalter", "Motor_14"), # Clutch switch + ("BCM1_Rueckfahrlicht_Schalter", "Gateway_72")] # Reverse light from BCM + checks.append(("Motor_14", 10)) # From J623 Engine control module if CP.networkLocation == NetworkLocation.fwdCamera: # Radars are here on CANBUS.pt @@ -234,18 +233,17 @@ class CarState(CarStateBase): @staticmethod def get_cam_can_parser(CP): - signals = [] checks = [] if CP.networkLocation == NetworkLocation.fwdCamera: signals += [ - # sig_name, sig_address, default - ("LDW_SW_Warnung_links", "LDW_02", 0), # Blind spot in warning mode on left side due to lane departure - ("LDW_SW_Warnung_rechts", "LDW_02", 0), # Blind spot in warning mode on right side due to lane departure - ("LDW_Seite_DLCTLC", "LDW_02", 0), # Direction of most likely lane departure (left or right) - ("LDW_DLC", "LDW_02", 0), # Lane departure, distance to line crossing - ("LDW_TLC", "LDW_02", 0), # Lane departure, time to line crossing + # sig_name, sig_address + ("LDW_SW_Warnung_links", "LDW_02"), # Blind spot in warning mode on left side due to lane departure + ("LDW_SW_Warnung_rechts", "LDW_02"), # Blind spot in warning mode on right side due to lane departure + ("LDW_Seite_DLCTLC", "LDW_02"), # Direction of most likely lane departure (left or right) + ("LDW_DLC", "LDW_02"), # Lane departure, distance to line crossing + ("LDW_TLC", "LDW_02"), # Lane departure, time to line crossing ] checks += [ # sig_address, frequency @@ -264,20 +262,20 @@ class CarState(CarStateBase): class MqbExtraSignals: # Additional signal and message lists for optional or bus-portable controllers fwd_radar_signals = [ - ("ACC_Wunschgeschw", "ACC_02", 0), # ACC set speed - ("AWV2_Freigabe", "ACC_10", 0), # FCW brake jerk release - ("ANB_Teilbremsung_Freigabe", "ACC_10", 0), # AEB partial braking release - ("ANB_Zielbremsung_Freigabe", "ACC_10", 0), # AEB target braking release + ("ACC_Wunschgeschw", "ACC_02"), # ACC set speed + ("AWV2_Freigabe", "ACC_10"), # FCW brake jerk release + ("ANB_Teilbremsung_Freigabe", "ACC_10"), # AEB partial braking release + ("ANB_Zielbremsung_Freigabe", "ACC_10"), # AEB target braking release ] fwd_radar_checks = [ ("ACC_10", 50), # From J428 ACC radar control module ("ACC_02", 17), # From J428 ACC radar control module ] bsm_radar_signals = [ - ("SWA_Infostufe_SWA_li", "SWA_01", 0), # Blind spot object info, left - ("SWA_Warnung_SWA_li", "SWA_01", 0), # Blind spot object warning, left - ("SWA_Infostufe_SWA_re", "SWA_01", 0), # Blind spot object info, right - ("SWA_Warnung_SWA_re", "SWA_01", 0), # Blind spot object warning, right + ("SWA_Infostufe_SWA_li", "SWA_01"), # Blind spot object info, left + ("SWA_Warnung_SWA_li", "SWA_01"), # Blind spot object warning, left + ("SWA_Infostufe_SWA_re", "SWA_01"), # Blind spot object info, right + ("SWA_Warnung_SWA_re", "SWA_01"), # Blind spot object warning, right ] bsm_radar_checks = [ ("SWA_01", 20), # From J1086 Lane Change Assist diff --git a/selfdrive/car/volkswagen/interface.py b/selfdrive/car/volkswagen/interface.py index 560e64ce2..961cfed7f 100644 --- a/selfdrive/car/volkswagen/interface.py +++ b/selfdrive/car/volkswagen/interface.py @@ -38,14 +38,14 @@ class CarInterface(CarInterfaceBase): else: ret.transmissionType = TransmissionType.manual - if any(msg in fingerprint[1] for msg in [0x40, 0x86, 0xB2, 0xFD]): # Airbag_01, LWI_01, ESP_19, ESP_21 + if any(msg in fingerprint[1] for msg in (0x40, 0x86, 0xB2, 0xFD)): # Airbag_01, LWI_01, ESP_19, ESP_21 ret.networkLocation = NetworkLocation.gateway else: ret.networkLocation = NetworkLocation.fwdCamera # Global lateral tuning defaults, can be overridden per-vehicle - ret.steerActuatorDelay = 0.05 + ret.steerActuatorDelay = 0.1 ret.steerRateCost = 1.0 ret.steerLimitTimer = 0.4 ret.steerRatio = 15.6 # Let the params learner figure this out @@ -152,7 +152,7 @@ class CarInterface(CarInterfaceBase): ret.wheelbase = 2.84 else: - raise ValueError("unsupported car %s" % candidate) + raise ValueError(f"unsupported car {candidate}") ret.rotationalInertia = scale_rot_inertia(ret.mass, ret.wheelbase) ret.centerToFront = ret.wheelbase * 0.45 @@ -174,12 +174,6 @@ class CarInterface(CarInterfaceBase): ret.canValid = self.cp.can_valid and self.cp_cam.can_valid ret.steeringRateLimited = self.CC.steer_rate_limited if self.CC is not None else False - # TODO: add a field for this to carState, car interface code shouldn't write params - # Update the device metric configuration to match the car at first startup, - # or if there's been a change. - #if self.CS.displayMetricUnits != self.displayMetricUnitsPrev: - # put_nonblocking("IsMetric", "1" if self.CS.displayMetricUnits else "0") - # Check for and process state-change events (button press or release) from # the turn stalk switch or ACC steering wheel/control stalk buttons. for button in self.CS.buttonStates: @@ -194,7 +188,7 @@ class CarInterface(CarInterfaceBase): # Vehicle health and operation safety checks if self.CS.parkingBrakeSet: events.add(EventName.parkBrake) - if self.CS.tsk_status in [6, 7]: + if self.CS.tsk_status in (6, 7): events.add(EventName.accFaulted) # Low speed steer alert hysteresis logic @@ -216,11 +210,12 @@ class CarInterface(CarInterfaceBase): return self.CS.out def apply(self, c): - can_sends = self.CC.update(c.enabled, self.CS, self.frame, self.ext_bus, c.actuators, - c.hudControl.visualAlert, - c.hudControl.leftLaneVisible, - c.hudControl.rightLaneVisible, - c.hudControl.leftLaneDepart, - c.hudControl.rightLaneDepart) + hud_control = c.hudControl + ret = self.CC.update(c, c.enabled, self.CS, self.frame, self.ext_bus, c.actuators, + hud_control.visualAlert, + hud_control.leftLaneVisible, + hud_control.rightLaneVisible, + hud_control.leftLaneDepart, + hud_control.rightLaneDepart) self.frame += 1 - return can_sends + return ret diff --git a/selfdrive/car/volkswagen/values.py b/selfdrive/car/volkswagen/values.py index 822326acd..241338c2c 100755 --- a/selfdrive/car/volkswagen/values.py +++ b/selfdrive/car/volkswagen/values.py @@ -1,5 +1,3 @@ -# flake8: noqa - from collections import defaultdict from typing import Dict @@ -101,24 +99,30 @@ class CAR: FW_VERSIONS = { CAR.ARTEON_MK1: { (Ecu.engine, 0x7e0, None): [ + b'\xf1\x873G0906259F \xf1\x890004', b'\xf1\x873G0906259P \xf1\x890001', ], (Ecu.transmission, 0x7e1, None): [ b'\xf1\x8709G927158L \xf1\x893611', + b'\xf1\x870GC300011L \xf1\x891401', ], (Ecu.srs, 0x715, None): [ + b'\xf1\x873Q0959655BK\xf1\x890703\xf1\x82\x0e1616001613121177161113772900', b'\xf1\x873Q0959655DL\xf1\x890732\xf1\x82\0161812141812171105141123052J00', ], (Ecu.eps, 0x712, None): [ + b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571B41815A1', b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\00567B0020800', ], (Ecu.fwdRadar, 0x757, None): [ b'\xf1\x872Q0907572T \xf1\x890383', + b'\xf1\x875Q0907572J \xf1\x890654', ], }, CAR.ATLAS_MK1: { (Ecu.engine, 0x7e0, None): [ b'\xf1\x8703H906026AA\xf1\x899970', + b'\xf1\x8703H906026AT\xf1\x891922', b'\xf1\x8703H906026F \xf1\x896696', b'\xf1\x8703H906026F \xf1\x899970', b'\xf1\x8703H906026J \xf1\x896026', @@ -129,17 +133,21 @@ FW_VERSIONS = { (Ecu.transmission, 0x7e1, None): [ b'\xf1\x8709G927158A \xf1\x893387', b'\xf1\x8709G927158DR\xf1\x893536', + b'\xf1\x8709G927158FT\xf1\x893835', ], (Ecu.srs, 0x715, None): [ b'\xf1\x873Q0959655BC\xf1\x890503\xf1\x82\0161914151912001103111122031200', b'\xf1\x873Q0959655BN\xf1\x890713\xf1\x82\0162214152212001105141122052900', b'\xf1\x873Q0959655DB\xf1\x890720\xf1\x82\0162214152212001105141122052900', + b'\xf1\x873Q0959655DM\xf1\x890732\xf1\x82\x0e1114151112001105161122052J00', ], (Ecu.eps, 0x712, None): [ b'\xf1\x873QF909144B \xf1\x891582\xf1\x82\00571B60924A1', + b'\xf1\x873QF909144B \xf1\x891582\xf1\x82\x0571B6G920A1', b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820528B6090105', ], (Ecu.fwdRadar, 0x757, None): [ + b'\xf1\x872Q0907572T \xf1\x890383', b'\xf1\x875Q0907572H \xf1\x890620', b'\xf1\x875Q0907572J \xf1\x890654', b'\xf1\x875Q0907572P \xf1\x890682', @@ -157,6 +165,7 @@ FW_VERSIONS = { b'\xf1\x8704E906027HD\xf1\x893742', b'\xf1\x8704E906027MA\xf1\x894958', b'\xf1\x8704L906021DT\xf1\x895520', + b'\xf1\x8704L906021DT\xf1\x898127', b'\xf1\x8704L906021N \xf1\x895518', b'\xf1\x8704L906026BP\xf1\x897608', b'\xf1\x8704L906026NF\xf1\x899528', @@ -203,6 +212,7 @@ FW_VERSIONS = { b'\xf1\x870D9300040A \xf1\x893613', b'\xf1\x870D9300040S \xf1\x894311', b'\xf1\x870D9300041H \xf1\x895220', + b'\xf1\x870D9300041P \xf1\x894507', b'\xf1\x870DD300045K \xf1\x891120', b'\xf1\x870DD300046F \xf1\x891601', b'\xf1\x870GC300012A \xf1\x891403', @@ -292,6 +302,7 @@ FW_VERSIONS = { b'\xf1\x8704E906024AK\xf1\x899937', b'\xf1\x8704E906024AS\xf1\x899912', b'\xf1\x8704E906024B \xf1\x895594', + b'\xf1\x8704E906024C \xf1\x899970', b'\xf1\x8704E906024L \xf1\x895595', b'\xf1\x8704E906024L \xf1\x899970', b'\xf1\x8704E906027MS\xf1\x896223', @@ -306,6 +317,7 @@ FW_VERSIONS = { ], (Ecu.srs, 0x715, None): [ b'\xf1\x875Q0959655AG\xf1\x890336\xf1\x82\02314171231313500314611011630169333463100', + b'\xf1\x875Q0959655AG\xf1\x890338\xf1\x82\x1314171231313500314611011630169333463100', b'\xf1\x875Q0959655BM\xf1\x890403\xf1\x82\02314171231313500314642011650169333463100', b'\xf1\x875Q0959655BM\xf1\x890403\xf1\x82\02314171231313500314643011650169333463100', b'\xf1\x875Q0959655BR\xf1\x890403\xf1\x82\02311170031313300314240011150119333433100', @@ -322,6 +334,7 @@ FW_VERSIONS = { ], (Ecu.fwdRadar, 0x757, None): [ b'\xf1\x875Q0907572N \xf1\x890681', + b'\xf1\x875Q0907572P \xf1\x890682', b'\xf1\x875Q0907572R \xf1\x890771', ], }, @@ -458,13 +471,16 @@ FW_VERSIONS = { }, CAR.TRANSPORTER_T61: { (Ecu.engine, 0x7e0, None): [ + b'\xf1\x8704L906057AP\xf1\x891186', b'\xf1\x8704L906057N \xf1\x890413', ], (Ecu.transmission, 0x7e1, None): [ b'\xf1\x870BT300012G \xf1\x893102', + b'\xf1\x870BT300012E \xf1\x893105', ], (Ecu.srs, 0x715, None): [ b'\xf1\x872Q0959655AE\xf1\x890506\xf1\x82\02316170411110411--04041704161611152S1411', + b'\xf1\x872Q0959655AF\xf1\x890506\xf1\x82\x1316171111110411--04041711121211152S1413', ], (Ecu.eps, 0x712, None): [ b'\xf1\x877LA909144F \xf1\x897150\xf1\x82\005323A5519A2', @@ -741,6 +757,7 @@ FW_VERSIONS = { (Ecu.engine, 0x7e0, None): [ b'\xf1\x8704L906026FP\xf1\x891196', b'\xf1\x8704L906026KB\xf1\x894071', + b'\xf1\x8704L906026KD\xf1\x894798', b'\xf1\x873G0906259B \xf1\x890002', b'\xf1\x873G0906264A \xf1\x890002', ], @@ -748,6 +765,7 @@ FW_VERSIONS = { b'\xf1\x870CW300042H \xf1\x891601', b'\xf1\x870D9300011T \xf1\x894801', b'\xf1\x870D9300012 \xf1\x894940', + b'\xf1\x870GC300043 \xf1\x892301', ], (Ecu.srs, 0x715, None): [ b'\xf1\x875Q0959655AE\xf1\x890130\xf1\x82\022111200111121001121118112231292221111', @@ -759,6 +777,7 @@ FW_VERSIONS = { b'\xf1\x875Q0909143M \xf1\x892041\xf1\x820522UZ070303', b'\xf1\x875Q0910143B \xf1\x892201\xf1\x82\00563UZ060700', b'\xf1\x875Q0910143B \xf1\x892201\xf1\x82\x0563UZ060600', + b'\xf1\x875Q0910143C \xf1\x892211\xf1\x82\x0567UZ070600', ], (Ecu.fwdRadar, 0x757, None): [ b'\xf1\x873Q0907572B \xf1\x890192', diff --git a/selfdrive/common/SConscript b/selfdrive/common/SConscript index 9b496fef7..8dfeecbdd 100644 --- a/selfdrive/common/SConscript +++ b/selfdrive/common/SConscript @@ -7,6 +7,7 @@ else: common_libs = [ 'params.cc', + 'statlog.cc', 'swaglog.cc', 'util.cc', 'gpio.cc', @@ -33,3 +34,4 @@ Export('_common', '_gpucommon', '_gpu_libs') if GetOption('test'): env.Program('tests/test_util', ['tests/test_util.cc'], LIBS=[_common]) + env.Program('tests/test_swaglog', ['tests/test_swaglog.cc'], LIBS=[_common, 'json11', 'zmq', 'pthread']) diff --git a/selfdrive/common/clutil.cc b/selfdrive/common/clutil.cc index 313978525..4e952a2a8 100644 --- a/selfdrive/common/clutil.cc +++ b/selfdrive/common/clutil.cc @@ -49,7 +49,7 @@ void cl_print_build_errors(cl_program program, cl_device_id device) { std::string log(log_size, '\0'); clGetProgramBuildInfo(program, device, CL_PROGRAM_BUILD_LOG, log_size, &log[0], NULL); - std::cout << "build failed; status=" << status << ", log:" << std::endl << log << std::endl; + std::cout << "build failed; status=" << status << ", log:" << std::endl << log << std::endl; } } // namespace diff --git a/selfdrive/common/modeldata.h b/selfdrive/common/modeldata.h index 9a9414cfa..8d91f7be1 100644 --- a/selfdrive/common/modeldata.h +++ b/selfdrive/common/modeldata.h @@ -10,33 +10,19 @@ const int LON_MPC_N = 32; const float MIN_DRAW_DISTANCE = 10.0; const float MAX_DRAW_DISTANCE = 100.0; -template -const std::array convert_array_to_type(const std::array &src) { - std::array dst = {}; - for (int i=0; i +constexpr std::array build_idxs(float max_val) { + std::array result{}; + for (int i = 0; i < size; ++i) { + result[i] = max_val * ((i / (double)(size - 1)) * (i / (double)(size - 1))); } - return dst; + return result; } -const std::array T_IDXS = { - 0. , 0.00976562, 0.0390625 , 0.08789062, 0.15625 , - 0.24414062, 0.3515625 , 0.47851562, 0.625 , 0.79101562, - 0.9765625 , 1.18164062, 1.40625 , 1.65039062, 1.9140625 , - 2.19726562, 2.5 , 2.82226562, 3.1640625 , 3.52539062, - 3.90625 , 4.30664062, 4.7265625 , 5.16601562, 5.625 , - 6.10351562, 6.6015625 , 7.11914062, 7.65625 , 8.21289062, - 8.7890625 , 9.38476562, 10.}; -const auto T_IDXS_FLOAT = convert_array_to_type(T_IDXS); - -const std::array X_IDXS = { - 0. , 0.1875, 0.75 , 1.6875, 3. , 4.6875, - 6.75 , 9.1875, 12. , 15.1875, 18.75 , 22.6875, - 27. , 31.6875, 36.75 , 42.1875, 48. , 54.1875, - 60.75 , 67.6875, 75. , 82.6875, 90.75 , 99.1875, - 108. , 117.1875, 126.75 , 136.6875, 147. , 157.6875, - 168.75 , 180.1875, 192.}; -const auto X_IDXS_FLOAT = convert_array_to_type(X_IDXS); +constexpr auto T_IDXS = build_idxs(10.0); +constexpr auto T_IDXS_FLOAT = build_idxs(10.0); +constexpr auto X_IDXS = build_idxs(192.0); +constexpr auto X_IDXS_FLOAT = build_idxs(192.0); const int TICI_CAM_WIDTH = 1928; diff --git a/selfdrive/common/params.cc b/selfdrive/common/params.cc index a405d2160..3f64f790c 100644 --- a/selfdrive/common/params.cc +++ b/selfdrive/common/params.cc @@ -85,15 +85,14 @@ private: std::unordered_map keys = { {"AccessToken", CLEAR_ON_MANAGER_START | DONT_LOG}, {"AthenadPid", PERSISTENT}, - {"BootedOnroad", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_OFF}, + {"AthenadUploadQueue", PERSISTENT}, {"CalibrationParams", PERSISTENT}, {"CarBatteryCapacity", PERSISTENT}, - {"CarParams", CLEAR_ON_MANAGER_START | CLEAR_ON_PANDA_DISCONNECT | CLEAR_ON_IGNITION_ON}, - {"CarParamsCache", CLEAR_ON_MANAGER_START | CLEAR_ON_PANDA_DISCONNECT}, - {"CarVin", CLEAR_ON_MANAGER_START | CLEAR_ON_PANDA_DISCONNECT | CLEAR_ON_IGNITION_ON}, - {"CommunityFeaturesToggle", PERSISTENT}, + {"CarParams", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_ON}, + {"CarParamsCache", CLEAR_ON_MANAGER_START}, + {"CarVin", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_ON}, {"CompletedTrainingVersion", PERSISTENT}, - {"ControlsReady", CLEAR_ON_MANAGER_START | CLEAR_ON_PANDA_DISCONNECT | CLEAR_ON_IGNITION_ON}, + {"ControlsReady", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_ON}, {"CurrentRoute", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_ON}, {"DisablePowerDown", PERSISTENT}, {"DisableRadar_Allow", PERSISTENT}, @@ -116,10 +115,10 @@ std::unordered_map keys = { {"GsmRoaming", PERSISTENT}, {"HardwareSerial", PERSISTENT}, {"HasAcceptedTerms", PERSISTENT}, - {"HasPrime", PERSISTENT}, {"IMEI", PERSISTENT}, {"InstallDate", PERSISTENT}, {"IsDriverViewEnabled", CLEAR_ON_MANAGER_START}, + {"IsEngaged", PERSISTENT}, {"IsLdwEnabled", PERSISTENT}, {"IsMetric", PERSISTENT}, {"IsOffroad", CLEAR_ON_MANAGER_START}, @@ -130,7 +129,10 @@ std::unordered_map keys = { {"JoystickDebugMode", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_OFF}, {"LastAthenaPingTime", CLEAR_ON_MANAGER_START}, {"LastGPSPosition", PERSISTENT}, + {"LastManagerExitReason", CLEAR_ON_MANAGER_START}, + {"LastPeripheralPandaType", PERSISTENT}, {"LastPowerDropDetected", CLEAR_ON_MANAGER_START}, + {"LastSystemShutdown", CLEAR_ON_MANAGER_START}, {"LastUpdateException", PERSISTENT}, {"LastUpdateTime", PERSISTENT}, {"LiveParameters", PERSISTENT}, @@ -139,8 +141,10 @@ std::unordered_map keys = { {"NavdRender", PERSISTENT}, {"OpenpilotEnabledToggle", PERSISTENT}, {"PandaHeartbeatLost", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_OFF}, + {"PandaSignatures", CLEAR_ON_MANAGER_START}, {"Passive", PERSISTENT}, {"PrimeRedirected", PERSISTENT}, + {"PrimeType", PERSISTENT}, {"RecordFront", PERSISTENT}, {"RecordFrontLock", PERSISTENT}, // for the internal fleet {"ReleaseNotes", PERSISTENT}, @@ -160,7 +164,7 @@ std::unordered_map keys = { {"ApiCache_NavDestinations", PERSISTENT}, {"ApiCache_Owner", PERSISTENT}, {"Offroad_CarUnrecognized", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_ON}, - {"Offroad_ChargeDisabled", CLEAR_ON_MANAGER_START | CLEAR_ON_PANDA_DISCONNECT}, + {"Offroad_ChargeDisabled", CLEAR_ON_MANAGER_START }, {"Offroad_ConnectivityNeeded", CLEAR_ON_MANAGER_START}, {"Offroad_ConnectivityNeededPrompt", CLEAR_ON_MANAGER_START}, {"Offroad_InvalidTime", CLEAR_ON_MANAGER_START}, diff --git a/selfdrive/common/params.h b/selfdrive/common/params.h index c4bdde001..be09c63d5 100644 --- a/selfdrive/common/params.h +++ b/selfdrive/common/params.h @@ -6,10 +6,9 @@ enum ParamKeyType { PERSISTENT = 0x02, CLEAR_ON_MANAGER_START = 0x04, - CLEAR_ON_PANDA_DISCONNECT = 0x08, - CLEAR_ON_IGNITION_ON = 0x10, - CLEAR_ON_IGNITION_OFF = 0x20, - DONT_LOG = 0x40, + CLEAR_ON_IGNITION_ON = 0x08, + CLEAR_ON_IGNITION_OFF = 0x10, + DONT_LOG = 0x20, ALL = 0xFFFFFFFF }; diff --git a/selfdrive/common/statlog.cc b/selfdrive/common/statlog.cc new file mode 100644 index 000000000..27dfc2ca9 --- /dev/null +++ b/selfdrive/common/statlog.cc @@ -0,0 +1,43 @@ +#ifndef _GNU_SOURCE +#define _GNU_SOURCE +#endif + +#include "selfdrive/common/statlog.h" +#include "selfdrive/common/util.h" + +#include +#include +#include + +class StatlogState : public LogState { + public: + StatlogState() : LogState("ipc:///tmp/stats") {} +}; + +static StatlogState s = {}; + +static void log(const char* metric_type, const char* metric, const char* fmt, ...) { + char* value_buf = nullptr; + va_list args; + va_start(args, fmt); + int ret = vasprintf(&value_buf, fmt, args); + va_end(args); + + if (ret > 0 && value_buf) { + char* line_buf = nullptr; + ret = asprintf(&line_buf, "%s:%s|%s", metric, value_buf, metric_type); + if (ret > 0 && line_buf) { + zmq_send(s.sock, line_buf, ret, ZMQ_NOBLOCK); + free(line_buf); + } + free(value_buf); + } +} + +void statlog_log(const char* metric_type, const char* metric, int value) { + log(metric_type, metric, "%d", value); +} + +void statlog_log(const char* metric_type, const char* metric, float value) { + log(metric_type, metric, "%f", value); +} diff --git a/selfdrive/common/statlog.h b/selfdrive/common/statlog.h new file mode 100644 index 000000000..5d223bb66 --- /dev/null +++ b/selfdrive/common/statlog.h @@ -0,0 +1,10 @@ +#pragma once + +#define STATLOG_GAUGE "g" +#define STATLOG_SAMPLE "sa" + +void statlog_log(const char* metric_type, const char* metric, int value); +void statlog_log(const char* metric_type, const char* metric, float value); + +#define statlog_gauge(metric, value) statlog_log(STATLOG_GAUGE, metric, value) +#define statlog_sample(metric, value) statlog_log(STATLOG_SAMPLE, metric, value) diff --git a/selfdrive/common/swaglog.cc b/selfdrive/common/swaglog.cc index 74488e220..1fe700415 100644 --- a/selfdrive/common/swaglog.cc +++ b/selfdrive/common/swaglog.cc @@ -16,75 +16,55 @@ #include "selfdrive/common/version.h" #include "selfdrive/hardware/hw.h" -class LogState { +class SwaglogState : public LogState { public: - LogState() = default; - ~LogState(); - std::mutex lock; - bool inited; + SwaglogState() : LogState("ipc:///tmp/logmessage") {} + + bool initialized = false; json11::Json::object ctx_j; - void *zctx; - void *sock; - int print_level; + + inline void initialize() { + ctx_j = json11::Json::object {}; + print_level = CLOUDLOG_WARNING; + const char* print_lvl = getenv("LOGPRINT"); + if (print_lvl) { + if (strcmp(print_lvl, "debug") == 0) { + print_level = CLOUDLOG_DEBUG; + } else if (strcmp(print_lvl, "info") == 0) { + print_level = CLOUDLOG_INFO; + } else if (strcmp(print_lvl, "warning") == 0) { + print_level = CLOUDLOG_WARNING; + } + } + + // openpilot bindings + char* dongle_id = getenv("DONGLE_ID"); + if (dongle_id) { + ctx_j["dongle_id"] = dongle_id; + } + char* daemon_name = getenv("MANAGER_DAEMON"); + if (daemon_name) { + ctx_j["daemon"] = daemon_name; + } + ctx_j["version"] = COMMA_VERSION; + ctx_j["dirty"] = !getenv("CLEAN"); + + // device type + if (Hardware::EON()) { + ctx_j["device"] = "eon"; + } else if (Hardware::TICI()) { + ctx_j["device"] = "tici"; + } else { + ctx_j["device"] = "pc"; + } + + initialized = true; + } }; -LogState::~LogState() { - zmq_close(sock); - zmq_ctx_destroy(zctx); -} +static SwaglogState s = {}; -static LogState s = {}; - -static void cloudlog_bind_locked(const char* k, const char* v) { - s.ctx_j[k] = v; -} - -static void cloudlog_init() { - if (s.inited) return; - s.ctx_j = json11::Json::object {}; - s.zctx = zmq_ctx_new(); - s.sock = zmq_socket(s.zctx, ZMQ_PUSH); - - int timeout = 100; // 100 ms timeout on shutdown for messages to be received by logmessaged - zmq_setsockopt(s.sock, ZMQ_LINGER, &timeout, sizeof(timeout)); - - zmq_connect(s.sock, "ipc:///tmp/logmessage"); - - s.print_level = CLOUDLOG_WARNING; - const char* print_level = getenv("LOGPRINT"); - if (print_level) { - if (strcmp(print_level, "debug") == 0) { - s.print_level = CLOUDLOG_DEBUG; - } else if (strcmp(print_level, "info") == 0) { - s.print_level = CLOUDLOG_INFO; - } else if (strcmp(print_level, "warning") == 0) { - s.print_level = CLOUDLOG_WARNING; - } - } - - // openpilot bindings - char* dongle_id = getenv("DONGLE_ID"); - if (dongle_id) { - cloudlog_bind_locked("dongle_id", dongle_id); - } - cloudlog_bind_locked("version", COMMA_VERSION); - s.ctx_j["dirty"] = !getenv("CLEAN"); - - // device type - if (Hardware::EON()) { - cloudlog_bind_locked("device", "eon"); - } else if (Hardware::TICI()) { - cloudlog_bind_locked("device", "tici"); - } else { - cloudlog_bind_locked("device", "pc"); - } - - s.inited = true; -} - -void log(int levelnum, const char* filename, int lineno, const char* func, const char* msg, const std::string& log_s) { - std::lock_guard lk(s.lock); - cloudlog_init(); +static void log(int levelnum, const char* filename, int lineno, const char* func, const char* msg, const std::string& log_s) { if (levelnum >= s.print_level) { printf("%s: %s\n", filename, msg); } @@ -97,10 +77,14 @@ void cloudlog_e(int levelnum, const char* filename, int lineno, const char* func char* msg_buf = nullptr; va_list args; va_start(args, fmt); - vasprintf(&msg_buf, fmt, args); + int ret = vasprintf(&msg_buf, fmt, args); va_end(args); - if (!msg_buf) return; + if (ret <= 0 || !msg_buf) return; + + std::lock_guard lk(s.lock); + + if (!s.initialized) s.initialize(); json11::Json log_j = json11::Json::object { {"msg", msg_buf}, @@ -115,9 +99,3 @@ void cloudlog_e(int levelnum, const char* filename, int lineno, const char* func log(levelnum, filename, lineno, func, msg_buf, log_s); free(msg_buf); } - -void cloudlog_bind(const char* k, const char* v) { - std::lock_guard lk(s.lock); - cloudlog_init(); - cloudlog_bind_locked(k, v); -} diff --git a/selfdrive/common/swaglog.h b/selfdrive/common/swaglog.h index 9a1d3c0a6..6403820ac 100644 --- a/selfdrive/common/swaglog.h +++ b/selfdrive/common/swaglog.h @@ -8,11 +8,11 @@ #define CLOUDLOG_ERROR 40 #define CLOUDLOG_CRITICAL 50 + + void cloudlog_e(int levelnum, const char* filename, int lineno, const char* func, const char* fmt, ...) /*__attribute__ ((format (printf, 6, 7)))*/; -void cloudlog_bind(const char* k, const char* v); - #define cloudlog(lvl, fmt, ...) cloudlog_e(lvl, __FILE__, __LINE__, \ __func__, \ fmt, ## __VA_ARGS__) diff --git a/selfdrive/common/util.h b/selfdrive/common/util.h index 9a6a4d9bd..bf0df3bca 100644 --- a/selfdrive/common/util.h +++ b/selfdrive/common/util.h @@ -3,6 +3,7 @@ #include #include #include +#include #include #include @@ -11,6 +12,7 @@ #include #include #include +#include #include #include #include @@ -91,7 +93,9 @@ bool create_directories(const std::string &dir, mode_t mode); std::string check_output(const std::string& command); inline void sleep_for(const int milliseconds) { - std::this_thread::sleep_for(std::chrono::milliseconds(milliseconds)); + if (milliseconds > 0) { + std::this_thread::sleep_for(std::chrono::milliseconds(milliseconds)); + } } } // namespace util @@ -161,3 +165,26 @@ void update_max_atomic(std::atomic& max, T const& value) { T prev = max; while(prev < value && !max.compare_exchange_weak(prev, value)) {} } + +class LogState { + public: + std::mutex lock; + void *zctx; + void *sock; + int print_level; + + LogState(const char* endpoint) { + zctx = zmq_ctx_new(); + sock = zmq_socket(zctx, ZMQ_PUSH); + + // Timeout on shutdown for messages to be received by the logging process + int timeout = 100; + zmq_setsockopt(sock, ZMQ_LINGER, &timeout, sizeof(timeout)); + + zmq_connect(sock, endpoint); + }; + ~LogState() { + zmq_close(sock); + zmq_ctx_destroy(zctx); + } +}; diff --git a/selfdrive/common/version.h b/selfdrive/common/version.h index aa786903c..f1f7df9ba 100644 --- a/selfdrive/common/version.h +++ b/selfdrive/common/version.h @@ -1 +1 @@ -#define COMMA_VERSION "0.8.12" +#define COMMA_VERSION "0.8.13" diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 19fe328db..f9260762e 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -31,14 +31,13 @@ from selfdrive.manager.process_config import managed_processes SOFT_DISABLE_TIME = 3 # seconds LDW_MIN_SPEED = 31 * CV.MPH_TO_MS LANE_DEPARTURE_THRESHOLD = 0.1 -STEER_ANGLE_SATURATION_TIMEOUT = 1.0 / DT_CTRL -STEER_ANGLE_SATURATION_THRESHOLD = 2.5 # Degrees REPLAY = "REPLAY" in os.environ SIMULATION = "SIMULATION" in os.environ NOSENSOR = "NOSENSOR" in os.environ IGNORE_PROCESSES = {"rtshield", "uploader", "deleter", "loggerd", "logmessaged", "tombstoned", - "logcatd", "proclogd", "clocksd", "updated", "timezoned", "manage_athenad"} | \ + "logcatd", "proclogd", "clocksd", "updated", "timezoned", "manage_athenad", + "statsd", "shutdownd"} | \ {k for k, v in managed_processes.items() if not v.enabled} ACTUATOR_FIELDS = set(car.CarControl.Actuators.schema.fields.keys()) @@ -54,7 +53,7 @@ ButtonEvent = car.CarState.ButtonEvent SafetyModel = car.CarParams.SafetyModel IGNORED_SAFETY_MODES = [SafetyModel.silent, SafetyModel.noOutput] - +CSID_MAP = {"0": EventName.roadCameraError, "1": EventName.wideRoadCameraError, "2": EventName.driverCameraError} class Controls: def __init__(self, sm=None, pm=None, can_sock=None): @@ -99,7 +98,6 @@ class Controls: # read params self.is_metric = params.get_bool("IsMetric") self.is_ldw_enabled = params.get_bool("IsLdwEnabled") - community_feature_toggle = params.get_bool("CommunityFeaturesToggle") openpilot_enabled_toggle = params.get_bool("OpenpilotEnabledToggle") passive = params.get_bool("Passive") or not openpilot_enabled_toggle @@ -109,11 +107,7 @@ class Controls: car_recognized = self.CP.carName != 'mock' controller_available = self.CI.CC is not None and not passive and not self.CP.dashcamOnly - community_feature = self.CP.communityFeature or \ - self.CP.fingerprintSource == car.CarParams.FingerprintSource.can - community_feature_disallowed = community_feature and (not community_feature_toggle) - self.read_only = not car_recognized or not controller_available or \ - self.CP.dashcamOnly or community_feature_disallowed + self.read_only = not car_recognized or not controller_available or self.CP.dashcamOnly if self.read_only: safety_config = car.CarParams.SafetyConfig.new_message() safety_config.safetyModel = car.CarParams.SafetyModel.noOutput @@ -132,13 +126,13 @@ class Controls: self.VM = VehicleModel(self.CP) if self.CP.steerControlType == car.CarParams.SteerControlType.angle: - self.LaC = LatControlAngle(self.CP) + self.LaC = LatControlAngle(self.CP, self.CI) elif self.CP.lateralTuning.which() == 'pid': self.LaC = LatControlPID(self.CP, self.CI) elif self.CP.lateralTuning.which() == 'indi': - self.LaC = LatControlINDI(self.CP) + self.LaC = LatControlINDI(self.CP, self.CI) elif self.CP.lateralTuning.which() == 'lqr': - self.LaC = LatControlLQR(self.CP) + self.LaC = LatControlLQR(self.CP, self.CI) self.initialized = False self.state = State.disabled @@ -150,15 +144,15 @@ class Controls: self.v_cruise_kph_last = 0 self.mismatch_counter = 0 self.cruise_mismatch_counter = 0 - self.can_error_counter = 0 + self.can_rcv_error_counter = 0 self.last_blinker_frame = 0 - self.saturated_count = 0 self.distance_traveled = 0 self.last_functional_fan_frame = 0 self.events_prev = [] self.current_alert_types = [ET.PERMANENT] self.logged_comm_issue = False self.button_timers = {ButtonEvent.Type.decelCruise: 0, ButtonEvent.Type.accelCruise: 0} + self.last_actuators = car.CarControl.Actuators.new_message() # TODO: no longer necessary, aside from process replay self.sm['liveParameters'].valid = True @@ -167,8 +161,6 @@ class Controls: if not sounds_available: self.events.add(EventName.soundsUnavailable, static=True) - if community_feature_disallowed and car_recognized and not self.CP.dashcamOnly: - self.events.add(EventName.communityFeatureDisallowed, static=True) if not car_recognized: self.events.add(EventName.carUnrecognized, static=True) if len(self.CP.carFw) > 0: @@ -189,10 +181,8 @@ class Controls: """Compute carEvents from carState""" self.events.clear() - self.events.add_from_msg(CS.events) - self.events.add_from_msg(self.sm['driverMonitoringState'].events) - # Handle startup event + # Add startup event if self.startup_event is not None: self.events.add(self.startup_event) self.startup_event = None @@ -202,6 +192,9 @@ class Controls: self.events.add(EventName.controlsInitializing) return + self.events.add_from_msg(CS.events) + self.events.add_from_msg(self.sm['driverMonitoringState'].events) + # Create events for battery, temperature, disk space, and memory if EON and (self.sm['peripheralState'].pandaType != PandaType.uno) and \ self.sm['deviceState'].batteryPercent < 1 and self.sm['deviceState'].chargingError: @@ -222,7 +215,7 @@ class Controls: # self.events.add(EventName.highCpuUsage) # Alert if fan isn't spinning for 5 seconds - if self.sm['peripheralState'].pandaType in [PandaType.uno, PandaType.dos]: + if self.sm['peripheralState'].pandaType in (PandaType.uno, PandaType.dos): if self.sm['peripheralState'].fanSpeedRpm == 0 and self.sm['deviceState'].fanSpeedPercentDesired > 50: if (self.sm.frame - self.last_functional_fan_frame) * DT_CTRL > 5.0: self.events.add(EventName.fanMalfunction) @@ -248,19 +241,22 @@ class Controls: self.events.add(EventName.preLaneChangeLeft) else: self.events.add(EventName.preLaneChangeRight) - elif self.sm['lateralPlan'].laneChangeState in [LaneChangeState.laneChangeStarting, - LaneChangeState.laneChangeFinishing]: + elif self.sm['lateralPlan'].laneChangeState in (LaneChangeState.laneChangeStarting, + LaneChangeState.laneChangeFinishing): self.events.add(EventName.laneChange) - if self.can_rcv_error or not CS.canValid: + if not CS.canValid: self.events.add(EventName.canError) for i, pandaState in enumerate(self.sm['pandaStates']): # All pandas must match the list of safetyConfigs, and if outside this list, must be silent or noOutput if i < len(self.CP.safetyConfigs): - safety_mismatch = pandaState.safetyModel != self.CP.safetyConfigs[i].safetyModel or pandaState.safetyParam != self.CP.safetyConfigs[i].safetyParam + safety_mismatch = pandaState.safetyModel != self.CP.safetyConfigs[i].safetyModel or \ + pandaState.safetyParam != self.CP.safetyConfigs[i].safetyParam or \ + pandaState.unsafeMode != self.CP.unsafeMode else: safety_mismatch = pandaState.safetyModel not in IGNORED_SAFETY_MODES + if safety_mismatch or self.mismatch_counter >= 200: self.events.add(EventName.controlsMismatch) @@ -272,12 +268,12 @@ class Controls: self.events.add(EventName.radarFault) elif not self.sm.valid["pandaStates"]: self.events.add(EventName.usbError) - elif not self.sm.all_alive_and_valid(): + elif not self.sm.all_alive_and_valid() or self.can_rcv_error: self.events.add(EventName.commIssue) if not self.logged_comm_issue: invalid = [s for s, valid in self.sm.valid.items() if not valid] not_alive = [s for s, alive in self.sm.alive.items() if not alive] - cloudlog.event("commIssue", invalid=invalid, not_alive=not_alive) + cloudlog.event("commIssue", invalid=invalid, not_alive=not_alive, can_error=self.can_rcv_error, error=True) self.logged_comm_issue = True else: self.logged_comm_issue = False @@ -293,9 +289,6 @@ class Controls: self.events.add(EventName.posenetInvalid) if not self.sm['liveLocationKalman'].deviceStable: self.events.add(EventName.deviceFalling) - for pandaState in self.sm['pandaStates']: - if log.PandaState.FaultType.relayMalfunction in pandaState.faults: - self.events.add(EventName.relayMalfunction) if not REPLAY: # Check for mismatch between openpilot and car's PCM @@ -312,25 +305,17 @@ class Controls: self.events.add(EventName.fcw) if TICI: - logs = messaging.drain_sock(self.log_sock, wait_for_one=False) - messages = [] - for m in logs: + for m in messaging.drain_sock(self.log_sock, wait_for_one=False): try: - messages.append(m.androidLog.message) + msg = m.androidLog.message + if any(err in msg for err in ("ERROR_CRC", "ERROR_ECC", "ERROR_STREAM_UNDERFLOW", "APPLY FAILED")): + csid = msg.split("CSID:")[-1].split(" ")[0] + evt = CSID_MAP.get(csid, None) + if evt is not None: + self.events.add(evt) except UnicodeDecodeError: pass - for err in ["ERROR_CRC", "ERROR_ECC", "ERROR_STREAM_UNDERFLOW", "APPLY FAILED"]: - for m in messages: - if err not in m: - continue - - csid = m.split("CSID:")[-1].split(" ")[0] - evt = {"0": EventName.roadCameraError, "1": EventName.wideRoadCameraError, - "2": EventName.driverCameraError}.get(csid, None) - if evt is not None: - self.events.add(evt) - # TODO: fix simulator if not SIMULATION: if not NOSENSOR: @@ -345,7 +330,7 @@ class Controls: self.events.add(EventName.localizerMalfunction) # Check if all manager processes are running - not_running = set(p.name for p in self.sm['managerState'].processes if not p.running) + not_running = {p.name for p in self.sm['managerState'].processes if not p.running} if self.sm.rcv_frame['managerState'] and (not_running - IGNORE_PROCESSES): self.events.add(EventName.processNotRunning) @@ -368,16 +353,21 @@ class Controls: self.sm.update(0) - all_valid = CS.canValid and self.sm.all_alive_and_valid() - if not self.initialized and (all_valid or self.sm.frame * DT_CTRL > 3.5 or SIMULATION): - if not self.read_only: - self.CI.init(self.CP, self.can_sock, self.pm.sock['sendcan']) - self.initialized = True - Params().put_bool("ControlsReady", True) + if not self.initialized: + all_valid = CS.canValid and self.sm.all_alive_and_valid() + if all_valid or self.sm.frame * DT_CTRL > 3.5 or SIMULATION: + if not self.read_only: + self.CI.init(self.CP, self.can_sock, self.pm.sock['sendcan']) + self.initialized = True + + if REPLAY and self.sm['pandaStates'][0].controlsAllowed: + self.state = State.enabled + + Params().put_bool("ControlsReady", True) # Check for CAN timeout if not can_strs: - self.can_error_counter += 1 + self.can_rcv_error_counter += 1 self.can_rcv_error = True else: self.can_rcv_error = False @@ -390,7 +380,7 @@ class Controls: self.mismatch_counter = 0 # All pandas not in silent mode must have controlsAllowed when openpilot is enabled - if any(not ps.controlsAllowed and self.enabled for ps in self.sm['pandaStates'] + if self.enabled and any(not ps.controlsAllowed for ps in self.sm['pandaStates'] if ps.safetyModel not in IGNORED_SAFETY_MODES): self.mismatch_counter += 1 @@ -406,7 +396,7 @@ class Controls: # if stock cruise is completely disabled, then we can use our own set speed logic if not self.CP.pcmCruise: self.v_cruise_kph = update_v_cruise(self.v_cruise_kph, CS.buttonEvents, self.button_timers, self.enabled, self.is_metric) - elif self.CP.pcmCruise and CS.cruiseState.enabled: + elif CS.cruiseState.enabled: self.v_cruise_kph = CS.cruiseState.speed * CV.MS_TO_KPH # decrement the soft disable timer at every step, as it's reset on @@ -440,7 +430,7 @@ class Controls: # no more soft disabling condition, so go back to ENABLED self.state = State.enabled - elif self.events.any(ET.SOFT_DISABLE) and self.soft_disable_timer > 0: + elif self.soft_disable_timer > 0: self.current_alert_types.append(ET.SOFT_DISABLE) elif self.soft_disable_timer <= 0: @@ -510,7 +500,7 @@ class Controls: lat_plan.psis, lat_plan.curvatures, lat_plan.curvatureRates) - actuators.steer, actuators.steeringAngleDeg, lac_log = self.LaC.update(lat_active, CS, self.CP, self.VM, params, + actuators.steer, actuators.steeringAngleDeg, lac_log = self.LaC.update(lat_active, CS, self.CP, self.VM, params, self.last_actuators, desired_curvature, desired_curvature_rate) else: lac_log = log.ControlsState.LateralDebugState.new_message() @@ -526,24 +516,14 @@ class Controls: lac_log.output = steer lac_log.saturated = abs(steer) >= 0.9 - # Check for difference between desired angle and angle for angle based control - angle_control_saturated = self.CP.steerControlType == car.CarParams.SteerControlType.angle and \ - abs(actuators.steeringAngleDeg - CS.steeringAngleDeg) > STEER_ANGLE_SATURATION_THRESHOLD - - if angle_control_saturated and not CS.steeringPressed and self.active: - self.saturated_count += 1 - else: - self.saturated_count = 0 - # Send a "steering required alert" if saturation count has reached the limit - if (lac_log.saturated and not CS.steeringPressed) or \ - (self.saturated_count > STEER_ANGLE_SATURATION_TIMEOUT): - - if len(lat_plan.dPathPoints): + if lac_log.active and lac_log.saturated and not CS.steeringPressed: + dpath_points = lat_plan.dPathPoints + if len(dpath_points): # Check if we deviated from the path # TODO use desired vs actual curvature - left_deviation = actuators.steer > 0 and lat_plan.dPathPoints[0] < -0.20 - right_deviation = actuators.steer < 0 and lat_plan.dPathPoints[0] > 0.20 + left_deviation = actuators.steer > 0 and dpath_points[0] < -0.20 + right_deviation = actuators.steer < 0 and dpath_points[0] > 0.20 if left_deviation or right_deviation: self.events.add(EventName.steerSaturated) @@ -562,7 +542,7 @@ class Controls: def update_button_timers(self, buttonEvents): # increment timer for buttons still pressed - for k in self.button_timers.keys(): + for k in self.button_timers: if self.button_timers[k] > 0: self.button_timers[k] += 1 @@ -578,71 +558,86 @@ class Controls: CC.active = self.active CC.actuators = actuators - if len(self.sm['liveLocationKalman'].orientationNED.value) > 2: - CC.roll = self.sm['liveLocationKalman'].orientationNED.value[0] - CC.pitch = self.sm['liveLocationKalman'].orientationNED.value[1] + orientation_value = self.sm['liveLocationKalman'].orientationNED.value + if len(orientation_value) > 2: + CC.roll = orientation_value[0] + CC.pitch = orientation_value[1] CC.cruiseControl.cancel = CS.cruiseState.enabled and (not self.enabled or not self.CP.pcmCruise) if self.joystick_mode and self.sm.rcv_frame['testJoystick'] > 0 and self.sm['testJoystick'].buttons[0]: CC.cruiseControl.cancel = True - CC.hudControl.setSpeed = float(self.v_cruise_kph * CV.KPH_TO_MS) - CC.hudControl.speedVisible = self.enabled - CC.hudControl.lanesVisible = self.enabled - CC.hudControl.leadVisible = self.sm['longitudinalPlan'].hasLead + hudControl = CC.hudControl + hudControl.setSpeed = float(self.v_cruise_kph * CV.KPH_TO_MS) + hudControl.speedVisible = self.enabled + hudControl.lanesVisible = self.enabled + hudControl.leadVisible = self.sm['longitudinalPlan'].hasLead - CC.hudControl.rightLaneVisible = True - CC.hudControl.leftLaneVisible = True + hudControl.rightLaneVisible = True + hudControl.leftLaneVisible = True recent_blinker = (self.sm.frame - self.last_blinker_frame) * DT_CTRL < 5.0 # 5s blinker cooldown ldw_allowed = self.is_ldw_enabled and CS.vEgo > LDW_MIN_SPEED and not recent_blinker \ and not self.active and self.sm['liveCalibration'].calStatus == Calibration.CALIBRATED - meta = self.sm['modelV2'].meta - if len(meta.desirePrediction) and ldw_allowed: + model_v2 = self.sm['modelV2'] + desire_prediction = model_v2.meta.desirePrediction + if len(desire_prediction) and ldw_allowed: right_lane_visible = self.sm['lateralPlan'].rProb > 0.5 left_lane_visible = self.sm['lateralPlan'].lProb > 0.5 - l_lane_change_prob = meta.desirePrediction[Desire.laneChangeLeft - 1] - r_lane_change_prob = meta.desirePrediction[Desire.laneChangeRight - 1] - l_lane_close = left_lane_visible and (self.sm['modelV2'].laneLines[1].y[0] > -(1.08 + CAMERA_OFFSET)) - r_lane_close = right_lane_visible and (self.sm['modelV2'].laneLines[2].y[0] < (1.08 - CAMERA_OFFSET)) + l_lane_change_prob = desire_prediction[Desire.laneChangeLeft - 1] + r_lane_change_prob = desire_prediction[Desire.laneChangeRight - 1] - CC.hudControl.leftLaneDepart = bool(l_lane_change_prob > LANE_DEPARTURE_THRESHOLD and l_lane_close) - CC.hudControl.rightLaneDepart = bool(r_lane_change_prob > LANE_DEPARTURE_THRESHOLD and r_lane_close) + lane_lines = model_v2.laneLines + l_lane_close = left_lane_visible and (lane_lines[1].y[0] > -(1.08 + CAMERA_OFFSET)) + r_lane_close = right_lane_visible and (lane_lines[2].y[0] < (1.08 - CAMERA_OFFSET)) - if CC.hudControl.rightLaneDepart or CC.hudControl.leftLaneDepart: + hudControl.leftLaneDepart = bool(l_lane_change_prob > LANE_DEPARTURE_THRESHOLD and l_lane_close) + hudControl.rightLaneDepart = bool(r_lane_change_prob > LANE_DEPARTURE_THRESHOLD and r_lane_close) + + if hudControl.rightLaneDepart or hudControl.leftLaneDepart: self.events.add(EventName.ldw) - clear_event = ET.WARNING if ET.WARNING not in self.current_alert_types else None + clear_event_types = set() + if ET.WARNING not in self.current_alert_types: + clear_event_types.add(ET.WARNING) + if self.enabled: + clear_event_types.add(ET.NO_ENTRY) + alerts = self.events.create_alerts(self.current_alert_types, [self.CP, self.sm, self.is_metric, self.soft_disable_timer]) self.AM.add_many(self.sm.frame, alerts) - self.AM.process_alerts(self.sm.frame, clear_event) - CC.hudControl.visualAlert = self.AM.visual_alert + current_alert = self.AM.process_alerts(self.sm.frame, clear_event_types) + if current_alert: + hudControl.visualAlert = current_alert.visual_alert if not self.read_only and self.initialized: # send car controls over can - can_sends = self.CI.apply(CC) + self.last_actuators, can_sends = self.CI.apply(CC) self.pm.send('sendcan', can_list_to_can_capnp(can_sends, msgtype='sendcan', valid=CS.canValid)) + CC.actuatorsOutput = self.last_actuators force_decel = (self.sm['driverMonitoringState'].awarenessStatus < 0.) or \ (self.state == State.softDisabling) # Curvature & Steering angle params = self.sm['liveParameters'] - steer_angle_without_offset = math.radians(CS.steeringAngleDeg - params.angleOffsetAverageDeg) - curvature = -self.VM.calc_curvature(steer_angle_without_offset, CS.vEgo) + + steer_angle_without_offset = math.radians(CS.steeringAngleDeg - params.angleOffsetDeg) + curvature = -self.VM.calc_curvature(steer_angle_without_offset, CS.vEgo, params.roll) # controlsState dat = messaging.new_message('controlsState') dat.valid = CS.canValid controlsState = dat.controlsState - controlsState.alertText1 = self.AM.alert_text_1 - controlsState.alertText2 = self.AM.alert_text_2 - controlsState.alertSize = self.AM.alert_size - controlsState.alertStatus = self.AM.alert_status - controlsState.alertBlinkingRate = self.AM.alert_rate - controlsState.alertType = self.AM.alert_type - controlsState.alertSound = self.AM.audible_alert + if current_alert: + controlsState.alertText1 = current_alert.alert_text_1 + controlsState.alertText2 = current_alert.alert_text_2 + controlsState.alertSize = current_alert.alert_size + controlsState.alertStatus = current_alert.alert_status + controlsState.alertBlinkingRate = current_alert.alert_rate + controlsState.alertType = current_alert.alert_type + controlsState.alertSound = current_alert.audible_alert + controlsState.canMonoTimes = list(CS.canMonoTimes) controlsState.longitudinalPlanMonoTime = self.sm.logMonoTime['longitudinalPlan'] controlsState.lateralPlanMonoTime = self.sm.logMonoTime['lateralPlan'] @@ -660,18 +655,20 @@ class Controls: controlsState.cumLagMs = -self.rk.remaining * 1000. controlsState.startMonoTime = int(start_time * 1e9) controlsState.forceDecel = bool(force_decel) - controlsState.canErrorCounter = self.can_error_counter + controlsState.canErrorCounter = self.can_rcv_error_counter + lat_tuning = self.CP.lateralTuning.which() if self.joystick_mode: controlsState.lateralControlState.debugState = lac_log elif self.CP.steerControlType == car.CarParams.SteerControlType.angle: controlsState.lateralControlState.angleState = lac_log - elif self.CP.lateralTuning.which() == 'pid': + elif lat_tuning == 'pid': controlsState.lateralControlState.pidState = lac_log - elif self.CP.lateralTuning.which() == 'lqr': + elif lat_tuning == 'lqr': controlsState.lateralControlState.lqrState = lac_log - elif self.CP.lateralTuning.which() == 'indi': + elif lat_tuning == 'indi': controlsState.lateralControlState.indiState = lac_log + self.pm.send('controlsState', dat) # carState diff --git a/selfdrive/controls/lib/alertmanager.py b/selfdrive/controls/lib/alertmanager.py index c8e702c5c..2dad05e21 100644 --- a/selfdrive/controls/lib/alertmanager.py +++ b/selfdrive/controls/lib/alertmanager.py @@ -5,7 +5,6 @@ from collections import defaultdict from dataclasses import dataclass from typing import List, Dict, Optional -from cereal import car, log from common.basedir import BASEDIR from common.params import Params from selfdrive.controls.lib.events import Alert @@ -36,55 +35,30 @@ class AlertEntry: return frame <= self.end_frame class AlertManager: - def __init__(self): - self.reset() self.alerts: Dict[str, AlertEntry] = defaultdict(AlertEntry) - def reset(self) -> None: - self.alert: Optional[Alert] = None - self.alert_type: str = "" - self.alert_text_1: str = "" - self.alert_text_2: str = "" - self.alert_status = log.ControlsState.AlertStatus.normal - self.alert_size = log.ControlsState.AlertSize.none - self.visual_alert = car.CarControl.HUDControl.VisualAlert.none - self.audible_alert = car.CarControl.HUDControl.AudibleAlert.none - self.alert_rate: float = 0. - def add_many(self, frame: int, alerts: List[Alert]) -> None: for alert in alerts: - key = alert.alert_type - self.alerts[key].alert = alert - if not self.alerts[key].active(frame): - self.alerts[key].start_frame = frame - min_end_frame = self.alerts[key].start_frame + alert.duration - self.alerts[key].end_frame = max(frame + 1, min_end_frame) + entry = self.alerts[alert.alert_type] + entry.alert = alert + if not entry.active(frame): + entry.start_frame = frame + min_end_frame = entry.start_frame + alert.duration + entry.end_frame = max(frame + 1, min_end_frame) - def process_alerts(self, frame: int, clear_event_type=None) -> None: + def process_alerts(self, frame: int, clear_event_types: set) -> Optional[Alert]: current_alert = AlertEntry() - for k, v in self.alerts.items(): - if v.alert is None: + for v in self.alerts.values(): + if not v.alert: continue - if clear_event_type is not None and v.alert.event_type == clear_event_type: - self.alerts[k].end_frame = -1 + if v.alert.event_type in clear_event_types: + v.end_frame = -1 # sort by priority first and then by start_frame greater = current_alert.alert is None or (v.alert.priority, v.start_frame) > (current_alert.alert.priority, current_alert.start_frame) if v.active(frame) and greater: current_alert = v - # clear current alert - self.reset() - - self.alert = current_alert.alert - if self.alert is not None: - self.alert_type = self.alert.alert_type - self.audible_alert = self.alert.audible_alert - self.visual_alert = self.alert.visual_alert - self.alert_text_1 = self.alert.alert_text_1 - self.alert_text_2 = self.alert.alert_text_2 - self.alert_status = self.alert.alert_status - self.alert_size = self.alert.alert_size - self.alert_rate = self.alert.alert_rate + return current_alert.alert diff --git a/selfdrive/controls/lib/alerts_offroad.json b/selfdrive/controls/lib/alerts_offroad.json index 4affe0cfe..aa54f582f 100644 --- a/selfdrive/controls/lib/alerts_offroad.json +++ b/selfdrive/controls/lib/alerts_offroad.json @@ -38,7 +38,7 @@ "severity": 1 }, "Offroad_StorageMissing": { - "text": "Storage drive not mounted.", + "text": "NVMe drive not mounted.", "severity": 1 }, "Offroad_CarUnrecognized": { diff --git a/selfdrive/controls/lib/desire_helper.py b/selfdrive/controls/lib/desire_helper.py new file mode 100644 index 000000000..c34d143a5 --- /dev/null +++ b/selfdrive/controls/lib/desire_helper.py @@ -0,0 +1,113 @@ +from cereal import log +from common.realtime import DT_MDL +from selfdrive.config import Conversions as CV + +LaneChangeState = log.LateralPlan.LaneChangeState +LaneChangeDirection = log.LateralPlan.LaneChangeDirection + +LANE_CHANGE_SPEED_MIN = 30 * CV.MPH_TO_MS +LANE_CHANGE_TIME_MAX = 10. + +DESIRES = { + LaneChangeDirection.none: { + LaneChangeState.off: log.LateralPlan.Desire.none, + LaneChangeState.preLaneChange: log.LateralPlan.Desire.none, + LaneChangeState.laneChangeStarting: log.LateralPlan.Desire.none, + LaneChangeState.laneChangeFinishing: log.LateralPlan.Desire.none, + }, + LaneChangeDirection.left: { + LaneChangeState.off: log.LateralPlan.Desire.none, + LaneChangeState.preLaneChange: log.LateralPlan.Desire.none, + LaneChangeState.laneChangeStarting: log.LateralPlan.Desire.laneChangeLeft, + LaneChangeState.laneChangeFinishing: log.LateralPlan.Desire.laneChangeLeft, + }, + LaneChangeDirection.right: { + LaneChangeState.off: log.LateralPlan.Desire.none, + LaneChangeState.preLaneChange: log.LateralPlan.Desire.none, + LaneChangeState.laneChangeStarting: log.LateralPlan.Desire.laneChangeRight, + LaneChangeState.laneChangeFinishing: log.LateralPlan.Desire.laneChangeRight, + }, +} + + +class DesireHelper: + def __init__(self): + self.lane_change_state = LaneChangeState.off + self.lane_change_direction = LaneChangeDirection.none + self.lane_change_timer = 0.0 + self.lane_change_ll_prob = 1.0 + self.keep_pulse_timer = 0.0 + self.prev_one_blinker = False + self.desire = log.LateralPlan.Desire.none + + def update(self, carstate, active, lane_change_prob): + v_ego = carstate.vEgo + one_blinker = carstate.leftBlinker != carstate.rightBlinker + below_lane_change_speed = v_ego < LANE_CHANGE_SPEED_MIN + + if not active or self.lane_change_timer > LANE_CHANGE_TIME_MAX: + self.lane_change_state = LaneChangeState.off + self.lane_change_direction = LaneChangeDirection.none + else: + # LaneChangeState.off + if self.lane_change_state == LaneChangeState.off and one_blinker and not self.prev_one_blinker and not below_lane_change_speed: + self.lane_change_state = LaneChangeState.preLaneChange + self.lane_change_ll_prob = 1.0 + + # LaneChangeState.preLaneChange + elif self.lane_change_state == LaneChangeState.preLaneChange: + # Set lane change direction + self.lane_change_direction = LaneChangeDirection.left if \ + carstate.leftBlinker else LaneChangeDirection.right + + torque_applied = carstate.steeringPressed and \ + ((carstate.steeringTorque > 0 and self.lane_change_direction == LaneChangeDirection.left) or + (carstate.steeringTorque < 0 and self.lane_change_direction == LaneChangeDirection.right)) + + blindspot_detected = ((carstate.leftBlindspot and self.lane_change_direction == LaneChangeDirection.left) or + (carstate.rightBlindspot and self.lane_change_direction == LaneChangeDirection.right)) + + if not one_blinker or below_lane_change_speed: + self.lane_change_state = LaneChangeState.off + elif torque_applied and not blindspot_detected: + self.lane_change_state = LaneChangeState.laneChangeStarting + + # LaneChangeState.laneChangeStarting + elif self.lane_change_state == LaneChangeState.laneChangeStarting: + # fade out over .5s + self.lane_change_ll_prob = max(self.lane_change_ll_prob - 2 * DT_MDL, 0.0) + + # 98% certainty + if lane_change_prob < 0.02 and self.lane_change_ll_prob < 0.01: + self.lane_change_state = LaneChangeState.laneChangeFinishing + + # LaneChangeState.laneChangeFinishing + elif self.lane_change_state == LaneChangeState.laneChangeFinishing: + # fade in laneline over 1s + self.lane_change_ll_prob = min(self.lane_change_ll_prob + DT_MDL, 1.0) + + if self.lane_change_ll_prob > 0.99: + self.lane_change_direction = LaneChangeDirection.none + if one_blinker: + self.lane_change_state = LaneChangeState.preLaneChange + else: + self.lane_change_state = LaneChangeState.off + + if self.lane_change_state in (LaneChangeState.off, LaneChangeState.preLaneChange): + self.lane_change_timer = 0.0 + else: + self.lane_change_timer += DT_MDL + + self.prev_one_blinker = one_blinker + + self.desire = DESIRES[self.lane_change_direction][self.lane_change_state] + + # Send keep pulse once per second during LaneChangeStart.preLaneChange + if self.lane_change_state in (LaneChangeState.off, LaneChangeState.laneChangeStarting): + self.keep_pulse_timer = 0.0 + elif self.lane_change_state == LaneChangeState.preLaneChange: + self.keep_pulse_timer += DT_MDL + if self.keep_pulse_timer > 1.0: + self.keep_pulse_timer = 0.0 + elif self.desire in (log.LateralPlan.Desire.keepLeft, log.LateralPlan.Desire.keepRight): + self.desire = log.LateralPlan.Desire.none diff --git a/selfdrive/controls/lib/drive_helpers.py b/selfdrive/controls/lib/drive_helpers.py index f173f5fd9..14be3d5ed 100644 --- a/selfdrive/controls/lib/drive_helpers.py +++ b/selfdrive/controls/lib/drive_helpers.py @@ -119,6 +119,6 @@ def get_lag_adjusted_curvature(CP, v_ego, psis, curvatures, curvature_rates): -max_curvature_rate, max_curvature_rate) safe_desired_curvature = clip(desired_curvature, - current_curvature - max_curvature_rate/DT_MDL, - current_curvature + max_curvature_rate/DT_MDL) + current_curvature - max_curvature_rate * DT_MDL, + current_curvature + max_curvature_rate * DT_MDL) return safe_desired_curvature, safe_desired_curvature_rate diff --git a/selfdrive/controls/lib/events.py b/selfdrive/controls/lib/events.py index 0048ca661..fbce9460a 100644 --- a/selfdrive/controls/lib/events.py +++ b/selfdrive/controls/lib/events.py @@ -1,5 +1,5 @@ from enum import IntEnum -from typing import Dict, Union, Callable +from typing import Dict, Union, Callable, List, Optional from cereal import log, car import cereal.messaging as messaging @@ -42,33 +42,30 @@ EVENT_NAME = {v: k for k, v in EventName.schema.enumerants.items()} class Events: def __init__(self): - self.events = [] - self.static_events = [] + self.events: List[int] = [] + self.static_events: List[int] = [] self.events_prev = dict.fromkeys(EVENTS.keys(), 0) @property - def names(self): + def names(self) -> List[int]: return self.events - def __len__(self): + def __len__(self) -> int: return len(self.events) - def add(self, event_name, static=False): + def add(self, event_name: int, static: bool=False) -> None: if static: self.static_events.append(event_name) self.events.append(event_name) - def clear(self): + def clear(self) -> None: self.events_prev = {k: (v + 1 if k in self.events else 0) for k, v in self.events_prev.items()} self.events = self.static_events.copy() - def any(self, event_type): - for e in self.events: - if event_type in EVENTS.get(e, {}).keys(): - return True - return False + def any(self, event_type: str) -> bool: + return any(event_type in EVENTS.get(e, {}) for e in self.events) - def create_alerts(self, event_types, callback_args=None): + def create_alerts(self, event_types: List[str], callback_args=None): if callback_args is None: callback_args = [] @@ -96,7 +93,7 @@ class Events: for event_name in self.events: event = car.CarEvent.new_message() event.name = event_name - for event_type in EVENTS.get(event_name, {}).keys(): + for event_type in EVENTS.get(event_name, {}): setattr(event, event_type, True) ret.append(event) return ret @@ -129,7 +126,7 @@ class Alert: self.creation_delay = creation_delay self.alert_type = "" - self.event_type = None + self.event_type: Optional[str] = None def __str__(self) -> str: return f"{self.alert_text_1}/{self.alert_text_2} {self.priority} {self.visual_alert} {self.audible_alert}" @@ -139,14 +136,14 @@ class Alert: class NoEntryAlert(Alert): - def __init__(self, alert_text_2, visual_alert=VisualAlert.none): + def __init__(self, alert_text_2: str, visual_alert: car.CarControl.HUDControl.VisualAlert=VisualAlert.none): super().__init__("openpilot Unavailable", alert_text_2, AlertStatus.normal, AlertSize.mid, Priority.LOW, visual_alert, AudibleAlert.refuse, 3.) class SoftDisableAlert(Alert): - def __init__(self, alert_text_2): + def __init__(self, alert_text_2: str): super().__init__("TAKE CONTROL IMMEDIATELY", alert_text_2, AlertStatus.userPrompt, AlertSize.full, Priority.MID, VisualAlert.steerRequired, @@ -155,13 +152,13 @@ class SoftDisableAlert(Alert): # less harsh version of SoftDisable, where the condition is user-triggered class UserSoftDisableAlert(SoftDisableAlert): - def __init__(self, alert_text_2): + def __init__(self, alert_text_2: str): super().__init__(alert_text_2), self.alert_text_1 = "openpilot will disengage" class ImmediateDisableAlert(Alert): - def __init__(self, alert_text_2): + def __init__(self, alert_text_2: str): super().__init__("TAKE CONTROL IMMEDIATELY", alert_text_2, AlertStatus.critical, AlertSize.full, Priority.HIGHEST, VisualAlert.steerRequired, @@ -239,7 +236,7 @@ def calibration_incomplete_alert(CP: car.CarParams, sm: messaging.SubMaster, met def no_gps_alert(CP: car.CarParams, sm: messaging.SubMaster, metric: bool, soft_disable_time: int) -> Alert: - gps_integrated = sm['peripheralState'].pandaType in [log.PandaState.PandaType.uno, log.PandaState.PandaType.dos] + gps_integrated = sm['peripheralState'].pandaType in (log.PandaState.PandaType.uno, log.PandaState.PandaType.dos) return Alert( "Poor GPS reception", "If sky is visible, contact support" if gps_integrated else "Check GPS antenna placement", @@ -317,14 +314,6 @@ EVENTS: Dict[int, Dict[str, Union[Alert, AlertCallbackType]]] = { #ET.PERMANENT: ImmediateDisableAlert("openpilot failed to cancel cruise"), }, - # Some features or cars are marked as community features. If openpilot - # detects the use of a community feature it switches to dashcam mode - # until these features are allowed using a toggle in settings. - EventName.communityFeatureDisallowed: { - ET.PERMANENT: NormalPermanentAlert("openpilot Unavailable", - "Enable Community Features in Settings"), - }, - # openpilot doesn't recognize the car. This switches openpilot into a # read-only mode. This can be solved by adding your fingerprint. # See https://github.com/commaai/openpilot/wiki/Fingerprinting for more information @@ -517,7 +506,7 @@ EVENTS: Dict[int, Dict[str, Union[Alert, AlertCallbackType]]] = { # current GPS position. This alert is thrown when the localizer is reset # more often than expected. EventName.localizerMalfunction: { - ET.PERMANENT: NormalPermanentAlert("Sensor Malfunction", "Contact Support"), + # ET.PERMANENT: NormalPermanentAlert("Sensor Malfunction", "Contact Support"), }, # ********** events that affect controls state transitions ********** @@ -832,4 +821,9 @@ EVENTS: Dict[int, Dict[str, Union[Alert, AlertCallbackType]]] = { ET.NO_ENTRY: NoEntryAlert("Cruise Fault: Restart the Car"), }, + EventName.lkasDisabled: { + ET.PERMANENT: NormalPermanentAlert("LKAS Disabled: Enable LKAS to engage"), + ET.NO_ENTRY: NoEntryAlert("LKAS Disabled"), + }, + } diff --git a/selfdrive/controls/lib/lane_planner.py b/selfdrive/controls/lib/lane_planner.py index 88a1f6a67..160808cff 100644 --- a/selfdrive/controls/lib/lane_planner.py +++ b/selfdrive/controls/lib/lane_planner.py @@ -9,12 +9,14 @@ from selfdrive.swaglog import cloudlog TRAJECTORY_SIZE = 33 # camera offset is meters from center car to camera +# model path is in the frame of EON's camera. TICI is 0.1 m away, +# however the average measured path difference is 0.04 m if EON: - CAMERA_OFFSET = 0.06 + CAMERA_OFFSET = -0.06 PATH_OFFSET = 0.0 elif TICI: - CAMERA_OFFSET = -0.04 - PATH_OFFSET = -0.04 + CAMERA_OFFSET = 0.04 + PATH_OFFSET = 0.04 else: CAMERA_OFFSET = 0.0 PATH_OFFSET = 0.0 @@ -44,30 +46,31 @@ class LanePlanner: self.path_offset = -PATH_OFFSET if wide_camera else PATH_OFFSET def parse_model(self, md): - if len(md.laneLines) == 4 and len(md.laneLines[0].t) == TRAJECTORY_SIZE: - self.ll_t = (np.array(md.laneLines[1].t) + np.array(md.laneLines[2].t))/2 + lane_lines = md.laneLines + if len(lane_lines) == 4 and len(lane_lines[0].t) == TRAJECTORY_SIZE: + self.ll_t = (np.array(lane_lines[1].t) + np.array(lane_lines[2].t))/2 # left and right ll x is the same - self.ll_x = md.laneLines[1].x - # only offset left and right lane lines; offsetting path does not make sense - self.lll_y = np.array(md.laneLines[1].y) - self.camera_offset - self.rll_y = np.array(md.laneLines[2].y) - self.camera_offset + self.ll_x = lane_lines[1].x + self.lll_y = np.array(lane_lines[1].y) + self.camera_offset + self.rll_y = np.array(lane_lines[2].y) + self.camera_offset self.lll_prob = md.laneLineProbs[1] self.rll_prob = md.laneLineProbs[2] self.lll_std = md.laneLineStds[1] self.rll_std = md.laneLineStds[2] - if len(md.meta.desireState): - self.l_lane_change_prob = md.meta.desireState[log.LateralPlan.Desire.laneChangeLeft] - self.r_lane_change_prob = md.meta.desireState[log.LateralPlan.Desire.laneChangeRight] + desire_state = md.meta.desireState + if len(desire_state): + self.l_lane_change_prob = desire_state[log.LateralPlan.Desire.laneChangeLeft] + self.r_lane_change_prob = desire_state[log.LateralPlan.Desire.laneChangeRight] def get_d_path(self, v_ego, path_t, path_xyz): # Reduce reliance on lanelines that are too far apart or # will be in a few seconds - path_xyz[:, 1] -= self.path_offset + path_xyz[:, 1] += self.path_offset l_prob, r_prob = self.lll_prob, self.rll_prob width_pts = self.rll_y - self.lll_y prob_mods = [] - for t_check in [0.0, 1.5, 3.0]: + for t_check in (0.0, 1.5, 3.0): width_at_t = interp(t_check * (v_ego + 7), self.ll_x, width_pts) prob_mods.append(interp(width_at_t, [4.0, 5.0], [1.0, 0.0])) mod = min(prob_mods) diff --git a/selfdrive/controls/lib/latcontrol.py b/selfdrive/controls/lib/latcontrol.py new file mode 100644 index 000000000..eb16aca2e --- /dev/null +++ b/selfdrive/controls/lib/latcontrol.py @@ -0,0 +1,28 @@ +from abc import abstractmethod, ABC + +from common.realtime import DT_CTRL +from common.numpy_fast import clip + +MIN_STEER_SPEED = 0.3 + + +class LatControl(ABC): + def __init__(self, CP, CI): + self.sat_count_rate = 1.0 * DT_CTRL + self.sat_limit = CP.steerLimitTimer + self.sat_count = 0. + + @abstractmethod + def update(self, active, CS, CP, VM, params, last_actuators, desired_curvature, desired_curvature_rate): + pass + + def reset(self): + self.sat_count = 0. + + def _check_saturation(self, saturated, CS): + if saturated and CS.vEgo > 10. and not CS.steeringRateLimited and not CS.steeringPressed: + self.sat_count += self.sat_count_rate + else: + self.sat_count -= self.sat_count_rate + self.sat_count = clip(self.sat_count, 0.0, self.sat_limit) + return self.sat_count > (self.sat_limit - 1e-3) diff --git a/selfdrive/controls/lib/latcontrol_angle.py b/selfdrive/controls/lib/latcontrol_angle.py index 8fcb9ae7b..c93535631 100644 --- a/selfdrive/controls/lib/latcontrol_angle.py +++ b/selfdrive/controls/lib/latcontrol_angle.py @@ -1,28 +1,25 @@ import math from cereal import log +from selfdrive.controls.lib.latcontrol import LatControl, MIN_STEER_SPEED + +STEER_ANGLE_SATURATION_THRESHOLD = 2.5 # Degrees -class LatControlAngle(): - def __init__(self, CP): - pass - - def reset(self): - pass - - def update(self, active, CS, CP, VM, params, desired_curvature, desired_curvature_rate): +class LatControlAngle(LatControl): + def update(self, active, CS, CP, VM, params, last_actuators, desired_curvature, desired_curvature_rate): angle_log = log.ControlsState.LateralAngleState.new_message() - if CS.vEgo < 0.3 or not active: + if CS.vEgo < MIN_STEER_SPEED or not active: angle_log.active = False angle_steers_des = float(CS.steeringAngleDeg) else: angle_log.active = True - angle_steers_des = math.degrees(VM.get_steer_from_curvature(-desired_curvature, CS.vEgo)) + angle_steers_des = math.degrees(VM.get_steer_from_curvature(-desired_curvature, CS.vEgo, params.roll)) angle_steers_des += params.angleOffsetDeg - angle_log.saturated = False + angle_control_saturated = abs(angle_steers_des - CS.steeringAngleDeg) > STEER_ANGLE_SATURATION_THRESHOLD + angle_log.saturated = self._check_saturation(angle_control_saturated, CS) angle_log.steeringAngleDeg = float(CS.steeringAngleDeg) - angle_log.steeringAngleDesiredDeg = angle_steers_des - + angle_log.steeringAngleDesiredDeg = angle_steers_des return 0, float(angle_steers_des), angle_log diff --git a/selfdrive/controls/lib/latcontrol_indi.py b/selfdrive/controls/lib/latcontrol_indi.py index 50a8e22b3..dc1b31bad 100644 --- a/selfdrive/controls/lib/latcontrol_indi.py +++ b/selfdrive/controls/lib/latcontrol_indi.py @@ -5,13 +5,13 @@ from cereal import log from common.filter_simple import FirstOrderFilter from common.numpy_fast import clip, interp from common.realtime import DT_CTRL -from selfdrive.car import apply_toyota_steer_torque_limits -from selfdrive.car.toyota.values import CarControllerParams from selfdrive.controls.lib.drive_helpers import get_steer_max +from selfdrive.controls.lib.latcontrol import LatControl, MIN_STEER_SPEED -class LatControlINDI(): - def __init__(self, CP): +class LatControlINDI(LatControl): + def __init__(self, CP, CI): + super().__init__(CP, CI) self.angle_steers_des = 0. A = np.array([[1.0, DT_CTRL, 0.0], @@ -35,15 +35,11 @@ class LatControlINDI(): self.A_K = A - np.dot(K, C) self.x = np.array([[0.], [0.], [0.]]) - self.enforce_rate_limit = CP.carName == "toyota" - self._RC = (CP.lateralTuning.indi.timeConstantBP, CP.lateralTuning.indi.timeConstantV) self._G = (CP.lateralTuning.indi.actuatorEffectivenessBP, CP.lateralTuning.indi.actuatorEffectivenessV) self._outer_loop_gain = (CP.lateralTuning.indi.outerLoopGainBP, CP.lateralTuning.indi.outerLoopGainV) self._inner_loop_gain = (CP.lateralTuning.indi.innerLoopGainBP, CP.lateralTuning.indi.innerLoopGainV) - self.sat_count_rate = 1.0 * DT_CTRL - self.sat_limit = CP.steerLimitTimer self.steer_filter = FirstOrderFilter(0., self.RC, DT_CTRL) self.reset() @@ -65,24 +61,11 @@ class LatControlINDI(): return interp(self.speed, self._inner_loop_gain[0], self._inner_loop_gain[1]) def reset(self): + super().reset() self.steer_filter.x = 0. - self.output_steer = 0. - self.sat_count = 0. self.speed = 0. - def _check_saturation(self, control, check_saturation, limit): - saturated = abs(control) == limit - - if saturated and check_saturation: - self.sat_count += self.sat_count_rate - else: - self.sat_count -= self.sat_count_rate - - self.sat_count = clip(self.sat_count, 0.0, 1.0) - - return self.sat_count > self.sat_limit - - def update(self, active, CS, CP, VM, params, curvature, curvature_rate): + def update(self, active, CS, CP, VM, params, last_actuators, desired_curvature, desired_curvature_rate): self.speed = CS.vEgo # Update Kalman filter y = np.array([[math.radians(CS.steeringAngleDeg)], [math.radians(CS.steeringRateDeg)]]) @@ -93,21 +76,21 @@ class LatControlINDI(): indi_log.steeringRateDeg = math.degrees(self.x[1]) indi_log.steeringAccelDeg = math.degrees(self.x[2]) - steers_des = VM.get_steer_from_curvature(-curvature, CS.vEgo) + steers_des = VM.get_steer_from_curvature(-desired_curvature, CS.vEgo, params.roll) steers_des += math.radians(params.angleOffsetDeg) indi_log.steeringAngleDesiredDeg = math.degrees(steers_des) - rate_des = VM.get_steer_from_curvature(-curvature_rate, CS.vEgo) + rate_des = VM.get_steer_from_curvature(-desired_curvature_rate, CS.vEgo, 0) indi_log.steeringRateDesiredDeg = math.degrees(rate_des) - if CS.vEgo < 0.3 or not active: + if CS.vEgo < MIN_STEER_SPEED or not active: indi_log.active = False - self.output_steer = 0.0 self.steer_filter.x = 0.0 + output_steer = 0 else: # Expected actuator value self.steer_filter.update_alpha(self.RC) - self.steer_filter.update(self.output_steer) + self.steer_filter.update(last_actuators.steer) # Compute acceleration error rate_sp = self.outer_loop_gain * (steers_des - self.x[0]) + rate_des @@ -119,21 +102,13 @@ class LatControlINDI(): delta_u = g_inv * accel_error # If steering pressed, only allow wind down - if CS.steeringPressed and (delta_u * self.output_steer > 0): + if CS.steeringPressed and (delta_u * last_actuators.steer > 0): delta_u = 0 - # Enforce rate limit - if self.enforce_rate_limit: - steer_max = float(CarControllerParams.STEER_MAX) - new_output_steer_cmd = steer_max * (self.steer_filter.x + delta_u) - prev_output_steer_cmd = steer_max * self.output_steer - new_output_steer_cmd = apply_toyota_steer_torque_limits(new_output_steer_cmd, prev_output_steer_cmd, prev_output_steer_cmd, CarControllerParams) - self.output_steer = new_output_steer_cmd / steer_max - else: - self.output_steer = self.steer_filter.x + delta_u + output_steer = self.steer_filter.x + delta_u steers_max = get_steer_max(CP, CS.vEgo) - self.output_steer = clip(self.output_steer, -steers_max, steers_max) + output_steer = clip(output_steer, -steers_max, steers_max) indi_log.active = True indi_log.rateSetPoint = float(rate_sp) @@ -141,9 +116,7 @@ class LatControlINDI(): indi_log.accelError = float(accel_error) indi_log.delayedOutput = float(self.steer_filter.x) indi_log.delta = float(delta_u) - indi_log.output = float(self.output_steer) + indi_log.output = float(output_steer) + indi_log.saturated = self._check_saturation(steers_max - abs(output_steer) < 1e-3, CS) - check_saturation = (CS.vEgo > 10.) and not CS.steeringRateLimited and not CS.steeringPressed - indi_log.saturated = self._check_saturation(self.output_steer, check_saturation, steers_max) - - return float(self.output_steer), float(steers_des), indi_log + return float(output_steer), float(steers_des), indi_log diff --git a/selfdrive/controls/lib/latcontrol_lqr.py b/selfdrive/controls/lib/latcontrol_lqr.py index 16fffac27..5c273a45b 100644 --- a/selfdrive/controls/lib/latcontrol_lqr.py +++ b/selfdrive/controls/lib/latcontrol_lqr.py @@ -5,10 +5,12 @@ from common.numpy_fast import clip from common.realtime import DT_CTRL from cereal import log from selfdrive.controls.lib.drive_helpers import get_steer_max +from selfdrive.controls.lib.latcontrol import LatControl, MIN_STEER_SPEED -class LatControlLQR(): - def __init__(self, CP): +class LatControlLQR(LatControl): + def __init__(self, CP, CI): + super().__init__(CP, CI) self.scale = CP.lateralTuning.lqr.scale self.ki = CP.lateralTuning.lqr.ki @@ -23,28 +25,13 @@ class LatControlLQR(): self.i_unwind_rate = 0.3 * DT_CTRL self.i_rate = 1.0 * DT_CTRL - self.sat_count_rate = 1.0 * DT_CTRL - self.sat_limit = CP.steerLimitTimer - self.reset() def reset(self): + super().reset() self.i_lqr = 0.0 - self.sat_count = 0.0 - def _check_saturation(self, control, check_saturation, limit): - saturated = abs(control) == limit - - if saturated and check_saturation: - self.sat_count += self.sat_count_rate - else: - self.sat_count -= self.sat_count_rate - - self.sat_count = clip(self.sat_count, 0.0, 1.0) - - return self.sat_count > self.sat_limit - - def update(self, active, CS, CP, VM, params, desired_curvature, desired_curvature_rate): + def update(self, active, CS, CP, VM, params, last_actuators, desired_curvature, desired_curvature_rate): lqr_log = log.ControlsState.LateralLQRState.new_message() steers_max = get_steer_max(CP, CS.vEgo) @@ -53,7 +40,7 @@ class LatControlLQR(): # Subtract offset. Zero angle should correspond to zero torque steering_angle_no_offset = CS.steeringAngleDeg - params.angleOffsetAverageDeg - desired_angle = math.degrees(VM.get_steer_from_curvature(-desired_curvature, CS.vEgo)) + desired_angle = math.degrees(VM.get_steer_from_curvature(-desired_curvature, CS.vEgo, params.roll)) instant_offset = params.angleOffsetDeg - params.angleOffsetAverageDeg desired_angle += instant_offset # Only add offset that originates from vehicle model errors @@ -64,7 +51,7 @@ class LatControlLQR(): e = steering_angle_no_offset - angle_steers_k self.x_hat = self.A.dot(self.x_hat) + self.B.dot(CS.steeringTorqueEps / torque_scale) + self.L.dot(e) - if CS.vEgo < 0.3 or not active: + if CS.vEgo < MIN_STEER_SPEED or not active: lqr_log.active = False lqr_output = 0. output_steer = 0. @@ -91,12 +78,9 @@ class LatControlLQR(): output_steer = lqr_output + self.i_lqr output_steer = clip(output_steer, -steers_max, steers_max) - check_saturation = (CS.vEgo > 10) and not CS.steeringRateLimited and not CS.steeringPressed - saturated = self._check_saturation(output_steer, check_saturation, steers_max) - lqr_log.steeringAngleDeg = angle_steers_k lqr_log.i = self.i_lqr lqr_log.output = output_steer lqr_log.lqrOutput = lqr_output - lqr_log.saturated = saturated + lqr_log.saturated = self._check_saturation(steers_max - abs(output_steer) < 1e-3, CS) return output_steer, desired_angle, lqr_log diff --git a/selfdrive/controls/lib/latcontrol_pid.py b/selfdrive/controls/lib/latcontrol_pid.py index c7730d011..f5ff5a95e 100644 --- a/selfdrive/controls/lib/latcontrol_pid.py +++ b/selfdrive/controls/lib/latcontrol_pid.py @@ -2,31 +2,33 @@ import math from selfdrive.controls.lib.pid import PIController from selfdrive.controls.lib.drive_helpers import get_steer_max +from selfdrive.controls.lib.latcontrol import LatControl, MIN_STEER_SPEED from cereal import log -class LatControlPID(): +class LatControlPID(LatControl): def __init__(self, CP, CI): + super().__init__(CP, CI) self.pid = PIController((CP.lateralTuning.pid.kpBP, CP.lateralTuning.pid.kpV), (CP.lateralTuning.pid.kiBP, CP.lateralTuning.pid.kiV), - k_f=CP.lateralTuning.pid.kf, pos_limit=1.0, neg_limit=-1.0, - sat_limit=CP.steerLimitTimer) + k_f=CP.lateralTuning.pid.kf, pos_limit=1.0, neg_limit=-1.0) self.get_steer_feedforward = CI.get_steer_feedforward_function() def reset(self): + super().reset() self.pid.reset() - def update(self, active, CS, CP, VM, params, desired_curvature, desired_curvature_rate): + def update(self, active, CS, CP, VM, params, last_actuators, desired_curvature, desired_curvature_rate): pid_log = log.ControlsState.LateralPIDState.new_message() pid_log.steeringAngleDeg = float(CS.steeringAngleDeg) pid_log.steeringRateDeg = float(CS.steeringRateDeg) - angle_steers_des_no_offset = math.degrees(VM.get_steer_from_curvature(-desired_curvature, CS.vEgo)) + angle_steers_des_no_offset = math.degrees(VM.get_steer_from_curvature(-desired_curvature, CS.vEgo, params.roll)) angle_steers_des = angle_steers_des_no_offset + params.angleOffsetDeg - pid_log.steeringAngleDesiredDeg = angle_steers_des + pid_log.steeringAngleDesiredDeg = angle_steers_des pid_log.angleError = angle_steers_des - CS.steeringAngleDeg - if CS.vEgo < 0.3 or not active: + if CS.vEgo < MIN_STEER_SPEED or not active: output_steer = 0.0 pid_log.active = False self.pid.reset() @@ -40,14 +42,13 @@ class LatControlPID(): deadzone = 0.0 - check_saturation = (CS.vEgo > 10) and not CS.steeringRateLimited and not CS.steeringPressed - output_steer = self.pid.update(angle_steers_des, CS.steeringAngleDeg, check_saturation=check_saturation, override=CS.steeringPressed, + output_steer = self.pid.update(angle_steers_des, CS.steeringAngleDeg, override=CS.steeringPressed, feedforward=steer_feedforward, speed=CS.vEgo, deadzone=deadzone) pid_log.active = True pid_log.p = self.pid.p pid_log.i = self.pid.i pid_log.f = self.pid.f pid_log.output = output_steer - pid_log.saturated = bool(self.pid.saturated) + pid_log.saturated = self._check_saturation(steers_max - abs(output_steer) < 1e-3, CS) return output_steer, angle_steers_des, pid_log diff --git a/selfdrive/controls/lib/lateral_mpc_lib/SConscript b/selfdrive/controls/lib/lateral_mpc_lib/SConscript index 148e4e123..f402e6e15 100644 --- a/selfdrive/controls/lib/lateral_mpc_lib/SConscript +++ b/selfdrive/controls/lib/lateral_mpc_lib/SConscript @@ -48,12 +48,13 @@ lenv.Clean(generated_files, Dir(gen)) lenv.Command(generated_files, ["lat_mpc.py"], - f"cd {Dir('.').abspath} && python lat_mpc.py") + f"cd {Dir('.').abspath} && python3 lat_mpc.py") lenv["CFLAGS"].append("-DACADOS_WITH_QPOASES") lenv["CXXFLAGS"].append("-DACADOS_WITH_QPOASES") lenv["CCFLAGS"].append("-Wno-unused") -lenv["LINKFLAGS"].append("-Wl,--disable-new-dtags") +if arch != "Darwin": + lenv["LINKFLAGS"].append("-Wl,--disable-new-dtags") lib_solver = lenv.SharedLibrary(f"{gen}/acados_ocp_solver_lat", build_files, LIBS=['m', 'acados', 'hpipm', 'blasfeo', 'qpOASES_e']) diff --git a/selfdrive/controls/lib/lateral_mpc_lib/lat_mpc.py b/selfdrive/controls/lib/lateral_mpc_lib/lat_mpc.py index 6162cf68a..eeda25627 100755 --- a/selfdrive/controls/lib/lateral_mpc_lib/lat_mpc.py +++ b/selfdrive/controls/lib/lateral_mpc_lib/lat_mpc.py @@ -3,6 +3,8 @@ import os import numpy as np from casadi import SX, vertcat, sin, cos + +from common.realtime import sec_since_boot from selfdrive.controls.lib.drive_helpers import LAT_MPC_N as N from selfdrive.controls.lib.drive_helpers import T_IDXS @@ -15,7 +17,8 @@ else: LAT_MPC_DIR = os.path.dirname(os.path.abspath(__file__)) EXPORT_DIR = os.path.join(LAT_MPC_DIR, "c_generated_code") JSON_FILE = "acados_ocp_lat.json" -X_DIM = 6 +X_DIM = 4 +P_DIM = 2 def gen_lat_model(): model = AcadosModel() @@ -26,9 +29,12 @@ def gen_lat_model(): y_ego = SX.sym('y_ego') psi_ego = SX.sym('psi_ego') curv_ego = SX.sym('curv_ego') + model.x = vertcat(x_ego, y_ego, psi_ego, curv_ego) + + # parameters v_ego = SX.sym('v_ego') rotation_radius = SX.sym('rotation_radius') - model.x = vertcat(x_ego, y_ego, psi_ego, curv_ego, v_ego, rotation_radius) + model.p = vertcat(v_ego, rotation_radius) # controls curv_rate = SX.sym('curv_rate') @@ -39,18 +45,14 @@ def gen_lat_model(): y_ego_dot = SX.sym('y_ego_dot') psi_ego_dot = SX.sym('psi_ego_dot') curv_ego_dot = SX.sym('curv_ego_dot') - v_ego_dot = SX.sym('v_ego_dot') - rotation_radius_dot = SX.sym('rotation_radius_dot') - model.xdot = vertcat(x_ego_dot, y_ego_dot, psi_ego_dot, curv_ego_dot, - v_ego_dot, rotation_radius_dot) + + model.xdot = vertcat(x_ego_dot, y_ego_dot, psi_ego_dot, curv_ego_dot) # dynamics model f_expl = vertcat(v_ego * cos(psi_ego) - rotation_radius * sin(psi_ego) * (v_ego * curv_ego), v_ego * sin(psi_ego) + rotation_radius * cos(psi_ego) * (v_ego * curv_ego), v_ego * curv_ego, - curv_rate, - 0.0, - 0.0) + curv_rate) model.f_impl_expr = model.xdot - f_expl model.f_expl_expr = f_expl return model @@ -77,8 +79,9 @@ def gen_lat_mpc_solver(): y_ego, psi_ego = ocp.model.x[1], ocp.model.x[2] curv_rate = ocp.model.u[0] - v_ego = ocp.model.x[4] + v_ego = ocp.model.p[0] + ocp.parameter_values = np.zeros((P_DIM, )) ocp.cost.yref = np.zeros((3, )) ocp.cost.yref_e = np.zeros((2, )) @@ -94,7 +97,7 @@ def gen_lat_mpc_solver(): ocp.constraints.idxbx = np.array([2,3]) ocp.constraints.ubx = np.array([np.radians(90), np.radians(50)]) ocp.constraints.lbx = np.array([-np.radians(90), -np.radians(50)]) - x0 = np.array([0.0, 0.0, 0.0, 0.0, 0.0, 0.0]) + x0 = np.zeros((X_DIM,)) ocp.constraints.x0 = x0 ocp.solver_options.qp_solver = 'PARTIAL_CONDENSING_HPIPM' @@ -102,7 +105,7 @@ def gen_lat_mpc_solver(): ocp.solver_options.integrator_type = 'ERK' ocp.solver_options.nlp_solver_type = 'SQP_RTI' ocp.solver_options.qp_solver_iter_max = 1 - ocp.solver_options.qp_solver_cond_N = N//4 + ocp.solver_options.qp_solver_cond_N = 1 # set prediction horizon ocp.solver_options.tf = Tf @@ -128,10 +131,12 @@ class LateralMpc(): # Somehow needed for stable init for i in range(N+1): self.solver.set(i, 'x', np.zeros(X_DIM)) + self.solver.set(i, 'p', np.zeros(P_DIM)) self.solver.constraints_set(0, "lbx", x0) self.solver.constraints_set(0, "ubx", x0) self.solver.solve() self.solution_status = 0 + self.solve_time = 0.0 self.cost = 0 def set_weights(self, path_weight, heading_weight, steer_rate_weight): @@ -141,17 +146,25 @@ class LateralMpc(): #TODO hacky weights to keep behavior the same self.solver.cost_set(N, 'W', (3/20.)*W[:2,:2]) - def run(self, x0, v_ego, car_rotation_radius, y_pts, heading_pts): + def run(self, x0, p, y_pts, heading_pts): x0_cp = np.copy(x0) + p_cp = np.copy(p) self.solver.constraints_set(0, "lbx", x0_cp) self.solver.constraints_set(0, "ubx", x0_cp) self.yref[:,0] = y_pts + v_ego = p_cp[0] + # rotation_radius = p_cp[1] self.yref[:,1] = heading_pts*(v_ego+5.0) for i in range(N): self.solver.cost_set(i, "yref", self.yref[i]) + self.solver.set(i, "p", p_cp) + self.solver.set(N, "p", p_cp) self.solver.cost_set(N, "yref", self.yref[N][:2]) + t = sec_since_boot() self.solution_status = self.solver.solve() + self.solve_time = sec_since_boot() - t + for i in range(N+1): self.x_sol[i] = self.solver.get(i, 'x') for i in range(N): diff --git a/selfdrive/controls/lib/lateral_planner.py b/selfdrive/controls/lib/lateral_planner.py index 0aa2359ae..a9c641139 100644 --- a/selfdrive/controls/lib/lateral_planner.py +++ b/selfdrive/controls/lib/lateral_planner.py @@ -1,4 +1,3 @@ -import math import numpy as np from common.realtime import sec_since_boot, DT_MDL from common.numpy_fast import interp @@ -6,54 +5,20 @@ from selfdrive.swaglog import cloudlog from selfdrive.controls.lib.lateral_mpc_lib.lat_mpc import LateralMpc from selfdrive.controls.lib.drive_helpers import CONTROL_N, MPC_COST_LAT, LAT_MPC_N, CAR_ROTATION_RADIUS from selfdrive.controls.lib.lane_planner import LanePlanner, TRAJECTORY_SIZE -from selfdrive.config import Conversions as CV +from selfdrive.controls.lib.desire_helper import DesireHelper import cereal.messaging as messaging from cereal import log -LaneChangeState = log.LateralPlan.LaneChangeState -LaneChangeDirection = log.LateralPlan.LaneChangeDirection - -LANE_CHANGE_SPEED_MIN = 30 * CV.MPH_TO_MS -LANE_CHANGE_TIME_MAX = 10. - -DESIRES = { - LaneChangeDirection.none: { - LaneChangeState.off: log.LateralPlan.Desire.none, - LaneChangeState.preLaneChange: log.LateralPlan.Desire.none, - LaneChangeState.laneChangeStarting: log.LateralPlan.Desire.none, - LaneChangeState.laneChangeFinishing: log.LateralPlan.Desire.none, - }, - LaneChangeDirection.left: { - LaneChangeState.off: log.LateralPlan.Desire.none, - LaneChangeState.preLaneChange: log.LateralPlan.Desire.none, - LaneChangeState.laneChangeStarting: log.LateralPlan.Desire.laneChangeLeft, - LaneChangeState.laneChangeFinishing: log.LateralPlan.Desire.laneChangeLeft, - }, - LaneChangeDirection.right: { - LaneChangeState.off: log.LateralPlan.Desire.none, - LaneChangeState.preLaneChange: log.LateralPlan.Desire.none, - LaneChangeState.laneChangeStarting: log.LateralPlan.Desire.laneChangeRight, - LaneChangeState.laneChangeFinishing: log.LateralPlan.Desire.laneChangeRight, - }, -} - class LateralPlanner: def __init__(self, CP, use_lanelines=True, wide_camera=False): self.use_lanelines = use_lanelines self.LP = LanePlanner(wide_camera) + self.DH = DesireHelper() self.last_cloudlog_t = 0 self.steer_rate_cost = CP.steerRateCost - self.solution_invalid_cnt = 0 - self.lane_change_state = LaneChangeState.off - self.lane_change_direction = LaneChangeDirection.none - self.lane_change_timer = 0.0 - self.lane_change_ll_prob = 1.0 - self.keep_pulse_timer = 0.0 - self.prev_one_blinker = False - self.desire = log.LateralPlan.Desire.none self.path_xyz = np.zeros((TRAJECTORY_SIZE, 3)) self.path_xyz_stds = np.ones((TRAJECTORY_SIZE, 3)) @@ -62,19 +27,19 @@ class LateralPlanner: self.y_pts = np.zeros(TRAJECTORY_SIZE) self.lat_mpc = LateralMpc() - self.reset_mpc(np.zeros(6)) + self.reset_mpc(np.zeros(4)) - def reset_mpc(self, x0=np.zeros(6)): + def reset_mpc(self, x0=np.zeros(4)): self.x0 = x0 self.lat_mpc.reset(x0=self.x0) def update(self, sm): v_ego = sm['carState'].vEgo - active = sm['controlsState'].active measured_curvature = sm['controlsState'].curvature + # Parse model predictions md = sm['modelV2'] - self.LP.parse_model(sm['modelV2']) + self.LP.parse_model(md) if len(md.position.x) == TRAJECTORY_SIZE and len(md.orientation.x) == TRAJECTORY_SIZE: self.path_xyz = np.column_stack([md.position.x, md.position.y, md.position.z]) self.t_idxs = np.array(md.position.t) @@ -83,84 +48,15 @@ class LateralPlanner: self.path_xyz_stds = np.column_stack([md.position.xStd, md.position.yStd, md.position.zStd]) # Lane change logic - one_blinker = sm['carState'].leftBlinker != sm['carState'].rightBlinker - below_lane_change_speed = v_ego < LANE_CHANGE_SPEED_MIN - - if (not active) or (self.lane_change_timer > LANE_CHANGE_TIME_MAX): - self.lane_change_state = LaneChangeState.off - self.lane_change_direction = LaneChangeDirection.none - else: - # LaneChangeState.off - if self.lane_change_state == LaneChangeState.off and one_blinker and not self.prev_one_blinker and not below_lane_change_speed: - self.lane_change_state = LaneChangeState.preLaneChange - self.lane_change_ll_prob = 1.0 - - # LaneChangeState.preLaneChange - elif self.lane_change_state == LaneChangeState.preLaneChange: - # Set lane change direction - if sm['carState'].leftBlinker: - self.lane_change_direction = LaneChangeDirection.left - elif sm['carState'].rightBlinker: - self.lane_change_direction = LaneChangeDirection.right - else: # If there are no blinkers we will go back to LaneChangeState.off - self.lane_change_direction = LaneChangeDirection.none - - torque_applied = sm['carState'].steeringPressed and \ - ((sm['carState'].steeringTorque > 0 and self.lane_change_direction == LaneChangeDirection.left) or - (sm['carState'].steeringTorque < 0 and self.lane_change_direction == LaneChangeDirection.right)) - - blindspot_detected = ((sm['carState'].leftBlindspot and self.lane_change_direction == LaneChangeDirection.left) or - (sm['carState'].rightBlindspot and self.lane_change_direction == LaneChangeDirection.right)) - - if not one_blinker or below_lane_change_speed: - self.lane_change_state = LaneChangeState.off - elif torque_applied and not blindspot_detected: - self.lane_change_state = LaneChangeState.laneChangeStarting - - # LaneChangeState.laneChangeStarting - elif self.lane_change_state == LaneChangeState.laneChangeStarting: - # fade out over .5s - self.lane_change_ll_prob = max(self.lane_change_ll_prob - 2 * DT_MDL, 0.0) - - # 98% certainty - lane_change_prob = self.LP.l_lane_change_prob + self.LP.r_lane_change_prob - if lane_change_prob < 0.02 and self.lane_change_ll_prob < 0.01: - self.lane_change_state = LaneChangeState.laneChangeFinishing - - # LaneChangeState.laneChangeFinishing - elif self.lane_change_state == LaneChangeState.laneChangeFinishing: - # fade in laneline over 1s - self.lane_change_ll_prob = min(self.lane_change_ll_prob + DT_MDL, 1.0) - if self.lane_change_ll_prob > 0.99: - self.lane_change_direction = LaneChangeDirection.none - if one_blinker: - self.lane_change_state = LaneChangeState.preLaneChange - else: - self.lane_change_state = LaneChangeState.off - - if self.lane_change_state in [LaneChangeState.off, LaneChangeState.preLaneChange]: - self.lane_change_timer = 0.0 - else: - self.lane_change_timer += DT_MDL - - self.prev_one_blinker = one_blinker - - self.desire = DESIRES[self.lane_change_direction][self.lane_change_state] - - # Send keep pulse once per second during LaneChangeStart.preLaneChange - if self.lane_change_state in [LaneChangeState.off, LaneChangeState.laneChangeStarting]: - self.keep_pulse_timer = 0.0 - elif self.lane_change_state == LaneChangeState.preLaneChange: - self.keep_pulse_timer += DT_MDL - if self.keep_pulse_timer > 1.0: - self.keep_pulse_timer = 0.0 - elif self.desire in [log.LateralPlan.Desire.keepLeft, log.LateralPlan.Desire.keepRight]: - self.desire = log.LateralPlan.Desire.none + lane_change_prob = self.LP.l_lane_change_prob + self.LP.r_lane_change_prob + self.DH.update(sm['carState'], sm['controlsState'].active, lane_change_prob) # Turn off lanes during lane change - if self.desire == log.LateralPlan.Desire.laneChangeRight or self.desire == log.LateralPlan.Desire.laneChangeLeft: - self.LP.lll_prob *= self.lane_change_ll_prob - self.LP.rll_prob *= self.lane_change_ll_prob + if self.DH.desire == log.LateralPlan.Desire.laneChangeRight or self.DH.desire == log.LateralPlan.Desire.laneChangeLeft: + self.LP.lll_prob *= self.DH.lane_change_ll_prob + self.LP.rll_prob *= self.DH.lane_change_ll_prob + + # Calculate final driving path and set MPC costs if self.use_lanelines: d_path_xyz = self.LP.get_d_path(v_ego, self.t_idxs, self.path_xyz) self.lat_mpc.set_weights(MPC_COST_LAT.PATH, MPC_COST_LAT.HEADING, self.steer_rate_cost) @@ -170,23 +66,24 @@ class LateralPlanner: # Heading cost is useful at low speed, otherwise end of plan can be off-heading heading_cost = interp(v_ego, [5.0, 10.0], [MPC_COST_LAT.HEADING, 0.0]) self.lat_mpc.set_weights(path_cost, heading_cost, self.steer_rate_cost) + y_pts = np.interp(v_ego * self.t_idxs[:LAT_MPC_N + 1], np.linalg.norm(d_path_xyz, axis=1), d_path_xyz[:, 1]) heading_pts = np.interp(v_ego * self.t_idxs[:LAT_MPC_N + 1], np.linalg.norm(self.path_xyz, axis=1), self.plan_yaw) self.y_pts = y_pts assert len(y_pts) == LAT_MPC_N + 1 assert len(heading_pts) == LAT_MPC_N + 1 - self.x0[4] = v_ego + # self.x0[4] = v_ego + p = np.array([v_ego, CAR_ROTATION_RADIUS]) self.lat_mpc.run(self.x0, - v_ego, - CAR_ROTATION_RADIUS, + p, y_pts, heading_pts) # init state for next self.x0[3] = interp(DT_MDL, self.t_idxs[:LAT_MPC_N + 1], self.lat_mpc.x_sol[:, 3]) # Check for infeasible MPC solution - mpc_nans = any(math.isnan(x) for x in self.lat_mpc.x_sol[:, 3]) + mpc_nans = np.isnan(self.lat_mpc.x_sol[:, 3]).any() t = sec_since_boot() if mpc_nans or self.lat_mpc.solution_status != 0: self.reset_mpc() @@ -204,20 +101,23 @@ class LateralPlanner: plan_solution_valid = self.solution_invalid_cnt < 2 plan_send = messaging.new_message('lateralPlan') plan_send.valid = sm.all_alive_and_valid(service_list=['carState', 'controlsState', 'modelV2']) - plan_send.lateralPlan.laneWidth = float(self.LP.lane_width) - plan_send.lateralPlan.dPathPoints = [float(x) for x in self.y_pts] - plan_send.lateralPlan.psis = [float(x) for x in self.lat_mpc.x_sol[0:CONTROL_N, 2]] - plan_send.lateralPlan.curvatures = [float(x) for x in self.lat_mpc.x_sol[0:CONTROL_N, 3]] - plan_send.lateralPlan.curvatureRates = [float(x) for x in self.lat_mpc.u_sol[0:CONTROL_N - 1]] + [0.0] - plan_send.lateralPlan.lProb = float(self.LP.lll_prob) - plan_send.lateralPlan.rProb = float(self.LP.rll_prob) - plan_send.lateralPlan.dProb = float(self.LP.d_prob) - plan_send.lateralPlan.mpcSolutionValid = bool(plan_solution_valid) + lateralPlan = plan_send.lateralPlan + lateralPlan.laneWidth = float(self.LP.lane_width) + lateralPlan.dPathPoints = self.y_pts.tolist() + lateralPlan.psis = self.lat_mpc.x_sol[0:CONTROL_N, 2].tolist() + lateralPlan.curvatures = self.lat_mpc.x_sol[0:CONTROL_N, 3].tolist() + lateralPlan.curvatureRates = [float(x) for x in self.lat_mpc.u_sol[0:CONTROL_N - 1]] + [0.0] + lateralPlan.lProb = float(self.LP.lll_prob) + lateralPlan.rProb = float(self.LP.rll_prob) + lateralPlan.dProb = float(self.LP.d_prob) - plan_send.lateralPlan.desire = self.desire - plan_send.lateralPlan.useLaneLines = self.use_lanelines - plan_send.lateralPlan.laneChangeState = self.lane_change_state - plan_send.lateralPlan.laneChangeDirection = self.lane_change_direction + lateralPlan.mpcSolutionValid = bool(plan_solution_valid) + lateralPlan.solverExecutionTime = self.lat_mpc.solve_time + + lateralPlan.desire = self.DH.desire + lateralPlan.useLaneLines = self.use_lanelines + lateralPlan.laneChangeState = self.DH.lane_change_state + lateralPlan.laneChangeDirection = self.DH.lane_change_direction pm.send('lateralPlan', plan_send) diff --git a/selfdrive/controls/lib/longcontrol.py b/selfdrive/controls/lib/longcontrol.py index beacc518d..21c34aa2d 100644 --- a/selfdrive/controls/lib/longcontrol.py +++ b/selfdrive/controls/lib/longcontrol.py @@ -7,21 +7,17 @@ from selfdrive.modeld.constants import T_IDXS LongCtrlState = car.CarControl.Actuators.LongControlState -STOPPING_TARGET_SPEED_OFFSET = 0.01 - # As per ISO 15622:2018 for all speeds ACCEL_MIN_ISO = -3.5 # m/s^2 ACCEL_MAX_ISO = 2.0 # m/s^2 -def long_control_state_trans(CP, active, long_control_state, v_ego, v_target_future, v_pid, - output_accel, brake_pressed, cruise_standstill, min_speed_can): +def long_control_state_trans(CP, active, long_control_state, v_ego, v_target_future, + brake_pressed, cruise_standstill): """Update longitudinal control state machine""" - stopping_target_speed = min_speed_can + STOPPING_TARGET_SPEED_OFFSET stopping_condition = (v_ego < 2.0 and cruise_standstill) or \ (v_ego < CP.vEgoStopping and - ((v_pid < stopping_target_speed and v_target_future < stopping_target_speed) or - brake_pressed)) + (v_target_future < CP.vEgoStopping or brake_pressed)) starting_condition = v_target_future > CP.vEgoStarting and not cruise_standstill @@ -30,8 +26,7 @@ def long_control_state_trans(CP, active, long_control_state, v_ego, v_target_fut else: if long_control_state == LongCtrlState.off: - if active: - long_control_state = LongCtrlState.pid + long_control_state = LongCtrlState.pid elif long_control_state == LongCtrlState.pid: if stopping_condition: @@ -39,12 +34,6 @@ def long_control_state_trans(CP, active, long_control_state, v_ego, v_target_fut elif long_control_state == LongCtrlState.stopping: if starting_condition: - long_control_state = LongCtrlState.starting - - elif long_control_state == LongCtrlState.starting: - if stopping_condition: - long_control_state = LongCtrlState.stopping - elif output_accel >= CP.startAccel: long_control_state = LongCtrlState.pid return long_control_state @@ -55,8 +44,7 @@ class LongControl(): self.long_control_state = LongCtrlState.off # initialized to off self.pid = PIController((CP.longitudinalTuning.kpBP, CP.longitudinalTuning.kpV), (CP.longitudinalTuning.kiBP, CP.longitudinalTuning.kiV), - rate=1/DT_CTRL, - sat_limit=0.8) + rate=1 / DT_CTRL) self.v_pid = 0.0 self.last_output_accel = 0.0 @@ -69,16 +57,19 @@ class LongControl(): """Update longitudinal control. This updates the state machine and runs a PID loop""" # Interp control trajectory # TODO estimate car specific lag, use .15s for now - if len(long_plan.speeds) == CONTROL_N: - v_target_lower = interp(CP.longitudinalActuatorDelayLowerBound, T_IDXS[:CONTROL_N], long_plan.speeds) - a_target_lower = 2 * (v_target_lower - long_plan.speeds[0])/CP.longitudinalActuatorDelayLowerBound - long_plan.accels[0] + speeds = long_plan.speeds + if len(speeds) == CONTROL_N: + v_target_lower = interp(CP.longitudinalActuatorDelayLowerBound, T_IDXS[:CONTROL_N], speeds) + a_target_lower = 2 * (v_target_lower - speeds[0])/CP.longitudinalActuatorDelayLowerBound - long_plan.accels[0] - v_target_upper = interp(CP.longitudinalActuatorDelayUpperBound, T_IDXS[:CONTROL_N], long_plan.speeds) - a_target_upper = 2 * (v_target_upper - long_plan.speeds[0])/CP.longitudinalActuatorDelayUpperBound - long_plan.accels[0] + v_target_upper = interp(CP.longitudinalActuatorDelayUpperBound, T_IDXS[:CONTROL_N], speeds) + a_target_upper = 2 * (v_target_upper - speeds[0])/CP.longitudinalActuatorDelayUpperBound - long_plan.accels[0] a_target = min(a_target_lower, a_target_upper) - v_target_future = long_plan.speeds[-1] + v_target = speeds[0] + v_target_future = speeds[-1] else: + v_target = 0.0 v_target_future = 0.0 a_target = 0.0 @@ -91,8 +82,8 @@ class LongControl(): # Update state machine output_accel = self.last_output_accel self.long_control_state = long_control_state_trans(CP, active, self.long_control_state, CS.vEgo, - v_target_future, self.v_pid, output_accel, - CS.brakePressed, CS.cruiseState.standstill, CP.minSpeedCan) + v_target_future, CS.brakePressed, + CS.cruiseState.standstill) if self.long_control_state == LongCtrlState.off or CS.gasPressed: self.reset(CS.vEgo) @@ -100,7 +91,7 @@ class LongControl(): # tracking objects and driving elif self.long_control_state == LongCtrlState.pid: - self.v_pid = long_plan.speeds[0] + self.v_pid = v_target # Toyota starts braking more when it thinks you want to stop # Freeze the integrator so we don't accelerate to compensate, and don't allow positive acceleration @@ -119,13 +110,6 @@ class LongControl(): if not CS.standstill or output_accel > CP.stopAccel: output_accel -= CP.stoppingDecelRate * DT_CTRL output_accel = clip(output_accel, accel_limits[0], accel_limits[1]) - - self.reset(CS.vEgo) - - # Intention is to move again, release brake fast before handing control to PID - elif self.long_control_state == LongCtrlState.starting: - if output_accel < CP.startAccel: - output_accel += CP.startingAccelRate * DT_CTRL self.reset(CS.vEgo) self.last_output_accel = output_accel diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/SConscript b/selfdrive/controls/lib/longitudinal_mpc_lib/SConscript index 4abe90f8f..4c43985d1 100644 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/SConscript +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/SConscript @@ -58,12 +58,13 @@ lenv.Clean(generated_files, Dir(gen)) lenv.Command(generated_files, ["long_mpc.py"], - f"cd {Dir('.').abspath} && python long_mpc.py") + f"cd {Dir('.').abspath} && python3 long_mpc.py") lenv["CFLAGS"].append("-DACADOS_WITH_QPOASES") lenv["CXXFLAGS"].append("-DACADOS_WITH_QPOASES") lenv["CCFLAGS"].append("-Wno-unused") -lenv["LINKFLAGS"].append("-Wl,--disable-new-dtags") +if arch != "Darwin": + lenv["LINKFLAGS"].append("-Wl,--disable-new-dtags") lib_solver = lenv.SharedLibrary(f"{gen}/acados_ocp_solver_long", build_files, LIBS=['m', 'acados', 'hpipm', 'blasfeo', 'qpOASES_e']) diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py b/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py index e0e0208d6..8625df745 100644 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/long_mpc.py @@ -40,7 +40,7 @@ CRASH_DISTANCE = .5 LIMIT_COST = 1e6 -# Less timestamps doesn't hurt performance and leads to +# Fewer timestamps don't hurt performance and lead to # much better convergence of the MPC with low iterations N = 12 MAX_T = 10.0 @@ -84,9 +84,9 @@ def gen_long_model(): model.xdot = vertcat(x_ego_dot, v_ego_dot, a_ego_dot) # live parameters - x_obstacle = SX.sym('x_obstacle') a_min = SX.sym('a_min') a_max = SX.sym('a_max') + x_obstacle = SX.sym('x_obstacle') prev_a = SX.sym('prev_a') model.p = vertcat(a_min, a_max, x_obstacle, prev_a) @@ -143,8 +143,8 @@ def gen_long_mpc_solver(): # Constraints on speed, acceleration and desired distance to # the obstacle, which is treated as a slack constraint so it - # behaves like an assymetrical cost. - constraints = vertcat((v_ego), + # behaves like an asymmetrical cost. + constraints = vertcat(v_ego, (a_ego - a_min), (a_max - a_ego), ((x_obstacle - x_ego) - (3/4) * (desired_dist_comfort)) / (v_ego + 10.)) @@ -169,7 +169,7 @@ def gen_long_mpc_solver(): ocp.constraints.idxsh = np.arange(CONSTR_DIM) # The HPIPM solver can give decent solutions even when it is stopped early - # Which is critical for our purpose where the compute time is strictly bounded + # Which is critical for our purpose where compute time is strictly bounded # We use HPIPM in the SPEED_ABS mode, which ensures fastest runtime. This # does not cause issues since the problem is well bounded. ocp.solver_options.qp_solver = 'PARTIAL_CONDENSING_HPIPM' @@ -190,21 +190,18 @@ def gen_long_mpc_solver(): return ocp -class LongitudinalMpc(): +class LongitudinalMpc: def __init__(self, e2e=False): self.e2e = e2e self.reset() - self.accel_limit_arr = np.zeros((N+1, 2)) - self.accel_limit_arr[:,0] = -1.2 - self.accel_limit_arr[:,1] = 1.2 self.source = SOURCES[2] def reset(self): self.solver = AcadosOcpSolverFast('long', N, EXPORT_DIR) - self.v_solution = [0.0 for i in range(N+1)] - self.a_solution = [0.0 for i in range(N+1)] + self.v_solution = np.zeros(N+1) + self.a_solution = np.zeros(N+1) self.prev_a = np.array(self.a_solution) - self.j_solution = [0.0 for i in range(N)] + self.j_solution = np.zeros(N) self.yref = np.zeros((N+1, COST_DIM)) for i in range(N): self.solver.cost_set(i, "yref", self.yref[i]) @@ -218,12 +215,16 @@ class LongitudinalMpc(): self.status = False self.crash_cnt = 0.0 self.solution_status = 0 + self.solve_time = 0.0 self.x0 = np.zeros(X_DIM) self.set_weights() def set_weights(self): if self.e2e: self.set_weights_for_xva_policy() + self.params[:,0] = -10. + self.params[:,1] = 10. + self.params[:,2] = 1e5 else: self.set_weights_for_lead_policy() @@ -264,7 +265,8 @@ class LongitudinalMpc(): self.x0[1] = v self.x0[2] = a - def extrapolate_lead(self, x_lead, v_lead, a_lead, a_lead_tau): + @staticmethod + def extrapolate_lead(x_lead, v_lead, a_lead, a_lead_tau): a_lead_traj = a_lead * np.exp(-a_lead_tau * (T_IDXS**2)/2.) v_lead_traj = np.clip(v_lead + np.cumsum(T_DIFFS * a_lead_traj), 0.0, 1e8) x_lead_traj = x_lead + np.cumsum(T_DIFFS * v_lead_traj) @@ -347,21 +349,19 @@ class LongitudinalMpc(): for i in range(N): self.solver.cost_set(i, "yref", self.yref[i]) self.solver.cost_set(N, "yref", self.yref[N][:COST_E_DIM]) - self.accel_limit_arr[:,0] = -10. - self.accel_limit_arr[:,1] = 10. - x_obstacle = 1e5*np.ones((N+1)) - self.params = np.concatenate([self.accel_limit_arr, - x_obstacle[:,None], - self.prev_a[:,None]], axis=1) + self.params[:,3] = np.copy(self.prev_a) self.run() - def run(self): for i in range(N+1): self.solver.set(i, 'p', self.params[i]) self.solver.constraints_set(0, "lbx", self.x0) self.solver.constraints_set(0, "ubx", self.x0) + + t = sec_since_boot() self.solution_status = self.solver.solve() + self.solve_time = sec_since_boot() - t + for i in range(N+1): self.x_sol[i] = self.solver.get(i, 'x') for i in range(N): @@ -373,12 +373,10 @@ class LongitudinalMpc(): self.prev_a = np.interp(T_IDXS + 0.05, T_IDXS, self.a_solution) - t = sec_since_boot() if self.solution_status != 0: if t > self.last_cloudlog_t + 5.0: self.last_cloudlog_t = t - cloudlog.warning("Long mpc reset, solution_status: %s" % ( - self.solution_status)) + cloudlog.warning(f"Long mpc reset, solution_status: {self.solution_status}") self.reset() diff --git a/selfdrive/controls/lib/longitudinal_planner.py b/selfdrive/controls/lib/longitudinal_planner.py index 41bae4c47..8c7940405 100755 --- a/selfdrive/controls/lib/longitudinal_planner.py +++ b/selfdrive/controls/lib/longitudinal_planner.py @@ -4,6 +4,7 @@ import numpy as np from common.numpy_fast import interp import cereal.messaging as messaging +from common.filter_simple import FirstOrderFilter from common.realtime import DT_MDL from selfdrive.modeld.constants import T_IDXS from selfdrive.config import Conversions as CV @@ -48,9 +49,8 @@ class Planner: self.fcw = False - self.v_desired = init_v self.a_desired = init_a - self.alpha = np.exp(-DT_MDL / 2.0) + self.v_desired_filter = FirstOrderFilter(init_v, 2.0, DT_MDL) self.v_desired_trajectory = np.zeros(CONTROL_N) self.a_desired_trajectory = np.zeros(CONTROL_N) @@ -69,14 +69,13 @@ class Planner: prev_accel_constraint = True if long_control_state == LongCtrlState.off or sm['carState'].gasPressed: - self.v_desired = v_ego + self.v_desired_filter.x = v_ego self.a_desired = a_ego # Smoothly changing between accel trajectory is only relevant when OP is driving prev_accel_constraint = False # Prevent divergence, smooth in current v_ego - self.v_desired = self.alpha * self.v_desired + (1 - self.alpha) * v_ego - self.v_desired = max(0.0, self.v_desired) + self.v_desired_filter.x = max(0.0, self.v_desired_filter.update(v_ego)) accel_limits = [A_CRUISE_MIN, get_max_accel(v_ego)] accel_limits_turns = limit_accel_in_turns(v_ego, sm['carState'].steeringAngleDeg, accel_limits, self.CP) @@ -88,7 +87,7 @@ class Planner: accel_limits_turns[0] = min(accel_limits_turns[0], self.a_desired + 0.05) accel_limits_turns[1] = max(accel_limits_turns[1], self.a_desired - 0.05) self.mpc.set_accel_limits(accel_limits_turns[0], accel_limits_turns[1]) - self.mpc.set_cur_state(self.v_desired, self.a_desired) + self.mpc.set_cur_state(self.v_desired_filter.x, self.a_desired) self.mpc.update(sm['carState'], sm['radarState'], v_cruise, prev_accel_constraint=prev_accel_constraint) self.v_desired_trajectory = np.interp(T_IDXS[:CONTROL_N], T_IDXS_MPC, self.mpc.v_solution) self.a_desired_trajectory = np.interp(T_IDXS[:CONTROL_N], T_IDXS_MPC, self.mpc.a_solution) @@ -102,7 +101,7 @@ class Planner: # Interpolate 0.05 seconds and save as starting point for next iteration a_prev = self.a_desired self.a_desired = float(interp(DT_MDL, T_IDXS[:CONTROL_N], self.a_desired_trajectory)) - self.v_desired = self.v_desired + DT_MDL * (self.a_desired + a_prev) / 2.0 + self.v_desired_filter.x = self.v_desired_filter.x + DT_MDL * (self.a_desired + a_prev) / 2.0 def publish(self, sm, pm): plan_send = messaging.new_message('longitudinalPlan') @@ -113,12 +112,14 @@ class Planner: longitudinalPlan.modelMonoTime = sm.logMonoTime['modelV2'] longitudinalPlan.processingDelay = (plan_send.logMonoTime / 1e9) - sm.logMonoTime['modelV2'] - longitudinalPlan.speeds = [float(x) for x in self.v_desired_trajectory] - longitudinalPlan.accels = [float(x) for x in self.a_desired_trajectory] - longitudinalPlan.jerks = [float(x) for x in self.j_desired_trajectory] + longitudinalPlan.speeds = self.v_desired_trajectory.tolist() + longitudinalPlan.accels = self.a_desired_trajectory.tolist() + longitudinalPlan.jerks = self.j_desired_trajectory.tolist() longitudinalPlan.hasLead = sm['radarState'].leadOne.status longitudinalPlan.longitudinalPlanSource = self.mpc.source longitudinalPlan.fcw = self.fcw + longitudinalPlan.solverExecutionTime = self.mpc.solve_time + pm.send('longitudinalPlan', plan_send) diff --git a/selfdrive/controls/lib/pid.py b/selfdrive/controls/lib/pid.py index e384aaaed..28c643819 100644 --- a/selfdrive/controls/lib/pid.py +++ b/selfdrive/controls/lib/pid.py @@ -13,7 +13,7 @@ def apply_deadzone(error, deadzone): return error class PIController(): - def __init__(self, k_p, k_i, k_f=1., pos_limit=None, neg_limit=None, rate=100, sat_limit=0.8): + def __init__(self, k_p, k_i, k_f=1., pos_limit=None, neg_limit=None, rate=100): self._k_p = k_p # proportional gain self._k_i = k_i # integral gain self.k_f = k_f # feedforward gain @@ -25,10 +25,8 @@ class PIController(): self.pos_limit = pos_limit self.neg_limit = neg_limit - self.sat_count_rate = 1.0 / rate self.i_unwind_rate = 0.3 / rate self.i_rate = 1.0 / rate - self.sat_limit = sat_limit self.reset() @@ -40,27 +38,13 @@ class PIController(): def k_i(self): return interp(self.speed, self._k_i[0], self._k_i[1]) - def _check_saturation(self, control, check_saturation, error): - saturated = (control < self.neg_limit) or (control > self.pos_limit) - - if saturated and check_saturation and abs(error) > 0.1: - self.sat_count += self.sat_count_rate - else: - self.sat_count -= self.sat_count_rate - - self.sat_count = clip(self.sat_count, 0.0, 1.0) - - return self.sat_count > self.sat_limit - def reset(self): self.p = 0.0 self.i = 0.0 self.f = 0.0 - self.sat_count = 0.0 - self.saturated = False self.control = 0 - def update(self, setpoint, measurement, speed=0.0, check_saturation=True, override=False, feedforward=0., deadzone=0., freeze_integrator=False): + def update(self, setpoint, measurement, speed=0.0, override=False, feedforward=0., deadzone=0., freeze_integrator=False): self.speed = speed error = float(apply_deadzone(setpoint - measurement, deadzone)) @@ -81,7 +65,6 @@ class PIController(): self.i = i control = self.p + self.f + self.i - self.saturated = self._check_saturation(control, check_saturation, error) self.control = clip(control, self.neg_limit, self.pos_limit) return self.control diff --git a/selfdrive/controls/lib/radar_helpers.py b/selfdrive/controls/lib/radar_helpers.py index 01498fa13..4f87fdf09 100644 --- a/selfdrive/controls/lib/radar_helpers.py +++ b/selfdrive/controls/lib/radar_helpers.py @@ -146,7 +146,7 @@ class Cluster(): } def __str__(self): - ret = "x: %4.1f y: %4.1f v: %4.1f a: %4.1f" % (self.dRel, self.yRel, self.vRel, self.aLeadK) + ret = f"x: {self.dRel:4.1f} y: {self.yRel:4.1f} v: {self.vRel:4.1f} a: {self.aLeadK:4.1f}" return ret def potential_low_speed_lead(self, v_ego): diff --git a/selfdrive/controls/lib/vehicle_model.py b/selfdrive/controls/lib/vehicle_model.py index a0b1dddfd..3f180d325 100755 --- a/selfdrive/controls/lib/vehicle_model.py +++ b/selfdrive/controls/lib/vehicle_model.py @@ -5,7 +5,7 @@ Dynamic bicycle model from "The Science of Vehicle Dynamics (2014), M. Guiggiani The state is x = [v, r]^T with v lateral speed [m/s], and r rotational speed [rad/s] -The input u is the steering angle [rad] +The input u is the steering angle [rad], and roll [rad] The system is defined by x_dot = A*x + B*u @@ -19,6 +19,9 @@ from numpy.linalg import solve from cereal import car +ACCELERATION_DUE_TO_GRAVITY = 9.8 + + class VehicleModel: def __init__(self, CP: car.CarParams): """ @@ -43,7 +46,7 @@ class VehicleModel: self.cR = stiffness_factor * self.cR_orig self.sR = steer_ratio - def steady_state_sol(self, sa: float, u: float) -> np.ndarray: + def steady_state_sol(self, sa: float, u: float, roll: float) -> np.ndarray: """Returns the steady state solution. If the speed is too low we can't use the dynamic model (tire slip is undefined), @@ -52,26 +55,28 @@ class VehicleModel: Args: sa: Steering wheel angle [rad] u: Speed [m/s] + roll: Road Roll [rad] Returns: 2x1 matrix with steady state solution (lateral speed, rotational speed) """ if u > 0.1: - return dyn_ss_sol(sa, u, self) + return dyn_ss_sol(sa, u, roll, self) else: return kin_ss_sol(sa, u, self) - def calc_curvature(self, sa: float, u: float) -> float: + def calc_curvature(self, sa: float, u: float, roll: float) -> float: """Returns the curvature. Multiplied by the speed this will give the yaw rate. Args: sa: Steering wheel angle [rad] u: Speed [m/s] + roll: Road Roll [rad] Returns: Curvature factor [1/m] """ - return self.curvature_factor(u) * sa / self.sR + return (self.curvature_factor(u) * sa / self.sR) + self.roll_compensation(roll, u) def curvature_factor(self, u: float) -> float: """Returns the curvature factor. @@ -86,43 +91,63 @@ class VehicleModel: sf = calc_slip_factor(self) return (1. - self.chi) / (1. - sf * u**2) / self.l - def get_steer_from_curvature(self, curv: float, u: float) -> float: + def get_steer_from_curvature(self, curv: float, u: float, roll: float) -> float: """Calculates the required steering wheel angle for a given curvature Args: curv: Desired curvature [1/m] u: Speed [m/s] + roll: Road Roll [rad] Returns: Steering wheel angle [rad] """ - return curv * self.sR * 1.0 / self.curvature_factor(u) + return (curv - self.roll_compensation(roll, u)) * self.sR * 1.0 / self.curvature_factor(u) - def get_steer_from_yaw_rate(self, yaw_rate: float, u: float) -> float: + def roll_compensation(self, roll: float, u: float) -> float: + """Calculates the roll-compensation to curvature + + Args: + roll: Road Roll [rad] + u: Speed [m/s] + + Returns: + Roll compensation curvature [rad] + """ + sf = calc_slip_factor(self) + + if abs(sf) < 1e-6: + return 0 + else: + return (ACCELERATION_DUE_TO_GRAVITY * roll) / ((1 / sf) - u**2) + + def get_steer_from_yaw_rate(self, yaw_rate: float, u: float, roll: float) -> float: """Calculates the required steering wheel angle for a given yaw_rate Args: yaw_rate: Desired yaw rate [rad/s] u: Speed [m/s] + roll: Road Roll [rad] Returns: Steering wheel angle [rad] """ curv = yaw_rate / u - return self.get_steer_from_curvature(curv, u) + return self.get_steer_from_curvature(curv, u, roll) - def yaw_rate(self, sa: float, u: float) -> float: + def yaw_rate(self, sa: float, u: float, roll: float) -> float: """Calculate yaw rate Args: sa: Steering wheel angle [rad] u: Speed [m/s] + roll: Road Roll [rad] Returns: Yaw rate [rad/s] """ - return self.calc_curvature(sa, u) * u + return self.calc_curvature(sa, u, roll) * u def kin_ss_sol(sa: float, u: float, VM: VehicleModel) -> np.ndarray: @@ -152,7 +177,7 @@ def create_dyn_state_matrices(u: float, VM: VehicleModel) -> Tuple[np.ndarray, n VM: Vehicle model Returns: - A tuple with the 2x2 A matrix, and 2x1 B matrix + A tuple with the 2x2 A matrix, and 2x2 B matrix Parameters in the vehicle model: cF: Tire stiffness Front [N/rad] @@ -165,30 +190,38 @@ def create_dyn_state_matrices(u: float, VM: VehicleModel) -> Tuple[np.ndarray, n chi: Steer ratio rear [-] """ A = np.zeros((2, 2)) - B = np.zeros((2, 1)) + B = np.zeros((2, 2)) A[0, 0] = - (VM.cF + VM.cR) / (VM.m * u) A[0, 1] = - (VM.cF * VM.aF - VM.cR * VM.aR) / (VM.m * u) - u A[1, 0] = - (VM.cF * VM.aF - VM.cR * VM.aR) / (VM.j * u) A[1, 1] = - (VM.cF * VM.aF**2 + VM.cR * VM.aR**2) / (VM.j * u) + + # Steering input B[0, 0] = (VM.cF + VM.chi * VM.cR) / VM.m / VM.sR B[1, 0] = (VM.cF * VM.aF - VM.chi * VM.cR * VM.aR) / VM.j / VM.sR + + # Roll input + B[0, 1] = -ACCELERATION_DUE_TO_GRAVITY + return A, B -def dyn_ss_sol(sa: float, u: float, VM: VehicleModel) -> np.ndarray: +def dyn_ss_sol(sa: float, u: float, roll: float, VM: VehicleModel) -> np.ndarray: """Calculate the steady state solution when x_dot = 0, Ax + Bu = 0 => x = -A^{-1} B u Args: sa: Steering angle [rad] u: Speed [m/s] + roll: Road Roll [rad] VM: Vehicle model Returns: 2x1 matrix with steady state solution """ A, B = create_dyn_state_matrices(u, VM) - return -solve(A, B) * sa + inp = np.array([[sa], [roll]]) + return -solve(A, B) @ inp def calc_slip_factor(VM): diff --git a/selfdrive/controls/radard.py b/selfdrive/controls/radard.py index 88f39ce43..65f8480c7 100755 --- a/selfdrive/controls/radard.py +++ b/selfdrive/controls/radard.py @@ -135,7 +135,7 @@ class RadarD(): self.tracks[ids].update(rpt[0], rpt[1], rpt[2], v_lead, rpt[3]) idens = list(sorted(self.tracks.keys())) - track_pts = list([self.tracks[iden].get_key_for_cluster() for iden in idens]) + track_pts = [self.tracks[iden].get_key_for_cluster() for iden in idens] # If we have multiple points, cluster them if len(track_pts) > 1: @@ -172,9 +172,10 @@ class RadarD(): radarState.carStateMonoTime = sm.logMonoTime['carState'] if enable_lead: - if len(sm['modelV2'].leadsV3) > 1: - radarState.leadOne = get_lead(self.v_ego, self.ready, clusters, sm['modelV2'].leadsV3[0], low_speed_override=True) - radarState.leadTwo = get_lead(self.v_ego, self.ready, clusters, sm['modelV2'].leadsV3[1], low_speed_override=False) + leads_v3 = sm['modelV2'].leadsV3 + if len(leads_v3) > 1: + radarState.leadOne = get_lead(self.v_ego, self.ready, clusters, leads_v3[0], low_speed_override=True) + radarState.leadTwo = get_lead(self.v_ego, self.ready, clusters, leads_v3[1], low_speed_override=False) return dat @@ -189,7 +190,7 @@ def radard_thread(sm=None, pm=None, can_sock=None): # import the radar from the fingerprint cloudlog.info("radard is importing %s", CP.carName) - RadarInterface = importlib.import_module('selfdrive.car.%s.radar_interface' % CP.carName).RadarInterface + RadarInterface = importlib.import_module(f'selfdrive.car.{CP.carName}.radar_interface').RadarInterface # *** setup messaging if can_sock is None: diff --git a/selfdrive/crash.py b/selfdrive/crash.py deleted file mode 100644 index e42b7532b..000000000 --- a/selfdrive/crash.py +++ /dev/null @@ -1,27 +0,0 @@ -"""Install exception handler for process crash.""" -from selfdrive.swaglog import cloudlog -from selfdrive.version import get_version - -import sentry_sdk -from sentry_sdk.integrations.threading import ThreadingIntegration - -def capture_exception(*args, **kwargs) -> None: - cloudlog.error("crash", exc_info=kwargs.get('exc_info', 1)) - - try: - sentry_sdk.capture_exception(*args, **kwargs) - sentry_sdk.flush() # https://github.com/getsentry/sentry-python/issues/291 - except Exception: - cloudlog.exception("sentry exception") - -def bind_user(**kwargs) -> None: - sentry_sdk.set_user(kwargs) - -def bind_extra(**kwargs) -> None: - for k, v in kwargs.items(): - sentry_sdk.set_tag(k, v) - -def init() -> None: - sentry_sdk.init("https://a8dc76b5bfb34908a601d67e2aa8bcf9@o33823.ingest.sentry.io/77924", - default_integrations=False, integrations=[ThreadingIntegration(propagate_hub=True)], - release=get_version()) diff --git a/selfdrive/debug/can_printer.py b/selfdrive/debug/can_printer.py index cb6ff2900..0aaaf1350 100755 --- a/selfdrive/debug/can_printer.py +++ b/selfdrive/debug/can_printer.py @@ -7,7 +7,7 @@ import cereal.messaging as messaging from common.realtime import sec_since_boot -def can_printer(bus, max_msg, addr): +def can_printer(bus, max_msg, addr, ascii_decode): logcan = messaging.sub_sock('can', addr=addr) start = sec_since_boot() @@ -22,12 +22,12 @@ def can_printer(bus, max_msg, addr): if sec_since_boot() - lp > 0.1: dd = chr(27) + "[2J" - dd += "%5.2f\n" % (sec_since_boot() - start) + dd += f"{sec_since_boot() - start:5.2f}\n" for addr in sorted(msgs.keys()): - a = msgs[addr][-1].decode('ascii', 'backslashreplace') + a = f"\"{msgs[addr][-1].decode('ascii', 'backslashreplace')}\"" if ascii_decode else "" x = binascii.hexlify(msgs[addr][-1]).decode('ascii') if max_msg is None or addr < max_msg: - dd += "%04X(%4d)(%6d) %s \"%s\"\n" % (addr, addr, len(msgs[addr]), x.ljust(20), a) + dd += "%04X(%4d)(%6d) %s %s\n" % (addr, addr, len(msgs[addr]), x.ljust(20), a) print(dd) lp = sec_since_boot() @@ -36,8 +36,9 @@ if __name__ == "__main__": formatter_class=argparse.ArgumentDefaultsHelpFormatter) parser.add_argument("--bus", type=int, help="CAN bus to print out", default=0) - parser.add_argument("--max_msg", type=int, help="max addr ") + parser.add_argument("--max_msg", type=int, help="max addr") + parser.add_argument("--ascii", action='store_true', help="decode as ascii") parser.add_argument("--addr", default="127.0.0.1") args = parser.parse_args() - can_printer(args.bus, args.max_msg, args.addr) + can_printer(args.bus, args.max_msg, args.addr, args.ascii) diff --git a/selfdrive/debug/check_freq.py b/selfdrive/debug/check_freq.py index 300b3ea1f..424ad67b6 100755 --- a/selfdrive/debug/check_freq.py +++ b/selfdrive/debug/check_freq.py @@ -42,6 +42,6 @@ if __name__ == "__main__": for name in socket_names: dts = np.diff(rcv_times[name]) mean = np.mean(dts) - print("%s: Freq %.2f Hz, Min %.2f%%, Max %.2f%%, valid " % (name, 1.0 / mean, np.min(dts) / mean * 100, np.max(dts) / mean * 100), all(valids[name])) + print(f"{name}: Freq {1.0 / mean:.2f} Hz, Min {np.min(dts) / mean * 100:.2f}%, Max {np.max(dts) / mean * 100:.2f}%, valid ", all(valids[name])) prev_print = t diff --git a/selfdrive/debug/cpu_usage_stat.py b/selfdrive/debug/cpu_usage_stat.py index aafc696b4..76e809d2c 100755 --- a/selfdrive/debug/cpu_usage_stat.py +++ b/selfdrive/debug/cpu_usage_stat.py @@ -110,14 +110,14 @@ if __name__ == "__main__": stat['avg'][name] = (stat['avg'][name] * (i - c) + avg * c) / (i) stat['cpu_samples'][name] = [] - msg = 'avg: {1:.2%}, min: {2:.2%}, max: {3:.2%} {0}'.format(os.path.basename(k), stat['avg']['total'], stat['min']['total'], stat['max']['total']) + msg = f"avg: {stat['avg']['total']:.2%}, min: {stat['min']['total']:.2%}, max: {stat['max']['total']:.2%} {os.path.basename(k)}" if args.detailed_times: for stat_type in ['avg', 'min', 'max']: - msg += '\n {}: {}'.format(stat_type, [name + ':' + str(round(stat[stat_type][name]*100, 2)) for name in cpu_time_names]) + msg += f"\n {stat_type}: {[(name + ':' + str(round(stat[stat_type][name] * 100, 2))) for name in cpu_time_names]}" l.append((os.path.basename(k), stat['avg']['total'], msg)) l.sort(key=lambda x: -x[1]) for x in l: print(x[2]) - print('avg sum: {0:.2%} over {1} samples {2} seconds\n'.format( + print('avg sum: {:.2%} over {} samples {} seconds\n'.format( sum(stat['avg']['total'] for k, stat in stats.items()), i, i * SLEEP_INTERVAL )) diff --git a/selfdrive/debug/dump.py b/selfdrive/debug/dump.py index 047c874fb..f208920f1 100755 --- a/selfdrive/debug/dump.py +++ b/selfdrive/debug/dump.py @@ -54,13 +54,13 @@ if __name__ == "__main__": elif args.dump_json: print(json.dumps(evt.to_dict())) elif values: - print("logMonotime = {}".format(evt.logMonoTime)) + print(f"logMonotime = {evt.logMonoTime}") for value in values: if hasattr(evt, value[0]): item = evt for key in value: item = getattr(item, key) - print("{} = {}".format(".".join(value), item)) + print(f"{'.'.join(value)} = {item}") print("") else: try: diff --git a/selfdrive/debug/fingerprint_from_route.py b/selfdrive/debug/fingerprint_from_route.py index 098e39fbe..326e68f8e 100755 --- a/selfdrive/debug/fingerprint_from_route.py +++ b/selfdrive/debug/fingerprint_from_route.py @@ -41,5 +41,5 @@ if __name__ == "__main__": sys.exit(1) route = Route(sys.argv[1]) - lr = MultiLogIterator(route.log_paths()[:5], wraparound=False) + lr = MultiLogIterator(route.log_paths()[:5]) get_fingerprint(lr) diff --git a/selfdrive/debug/get_fingerprint.py b/selfdrive/debug/get_fingerprint.py index 6c38957be..e678db4f1 100755 --- a/selfdrive/debug/get_fingerprint.py +++ b/selfdrive/debug/get_fingerprint.py @@ -27,5 +27,5 @@ while True: fingerprint = ', '.join("%d: %d" % v for v in sorted(msgs.items())) - print("number of messages {0}:".format(len(msgs))) - print("fingerprint {0}".format(fingerprint)) + print(f"number of messages {len(msgs)}:") + print(f"fingerprint {fingerprint}") diff --git a/selfdrive/debug/hyundai_enable_radar_points.py b/selfdrive/debug/hyundai_enable_radar_points.py index 204d2480c..8132a4655 100755 --- a/selfdrive/debug/hyundai_enable_radar_points.py +++ b/selfdrive/debug/hyundai_enable_radar_points.py @@ -13,42 +13,45 @@ USE AT YOUR OWN RISK! Safety features, like AEB and FCW, might be affected by th import sys import argparse +from typing import NamedTuple from subprocess import check_output, CalledProcessError from panda.python import Panda from panda.python.uds import UdsClient, SESSION_TYPE, DATA_IDENTIFIER_TYPE +class ConfigValues(NamedTuple): + default_config: bytes + tracks_enabled: bytes + # If your radar supports changing data identifier 0x0142 as well make a PR to # this file to add your firmware version. Make sure to post a drive as proof! # NOTE: these firmware versions do not match what openpilot uses # because this script uses a different diagnostic session type SUPPORTED_FW_VERSIONS = { # 2020 SONATA - b"DN8_ SCC FHCUP 1.00 1.00 99110-L0000\x19\x08)\x15T ": { - "default_config": b"\x00\x00\x00\x01\x00\x00", - "tracks_enabled": b"\x00\x00\x00\x01\x00\x01", - }, + b"DN8_ SCC FHCUP 1.00 1.00 99110-L0000\x19\x08)\x15T ": ConfigValues( + default_config=b"\x00\x00\x00\x01\x00\x00", + tracks_enabled=b"\x00\x00\x00\x01\x00\x01"), # 2021 SONATA HYBRID - b"DNhe SCC FHCUP 1.00 1.02 99110-L5000 \x01#\x15# ": { - "default_config": b"\x00\x00\x00\x01\x00\x00", - "tracks_enabled": b"\x00\x00\x00\x01\x00\x01", - }, + b"DNhe SCC FHCUP 1.00 1.02 99110-L5000 \x01#\x15# ": ConfigValues( + default_config=b"\x00\x00\x00\x01\x00\x00", + tracks_enabled=b"\x00\x00\x00\x01\x00\x01"), # 2020 PALISADE - b"LX2_ SCC FHCUP 1.00 1.04 99110-S8100\x19\x05\x02\x16V ": { - "default_config": b"\x00\x00\x00\x01\x00\x00", - "tracks_enabled": b"\x00\x00\x00\x01\x00\x01", - }, + b"LX2_ SCC FHCUP 1.00 1.04 99110-S8100\x19\x05\x02\x16V ": ConfigValues( + default_config=b"\x00\x00\x00\x01\x00\x00", + tracks_enabled=b"\x00\x00\x00\x01\x00\x01"), + # 2022 PALISADE + b"LX2_ SCC FHCUP 1.00 1.00 99110-S8110!\x04\x05\x17\x01 ": ConfigValues( + default_config=b"\x00\x00\x00\x01\x00\x00", + tracks_enabled=b"\x00\x00\x00\x01\x00\x01"), # 2020 SANTA FE - b"TM__ SCC F-CUP 1.00 1.03 99110-S2000\x19\x050\x13' ": { - "default_config": b"\x00\x00\x00\x01\x00\x00", - "tracks_enabled": b"\x00\x00\x00\x01\x00\x01", - }, - + b"TM__ SCC F-CUP 1.00 1.03 99110-S2000\x19\x050\x13' ": ConfigValues( + default_config=b"\x00\x00\x00\x01\x00\x00", + tracks_enabled=b"\x00\x00\x00\x01\x00\x01"), # 2020 GENESIS G70 - b'IK__ SCC F-CUP 1.00 1.02 96400-G9100\x18\x07\x06\x17\x12 ': { - "default config": b"\x00\x00\x00\x01\x00\x00", - "tracks_enabled": b"\x00\x00\x00\x01\x00\x01", - }, + b'IK__ SCC F-CUP 1.00 1.02 96400-G9100\x18\x07\x06\x17\x12 ': ConfigValues( + default_config=b"\x00\x00\x00\x01\x00\x00", + tracks_enabled=b"\x00\x00\x00\x01\x00\x01"), } if __name__ == "__main__": @@ -90,13 +93,14 @@ if __name__ == "__main__": print("[GET CONFIGURATION]") config_data_id : DATA_IDENTIFIER_TYPE = 0x0142 # type: ignore current_config = uds_client.read_data_by_identifier(config_data_id) - new_config = SUPPORTED_FW_VERSIONS[fw_version]["default_config" if args.default else "tracks_enabled"] + config_values = SUPPORTED_FW_VERSIONS[fw_version] + new_config = config_values.default_config if args.default else config_values.tracks_enabled print(f"current config: 0x{current_config.hex()}") if current_config != new_config: print("[CHANGE CONFIGURATION]") print(f"new config: 0x{new_config.hex()}") uds_client.write_data_by_identifier(config_data_id, new_config) - if not args.default and current_config != SUPPORTED_FW_VERSIONS[fw_version]["default_config"]: + if not args.default and current_config != SUPPORTED_FW_VERSIONS[fw_version].default_config: print("\ncurrent config does not match expected default! (aborted)") sys.exit(1) diff --git a/selfdrive/debug/live_cpu_and_temp.py b/selfdrive/debug/live_cpu_and_temp.py index 5589b0d6d..e46c0b0a1 100755 --- a/selfdrive/debug/live_cpu_and_temp.py +++ b/selfdrive/debug/live_cpu_and_temp.py @@ -71,7 +71,7 @@ if __name__ == "__main__": total_times = total_times_new[:] busy_times = busy_times_new[:] - print("CPU %.2f%% - RAM: %.2f%% - Temp %.2fC" % (100. * mean(cores), last_mem, last_temp)) + print(f"CPU {100.0 * mean(cores):.2f}% - RAM: {last_mem:.2f}% - Temp {last_temp:.2f}C") if args.cpu and prev_proclog is not None: procs = {} diff --git a/selfdrive/debug/run_process_on_route.py b/selfdrive/debug/run_process_on_route.py index bcb741f54..a6e67d2b2 100755 --- a/selfdrive/debug/run_process_on_route.py +++ b/selfdrive/debug/run_process_on_route.py @@ -17,13 +17,13 @@ if __name__ == "__main__": cfg = [c for c in CONFIGS if c.proc_name == args.process][0] route = Route(args.route) - lr = MultiLogIterator(route.log_paths(), wraparound=False) + lr = MultiLogIterator(route.log_paths()) inputs = list(lr) outputs = replay_process(cfg, inputs) # Remove message generated by the process under test and merge in the new messages - produces = set(o.which() for o in outputs) + produces = {o.which() for o in outputs} inputs = [i for i in inputs if i.which() not in produces] outputs = sorted(inputs + outputs, key=lambda x: x.logMonoTime) diff --git a/selfdrive/debug/toyota_eps_factor.py b/selfdrive/debug/toyota_eps_factor.py index e63122b6a..0a459bb71 100755 --- a/selfdrive/debug/toyota_eps_factor.py +++ b/selfdrive/debug/toyota_eps_factor.py @@ -59,6 +59,6 @@ def get_eps_factor(lr, plot=False): if __name__ == "__main__": r = Route(sys.argv[1]) - lr = MultiLogIterator(r.log_paths(), wraparound=False) + lr = MultiLogIterator(r.log_paths()) n = get_eps_factor(lr, plot="--plot" in sys.argv) print("EPS torque factor: ", n) diff --git a/selfdrive/debug/vw_mqb_config.py b/selfdrive/debug/vw_mqb_config.py new file mode 100755 index 000000000..1dd28d371 --- /dev/null +++ b/selfdrive/debug/vw_mqb_config.py @@ -0,0 +1,145 @@ +#!/usr/bin/env python3 + +import argparse +import struct +from enum import IntEnum +from panda import Panda +from panda.python.uds import UdsClient, MessageTimeoutError, NegativeResponseError, SESSION_TYPE,\ + DATA_IDENTIFIER_TYPE, ACCESS_TYPE + +# TODO: extend UDS library to allow custom/vendor-defined data identifiers without ignoring type checks +class VOLKSWAGEN_DATA_IDENTIFIER_TYPE(IntEnum): + CODING = 0x0600 + +# TODO: extend UDS library security_access() to take an access level offset per ISO 14229-1:2020 10.4 and remove this +class ACCESS_TYPE_LEVEL_1(IntEnum): + REQUEST_SEED = ACCESS_TYPE.REQUEST_SEED + 2 + SEND_KEY = ACCESS_TYPE.SEND_KEY + 2 + +MQB_EPS_CAN_ADDR = 0x712 +RX_OFFSET = 0x6a + +if __name__ == "__main__": + desc_text = "Shows Volkswagen EPS software and coding info, and enables or disables Heading Control Assist " + \ + "(Lane Assist). Useful for enabling HCA on cars without factory Lane Assist that want to use " + \ + "openpilot integrated at the CAN gateway (J533)." + epilog_text = "This tool is meant to run directly on a vehicle-installed comma two or comma three, with the " + \ + "openpilot/tmux processes stopped. It should also work on a separate PC with a USB-attached comma " + \ + "panda. Vehicle ignition must be on. Recommend engine not be running when making changes. Must " + \ + "turn ignition off and on again for any changes to take effect." + parser = argparse.ArgumentParser(description=desc_text, epilog=epilog_text) + parser.add_argument("--debug", action="store_true", help="enable ISO-TP/UDS stack debugging output") + parser.add_argument("action", choices={"show", "enable", "disable"}, help="show or modify current EPS HCA config") + args = parser.parse_args() + + panda = Panda() + panda.set_safety_mode(Panda.SAFETY_ELM327) + bus = 1 if panda.has_obd() else 0 + uds_client = UdsClient(panda, MQB_EPS_CAN_ADDR, MQB_EPS_CAN_ADDR + RX_OFFSET, bus, timeout=0.2, debug=args.debug) + + try: + uds_client.diagnostic_session_control(SESSION_TYPE.EXTENDED_DIAGNOSTIC) + except MessageTimeoutError: + print("Timeout opening session with EPS") + quit() + + odx_file, current_coding = None, None + try: + hw_pn = uds_client.read_data_by_identifier(DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_ECU_HARDWARE_NUMBER).decode("utf-8") + sw_pn = uds_client.read_data_by_identifier(DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_SPARE_PART_NUMBER).decode("utf-8") + sw_ver = uds_client.read_data_by_identifier(DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_ECU_SOFTWARE_VERSION_NUMBER).decode("utf-8") + component = uds_client.read_data_by_identifier(DATA_IDENTIFIER_TYPE.SYSTEM_NAME_OR_ENGINE_TYPE).decode("utf-8") + odx_file = uds_client.read_data_by_identifier(DATA_IDENTIFIER_TYPE.ODX_FILE).decode("utf-8") + current_coding = uds_client.read_data_by_identifier(VOLKSWAGEN_DATA_IDENTIFIER_TYPE.CODING) # type: ignore + coding_text = current_coding.hex() + + print("\nEPS diagnostic data\n") + print(f" Part No HW: {hw_pn}") + print(f" Part No SW: {sw_pn}") + print(f" SW Version: {sw_ver}") + print(f" Component: {component}") + print(f" Coding: {coding_text}") + print(f" ASAM Dataset: {odx_file}") + except NegativeResponseError: + print("Error fetching data from EPS") + quit() + except MessageTimeoutError: + print("Timeout fetching data from EPS") + quit() + + coding_variant, current_coding_array = None, None + # EV_SteerAssisMQB covers the majority of MQB racks (EPS_MQB_ZFLS) + # APA racks (MQB_PP_APA) have a different coding layout, which should + # be easy to support once we identify the specific config bit + if odx_file == "EV_SteerAssisMQB\x00": + coding_variant = "ZF" + current_coding_array = struct.unpack("!4B", current_coding) + hca_enabled = (current_coding_array[0] & (1 << 4) != 0) + hca_text = ("DISABLED", "ENABLED")[hca_enabled] + print(f" Lane Assist: {hca_text}") + else: + print("Configuration changes not yet supported on this EPS!") + quit() + + try: + params = uds_client.read_data_by_identifier(DATA_IDENTIFIER_TYPE.APPLICATION_DATA_IDENTIFICATION).decode("utf-8") + param_version_system_params = params[1:3] + param_vehicle_type = params[3:5] + param_index_char_curve = params[5:7] + param_version_char_values = params[7:9] + param_version_memory_map = params[9:11] + print("\nEPS parameterization (per-vehicle calibration) data\n") + print(f" Version of system parameters: {param_version_system_params}") + print(f" Vehicle type: {param_vehicle_type}") + print(f" Index of characteristic curve: {param_index_char_curve}") + print(f" Version of characteristic values: {param_version_char_values}") + print(f" Version of memory map: {param_version_memory_map}") + except (NegativeResponseError, MessageTimeoutError): + print("Error fetching parameterization data from EPS!") + quit() + + if args.action in ["enable", "disable"]: + print("\nAttempting configuration update") + + assert(coding_variant == "ZF") # revisit when we have the APA rack coding bit + # ZF EPS config coding length can be anywhere from 1 to 4 bytes, but the + # bit we care about is always in the same place in the first byte + if args.action == "enable": + new_byte_0 = current_coding_array[0] | (1 << 4) + else: + new_byte_0 = current_coding_array[0] & ~(1 << 4) + new_coding = new_byte_0.to_bytes(1, "little") + current_coding[1:] + + try: + seed = uds_client.security_access(ACCESS_TYPE_LEVEL_1.REQUEST_SEED) # type: ignore + key = struct.unpack("!I", seed)[0] + 28183 # yeah, it's like that + uds_client.security_access(ACCESS_TYPE_LEVEL_1.SEND_KEY, struct.pack("!I", key)) # type: ignore + except (NegativeResponseError, MessageTimeoutError): + print("Security access failed!") + quit() + + try: + # Programming date and tester number must be written before making + # a change, or write to CODING will fail with request sequence error + # Encoding on tester is unclear, it contains the workshop code in the + # last two bytes, but not the VZ/importer or tester serial number + # Can't seem to read it back, but we can read the calibration tester, + # so fib a little and say that same tester did the programming + # TODO: encode the actual current date + prog_date = b'\x22\x02\x08' + uds_client.write_data_by_identifier(DATA_IDENTIFIER_TYPE.PROGRAMMING_DATE, prog_date) + tester_num = uds_client.read_data_by_identifier(DATA_IDENTIFIER_TYPE.CALIBRATION_REPAIR_SHOP_CODE_OR_CALIBRATION_EQUIPMENT_SERIAL_NUMBER) + uds_client.write_data_by_identifier(DATA_IDENTIFIER_TYPE.REPAIR_SHOP_CODE_OR_TESTER_SERIAL_NUMBER, tester_num) + uds_client.write_data_by_identifier(VOLKSWAGEN_DATA_IDENTIFIER_TYPE.CODING, new_coding) # type: ignore + except (NegativeResponseError, MessageTimeoutError): + print("Writing new configuration failed!") + quit() + + try: + # Read back result just to make 100% sure everything worked + current_coding_text = uds_client.read_data_by_identifier(VOLKSWAGEN_DATA_IDENTIFIER_TYPE.CODING).hex() # type: ignore + print(f" New coding: {current_coding_text}") + except (NegativeResponseError, MessageTimeoutError): + print("Reading back updated coding failed!") + quit() + print("EPS configuration successfully updated") diff --git a/selfdrive/hardware/base.py b/selfdrive/hardware/base.py index 06c86f0c2..b551138ce 100644 --- a/selfdrive/hardware/base.py +++ b/selfdrive/hardware/base.py @@ -1,11 +1,12 @@ -from abc import abstractmethod +from abc import abstractmethod, ABC from collections import namedtuple +from typing import Dict ThermalConfig = namedtuple('ThermalConfig', ['cpu', 'gpu', 'mem', 'bat', 'ambient', 'pmic']) -class HardwareBase: +class HardwareBase(ABC): @staticmethod - def get_cmdline(): + def get_cmdline() -> Dict[str, str]: with open('/proc/cmdline') as f: cmdline = f.read() return {kv[0]: kv[1] for kv in [s.split('=') for s in cmdline.split(' ')] if len(kv) == 2} @@ -66,6 +67,10 @@ class HardwareBase: def get_network_strength(self, network_type): pass + @staticmethod + def set_bandwidth_limit(upload_speed_kbps: int, download_speed_kbps: int) -> None: + pass + @abstractmethod def get_battery_capacity(self): pass diff --git a/selfdrive/hardware/eon/androidd.py b/selfdrive/hardware/eon/androidd.py index b836eb012..3d91468b9 100755 --- a/selfdrive/hardware/eon/androidd.py +++ b/selfdrive/hardware/eon/androidd.py @@ -4,13 +4,14 @@ import time import psutil from typing import Optional +import cereal.messaging as messaging from common.realtime import set_core_affinity, set_realtime_priority from selfdrive.swaglog import cloudlog MAX_MODEM_CRASHES = 3 MODEM_PATH = "/sys/devices/soc/2080000.qcom,mss/subsys5" -WATCHED_PROCS = ["zygote", "zygote64", "/system/bin/servicemanager", "/system/bin/surfaceflinger"] +WATCHED_PROCS = ["zygote", "zygote64", "system_server", "/system/bin/servicemanager", "/system/bin/surfaceflinger"] def get_modem_crash_count() -> Optional[int]: @@ -37,6 +38,8 @@ def main(): crash_count = 0 modem_killed = False modem_state = "ONLINE" + androidLog = messaging.sub_sock('androidLog') + while True: # check critical android services if any(p is None or not p.is_running() for p in procs.values()) or not len(procs): @@ -49,9 +52,18 @@ def main(): if len(procs): for p in WATCHED_PROCS: if cur[p] != procs[p]: - cloudlog.event("android service pid changed", proc=p, cur=cur[p], prev=procs[p]) + cloudlog.event("android service pid changed", proc=p, cur=cur[p], prev=procs[p], error=True) procs.update(cur) + # log caught NetworkPolicy exceptions + msgs = messaging.drain_sock(androidLog) + for m in msgs: + try: + if m.androidLog.tag == "NetworkPolicy" and m.androidLog.message.startswith("problem with advise persist threshold"): + cloudlog.event("network policy exception caught", androidLog=m.androidLog, error=True) + except UnicodeDecodeError: + pass + if os.path.exists(MODEM_PATH): # check modem state state = get_modem_state() @@ -68,7 +80,7 @@ def main(): # handle excessive modem crashes if crash_count > MAX_MODEM_CRASHES and not modem_killed: - cloudlog.event("killing modem") + cloudlog.event("killing modem", error=True) with open("/sys/kernel/debug/msm_subsys/modem", "w") as f: f.write("put") modem_killed = True diff --git a/selfdrive/hardware/eon/hardware.py b/selfdrive/hardware/eon/hardware.py index fa275c5a9..4ab9f81fc 100644 --- a/selfdrive/hardware/eon/hardware.py +++ b/selfdrive/hardware/eon/hardware.py @@ -10,6 +10,12 @@ from typing import List, Union from cereal import log from selfdrive.hardware.base import HardwareBase, ThermalConfig +try: + from common.params import Params +except Exception: + # openpilot is not built yet + Params = None + NetworkType = log.DeviceState.NetworkType NetworkStrength = log.DeviceState.NetworkStrength @@ -70,6 +76,11 @@ class Android(HardwareBase): return f.read().strip() def get_device_type(self): + try: + if int(Params().get("LastPeripheralPandaType")) == log.PandaState.PandaType.uno: + return "two" + except Exception: + pass return "eon" def get_sound_card_online(self): diff --git a/selfdrive/hardware/eon/neos.json b/selfdrive/hardware/eon/neos.json index 228029e9f..4010f7126 100644 --- a/selfdrive/hardware/eon/neos.json +++ b/selfdrive/hardware/eon/neos.json @@ -1,7 +1,7 @@ { - "ota_url": "https://commadist.azureedge.net/neosupdate/ota-signed-5dc2575d713977666a8e14ae1b43a04d7f63123934c80fa10751d949a107653e.zip", - "ota_hash": "5dc2575d713977666a8e14ae1b43a04d7f63123934c80fa10751d949a107653e", - "recovery_url": "https://commadist.azureedge.net/neosupdate/recovery-f01a55c9ba52ca57668d1684c6bf4118efd31916b04f8c1fcd8495013d3677eb.img", + "ota_url": "https://commadist.azureedge.net/neosupdate/ota-signed-50da8800caa5cbc224acbaa21f3a83d21802a31d89cccfc62a898903a8eb19e7.zip", + "ota_hash": "50da8800caa5cbc224acbaa21f3a83d21802a31d89cccfc62a898903a8eb19e7", + "recovery_url": "https://commadist.azureedge.net/neosupdate/recovery-fe76739438d28ea6111853a737b616afdf340ba75c01c0ee99e6a28c19ecc29f.img", "recovery_len": 15222060, - "recovery_hash": "f01a55c9ba52ca57668d1684c6bf4118efd31916b04f8c1fcd8495013d3677eb" + "recovery_hash": "fe76739438d28ea6111853a737b616afdf340ba75c01c0ee99e6a28c19ecc29f" } diff --git a/selfdrive/hardware/eon/shutdownd.py b/selfdrive/hardware/eon/shutdownd.py new file mode 100755 index 000000000..15112e7d5 --- /dev/null +++ b/selfdrive/hardware/eon/shutdownd.py @@ -0,0 +1,34 @@ +#!/usr/bin/env python3 +import os +import time +import datetime + +from common.params import Params +from selfdrive.hardware.eon.hardware import getprop +from selfdrive.swaglog import cloudlog + +def main(): + prev = b"" + params = Params() + while True: + with open("/dev/__properties__", 'rb') as f: + cur = f.read() + + if cur != prev: + prev = cur + + # 0 for shutdown, 1 for reboot + prop = getprop("sys.shutdown.requested") + if prop is not None and len(prop) > 0: + os.system("pkill -9 loggerd") + params.put("LastSystemShutdown", f"'{prop}' {datetime.datetime.now()}") + os.sync() + + time.sleep(120) + cloudlog.error('shutdown false positive') + break + + time.sleep(0.1) + +if __name__ == "__main__": + main() diff --git a/selfdrive/hardware/hw.h b/selfdrive/hardware/hw.h index d7a6c8d1d..f18ede01e 100644 --- a/selfdrive/hardware/hw.h +++ b/selfdrive/hardware/hw.h @@ -20,17 +20,16 @@ public: #endif namespace Path { -inline static std::string HOME = util::getenv("HOME"); inline std::string log_root() { if (const char *env = getenv("LOG_ROOT")) { return env; } - return Hardware::PC() ? HOME + "/.comma/media/0/realdata" : "/data/media/0/realdata"; + return Hardware::PC() ? util::getenv("HOME") + "/.comma/media/0/realdata" : "/data/media/0/realdata"; } inline std::string params() { - return Hardware::PC() ? HOME + "/.comma/params" : "/data/params"; + return Hardware::PC() ? util::getenv("HOME") + "/.comma/params" : "/data/params"; } inline std::string rsa_file() { - return Hardware::PC() ? HOME + "/.comma/persist/comma/id_rsa" : "/persist/comma/id_rsa"; + return Hardware::PC() ? util::getenv("HOME") + "/.comma/persist/comma/id_rsa" : "/persist/comma/id_rsa"; } } // namespace Path diff --git a/selfdrive/hardware/tici/agnos.json b/selfdrive/hardware/tici/agnos.json index f22575a33..6674ddaa5 100644 --- a/selfdrive/hardware/tici/agnos.json +++ b/selfdrive/hardware/tici/agnos.json @@ -1,10 +1,10 @@ [ { "name": "boot", - "url": "https://commadist.azureedge.net/agnosupdate/boot-5ad783213b7de18400f5fd3609fe75677fec80780ae31cbdf5a8ee7106675d7c.img.xz", - "hash": "5ad783213b7de18400f5fd3609fe75677fec80780ae31cbdf5a8ee7106675d7c", - "hash_raw": "5ad783213b7de18400f5fd3609fe75677fec80780ae31cbdf5a8ee7106675d7c", - "size": 14768128, + "url": "https://commadist.azureedge.net/agnosupdate/boot-0a86272196cb54607f8ba082f412fed4607baaf6ce3eb8dc8e950b4a1d763954.img.xz", + "hash": "0a86272196cb54607f8ba082f412fed4607baaf6ce3eb8dc8e950b4a1d763954", + "hash_raw": "0a86272196cb54607f8ba082f412fed4607baaf6ce3eb8dc8e950b4a1d763954", + "size": 14776320, "sparse": false, "full_check": true, "has_ab": true @@ -41,9 +41,9 @@ }, { "name": "system", - "url": "https://commadist.azureedge.net/agnosupdate/system-0fee88a42385d067756e9b25d57a80228835310deb7b5eef7b7bed5c22c45515.img.xz", - "hash": "a043cba1ae08ca6d17704a8a0978b1e27e5bc79abb85b97efd35203ae26ae1ea", - "hash_raw": "0fee88a42385d067756e9b25d57a80228835310deb7b5eef7b7bed5c22c45515", + "url": "https://commadist.azureedge.net/agnosupdate/system-9b0b534ed0c35c25850dbb73d3f052611f2e2c9db32410edc25d75fbcfc6c15e.img.xz", + "hash": "b1f622f00037bbdb28c0a6016c0e42fa7f87e99591ff2417c757a67ff559b526", + "hash_raw": "9b0b534ed0c35c25850dbb73d3f052611f2e2c9db32410edc25d75fbcfc6c15e", "size": 10737418240, "sparse": true, "full_check": false, diff --git a/selfdrive/hardware/tici/hardware.py b/selfdrive/hardware/tici/hardware.py index 855eee908..41ae316d3 100644 --- a/selfdrive/hardware/tici/hardware.py +++ b/selfdrive/hardware/tici/hardware.py @@ -218,6 +218,65 @@ class Tici(HardwareBase): return network_strength + @staticmethod + def set_bandwidth_limit(upload_speed_kbps: int, download_speed_kbps: int) -> None: + upload_speed_kbps = int(upload_speed_kbps) # Ensure integer value + download_speed_kbps = int(download_speed_kbps) # Ensure integer value + + adapter = "wwan0" + ifb = "ifb0" + + sudo = ["sudo"] + tc = sudo + ["tc"] + + # check, cmd + cleanup = [ + # Clean up old rules + (False, tc + ["qdisc", "del", "dev", adapter, "root"]), + (False, tc + ["qdisc", "del", "dev", ifb, "root"]), + (False, tc + ["qdisc", "del", "dev", adapter, "ingress"]), + (False, tc + ["qdisc", "del", "dev", ifb, "ingress"]), + + # Bring ifb0 down + (False, sudo + ["ip", "link", "set", "dev", ifb, "down"]), + ] + + upload = [ + # Create root Hierarchy Token Bucket that sends all trafic to 1:20 + (True, tc + ["qdisc", "add", "dev", adapter, "root", "handle", "1:", "htb", "default", "20"]), + + # Create class 1:20 with specified rate limit + (True, tc + ["class", "add", "dev", adapter, "parent", "1:", "classid", "1:20", "htb", "rate", f"{upload_speed_kbps}kbit"]), + + # Create universal 32 bit filter on adapter that sends all outbound ip traffic through the class + (True, tc + ["filter", "add", "dev", adapter, "parent", "1:", "protocol", "ip", "prio", "10", "u32", "match", "ip", "dst", "0.0.0.0/0", "flowid", "1:20"]), + ] + + download = [ + # Bring ifb0 up + (True, sudo + ["ip", "link", "set", "dev", ifb, "up"]), + + # Redirect ingress (incoming) to egress ifb0 + (True, tc + ["qdisc", "add", "dev", adapter, "handle", "ffff:", "ingress"]), + (True, tc + ["filter", "add", "dev", adapter, "parent", "ffff:", "protocol", "ip", "u32", "match", "u32", "0", "0", "action", "mirred", "egress", "redirect", "dev", ifb]), + + # Add class and rules for virtual interface + (True, tc + ["qdisc", "add", "dev", ifb, "root", "handle", "2:", "htb"]), + (True, tc + ["class", "add", "dev", ifb, "parent", "2:", "classid", "2:1", "htb", "rate", f"{download_speed_kbps}kbit"]), + + # Add filter to rule for IP address + (True, tc + ["filter", "add", "dev", ifb, "protocol", "ip", "parent", "2:", "prio", "1", "u32", "match", "ip", "src", "0.0.0.0/0", "flowid", "2:1"]), + ] + + commands = cleanup + if upload_speed_kbps != -1: + commands += upload + if download_speed_kbps != -1: + commands += download + + for check, cmd in commands: + subprocess.run(cmd, check=check) + def get_modem_version(self): try: modem = self.get_modem() @@ -320,6 +379,9 @@ class Tici(HardwareBase): def initialize_hardware(self): self.amplifier.initialize_configuration() + # Allow thermald to write engagement status to kmsg + os.system("sudo chmod a+w /dev/kmsg") + def get_networks(self): r = {} diff --git a/selfdrive/locationd/calibrationd.py b/selfdrive/locationd/calibrationd.py index 604f4f68d..ae314e38c 100755 --- a/selfdrive/locationd/calibrationd.py +++ b/selfdrive/locationd/calibrationd.py @@ -6,17 +6,20 @@ While the roll calibration is a real value that can be estimated, here we assume and the image input into the neural network is not corrected for roll. ''' +import gc import os -import copy import numpy as np -import cereal.messaging as messaging +from typing import NoReturn + from cereal import log -from selfdrive.hardware import TICI +import cereal.messaging as messaging from common.params import Params, put_nonblocking +from common.realtime import set_realtime_priority from common.transformations.model import model_height from common.transformations.camera import get_view_frame_from_road_frame from common.transformations.orientation import rot_from_euler, euler_from_rot from selfdrive.config import Conversions as CV +from selfdrive.hardware import TICI from selfdrive.swaglog import cloudlog MIN_SPEED_FILTER = 15 * CV.MPH_TO_MS @@ -69,7 +72,7 @@ class Calibrator(): if param_put and calibration_params: try: msg = log.Event.from_bytes(calibration_params) - rpy_init = list(msg.liveCalibration.rpyCalib) + rpy_init = np.array(msg.liveCalibration.rpyCalib) valid_blocks = msg.liveCalibration.validBlocks except Exception: cloudlog.exception("Error reading cached CalibrationParams") @@ -79,13 +82,15 @@ class Calibrator(): def reset(self, rpy_init=RPY_INIT, valid_blocks=0, smooth_from=None): if not np.isfinite(rpy_init).all(): - self.rpy = copy.copy(RPY_INIT) + self.rpy = RPY_INIT.copy() else: - self.rpy = rpy_init + self.rpy = rpy_init.copy() + if not np.isfinite(valid_blocks) or valid_blocks < 0: - self.valid_blocks = 0 + self.valid_blocks = 0 else: self.valid_blocks = valid_blocks + self.rpys = np.tile(self.rpy, (INPUTS_WANTED, 1)) self.idx = 0 @@ -99,10 +104,19 @@ class Calibrator(): self.old_rpy = smooth_from self.old_rpy_weight = 1.0 + def get_valid_idxs(self): + # exclude current block_idx from validity window + before_current = list(range(self.block_idx)) + after_current = list(range(min(self.valid_blocks, self.block_idx + 1), self.valid_blocks)) + return before_current + after_current + def update_status(self): - if self.valid_blocks > 0: - max_rpy_calib = np.array(np.max(self.rpys[:self.valid_blocks], axis=0)) - min_rpy_calib = np.array(np.min(self.rpys[:self.valid_blocks], axis=0)) + valid_idxs = self.get_valid_idxs() + if valid_idxs: + rpys = self.rpys[valid_idxs] + self.rpy = np.mean(rpys, axis=0) + max_rpy_calib = np.array(np.max(rpys, axis=0)) + min_rpy_calib = np.array(np.min(rpys, axis=0)) self.calib_spread = np.abs(max_rpy_calib - min_rpy_calib) else: self.calib_spread = np.zeros(3) @@ -157,8 +171,6 @@ class Calibrator(): self.block_idx += 1 self.valid_blocks = max(self.block_idx, self.valid_blocks) self.block_idx = self.block_idx % INPUTS_WANTED - if self.valid_blocks > 0: - self.rpy = np.mean(self.rpys[:self.valid_blocks], axis=0) self.update_status() @@ -172,16 +184,19 @@ class Calibrator(): msg.liveCalibration.validBlocks = self.valid_blocks msg.liveCalibration.calStatus = self.cal_status msg.liveCalibration.calPerc = min(100 * (self.valid_blocks * BLOCK_SIZE + self.idx) // (INPUTS_NEEDED * BLOCK_SIZE), 100) - msg.liveCalibration.extrinsicMatrix = [float(x) for x in extrinsic_matrix.flatten()] - msg.liveCalibration.rpyCalib = [float(x) for x in smooth_rpy] - msg.liveCalibration.rpyCalibSpread = [float(x) for x in self.calib_spread] + msg.liveCalibration.extrinsicMatrix = extrinsic_matrix.flatten().tolist() + msg.liveCalibration.rpyCalib = smooth_rpy.tolist() + msg.liveCalibration.rpyCalibSpread = self.calib_spread.tolist() return msg - def send_data(self, pm): + def send_data(self, pm) -> None: pm.send('liveCalibration', self.get_msg()) -def calibrationd_thread(sm=None, pm=None): +def calibrationd_thread(sm=None, pm=None) -> NoReturn: + gc.disable() + set_realtime_priority(1) + if sm is None: sm = messaging.SubMaster(['cameraOdometry', 'carState'], poll=['cameraOdometry']) @@ -209,7 +224,7 @@ def calibrationd_thread(sm=None, pm=None): calibrator.send_data(pm) -def main(sm=None, pm=None): +def main(sm=None, pm=None) -> NoReturn: calibrationd_thread(sm, pm) diff --git a/selfdrive/locationd/locationd.cc b/selfdrive/locationd/locationd.cc index 0350625a9..b723878e9 100755 --- a/selfdrive/locationd/locationd.cc +++ b/selfdrive/locationd/locationd.cc @@ -80,11 +80,10 @@ void Localizer::build_live_location(cereal::LiveLocationKalman::Builder& fix) { VectorXd vel_ecef = predicted_state.segment(STATE_ECEF_VELOCITY_START); VectorXd vel_ecef_std = predicted_std.segment(STATE_ECEF_VELOCITY_ERR_START); VectorXd fix_pos_geo_vec = this->get_position_geodetic(); - //fix_pos_geo_std = np.abs(coord.ecef2geodetic(fix_ecef + fix_ecef_std) - fix_pos_geo) VectorXd orientation_ecef = quat2euler(vector2quat(predicted_state.segment(STATE_ECEF_ORIENTATION_START))); VectorXd orientation_ecef_std = predicted_std.segment(STATE_ECEF_ORIENTATION_ERR_START); + MatrixXdr orientation_ecef_cov = predicted_cov.block(STATE_ECEF_ORIENTATION_ERR_START, STATE_ECEF_ORIENTATION_ERR_START); MatrixXdr device_from_ecef = euler2rot(orientation_ecef).transpose(); - //VectorXd calibrated_orientation_ecef = rot2euler(device_from_ecef); VectorXd calibrated_orientation_ecef = rot2euler((this->calib_from_device * device_from_ecef).transpose()); VectorXd acc_calib = this->calib_from_device * predicted_state.segment(STATE_ACCELERATION_START); @@ -116,11 +115,10 @@ void Localizer::build_live_location(cereal::LiveLocationKalman::Builder& fix) { VectorXd vel_calib_std = rotate_cov(this->calib_from_device, vel_device_cov).diagonal().array().sqrt(); VectorXd orientation_ned = ned_euler_from_ecef(fix_ecef_ecef, orientation_ecef); - //orientation_ned_std = ned_euler_from_ecef(fix_ecef, orientation_ecef + orientation_ecef_std) - orientation_ned + VectorXd orientation_ned_std = rotate_cov(this->converter->ecef2ned_matrix, orientation_ecef_cov).diagonal().array().sqrt(); VectorXd calibrated_orientation_ned = ned_euler_from_ecef(fix_ecef_ecef, calibrated_orientation_ecef); VectorXd nextfix_ecef = fix_ecef + vel_ecef; VectorXd ned_vel = this->converter->ecef2ned((ECEF) { .x = nextfix_ecef(0), .y = nextfix_ecef(1), .z = nextfix_ecef(2) }).to_vector() - converter->ecef2ned(fix_ecef_ecef).to_vector(); - //ned_vel_std = self.converter->ecef2ned(fix_ecef + vel_ecef + vel_ecef_std) - self.converter->ecef2ned(fix_ecef + vel_ecef) VectorXd accDevice = predicted_state.segment(STATE_ACCELERATION_START); VectorXd accDeviceErr = predicted_std.segment(STATE_ACCELERATION_ERR_START); @@ -130,6 +128,7 @@ void Localizer::build_live_location(cereal::LiveLocationKalman::Builder& fix) { Vector3d nans = Vector3d(NAN, NAN, NAN); + // TODO fill in NED and Calibrated stds // write measurements to msg init_measurement(fix.initPositionGeodetic(), fix_pos_geo_vec, nans, this->gps_mode); init_measurement(fix.initPositionECEF(), fix_ecef, fix_ecef_std, this->gps_mode); @@ -139,7 +138,7 @@ void Localizer::build_live_location(cereal::LiveLocationKalman::Builder& fix) { init_measurement(fix.initAccelerationDevice(), accDevice, accDeviceErr, true); init_measurement(fix.initOrientationECEF(), orientation_ecef, orientation_ecef_std, this->gps_mode); init_measurement(fix.initCalibratedOrientationECEF(), calibrated_orientation_ecef, nans, this->calibrated && this->gps_mode); - init_measurement(fix.initOrientationNED(), orientation_ned, nans, this->gps_mode); + init_measurement(fix.initOrientationNED(), orientation_ned, orientation_ned_std, this->gps_mode); init_measurement(fix.initCalibratedOrientationNED(), calibrated_orientation_ned, nans, this->calibrated && this->gps_mode); init_measurement(fix.initAngularVelocityDevice(), angVelocityDevice, angVelocityDeviceErr, true); init_measurement(fix.initVelocityCalibrated(), vel_calib, vel_calib_std, this->calibrated); @@ -232,9 +231,10 @@ void Localizer::handle_sensors(double current_time, const capnp::Listdevice_fell |= (floatlist2vector(v) - Vector3d(10.0, 0.0, 0.0)).norm() > 40.0; + //this->device_fell |= (floatlist2vector(v) - Vector3d(10.0, 0.0, 0.0)).norm() > 40.0; auto meas = Vector3d(-v[2], -v[1], -v[0]); if (meas.norm() < ACCEL_SANITY_CHECK) { diff --git a/selfdrive/locationd/models/car_kf.py b/selfdrive/locationd/models/car_kf.py index dac95dcd7..75534efa5 100755 --- a/selfdrive/locationd/models/car_kf.py +++ b/selfdrive/locationd/models/car_kf.py @@ -5,6 +5,7 @@ from typing import Any, Dict import numpy as np +from selfdrive.controls.lib.vehicle_model import ACCELERATION_DUE_TO_GRAVITY from selfdrive.locationd.models.constants import ObservationKind from selfdrive.swaglog import cloudlog @@ -37,6 +38,7 @@ class States(): VELOCITY = _slice(2) # (x, y) [m/s] YAW_RATE = _slice(1) # [rad/s] STEER_ANGLE = _slice(1) # [rad] + ROAD_ROLL = _slice(1) # [rad] class CarKalman(KalmanFilter): @@ -51,6 +53,7 @@ class CarKalman(KalmanFilter): 10.0, 0.0, 0.0, 0.0, + 0.0 ]) # process noise @@ -63,14 +66,16 @@ class CarKalman(KalmanFilter): .1**2, .01**2, math.radians(0.1)**2, math.radians(0.1)**2, + math.radians(1)**2, ]) P_initial = Q.copy() obs_noise: Dict[int, Any] = { - ObservationKind.STEER_ANGLE: np.atleast_2d(math.radians(0.01)**2), + ObservationKind.STEER_ANGLE: np.atleast_2d(math.radians(0.05)**2), ObservationKind.ANGLE_OFFSET_FAST: np.atleast_2d(math.radians(10.0)**2), + ObservationKind.ROAD_ROLL: np.atleast_2d(math.radians(1.0)**2), ObservationKind.STEER_RATIO: np.atleast_2d(5.0**2), - ObservationKind.STIFFNESS: np.atleast_2d(5.0**2), + ObservationKind.STIFFNESS: np.atleast_2d(0.5**2), ObservationKind.ROAD_FRAME_X_SPEED: np.atleast_2d(0.1**2), } @@ -87,7 +92,7 @@ class CarKalman(KalmanFilter): def generate_code(generated_dir): dim_state = CarKalman.initial_x.shape[0] name = CarKalman.name - + # vehicle models comes from The Science of Vehicle Dynamics: Handling, Braking, and Ride of Road and Race Cars # Model used is in 6.15 with formula from 6.198 @@ -101,11 +106,12 @@ class CarKalman(KalmanFilter): state = sp.Matrix(state_sym) # Vehicle model constants - x = state[States.STIFFNESS, :][0, 0] + sf = state[States.STIFFNESS, :][0, 0] - cF, cR = x * cF_orig, x * cR_orig + cF, cR = sf * cF_orig, sf * cR_orig angle_offset = state[States.ANGLE_OFFSET, :][0, 0] angle_offset_fast = state[States.ANGLE_OFFSET_FAST, :][0, 0] + theta = state[States.ROAD_ROLL, :][0, 0] sa = state[States.STEER_ANGLE, :][0, 0] sR = state[States.STEER_RATIO, :][0, 0] @@ -122,8 +128,12 @@ class CarKalman(KalmanFilter): B[0, 0] = cF / m / sR B[1, 0] = (cF * aF) / j / sR + C = sp.Matrix(np.zeros((2, 1))) + C[0, 0] = ACCELERATION_DUE_TO_GRAVITY + C[1, 0] = 0 + x = sp.Matrix([v, r]) # lateral velocity, yaw rate - x_dot = A * x + B * (sa - angle_offset - angle_offset_fast) + x_dot = A * x + B * (sa - angle_offset - angle_offset_fast) - C * theta dt = sp.Symbol('dt') state_dot = sp.Matrix(np.zeros((dim_state, 1))) @@ -144,12 +154,13 @@ class CarKalman(KalmanFilter): [sp.Matrix([sa]), ObservationKind.STEER_ANGLE, None], [sp.Matrix([angle_offset_fast]), ObservationKind.ANGLE_OFFSET_FAST, None], [sp.Matrix([sR]), ObservationKind.STEER_RATIO, None], - [sp.Matrix([x]), ObservationKind.STIFFNESS, None], + [sp.Matrix([sf]), ObservationKind.STIFFNESS, None], + [sp.Matrix([theta]), ObservationKind.ROAD_ROLL, None], ] gen_code(generated_dir, name, f_sym, dt, state_sym, obs_eqs, dim_state, dim_state, global_vars=global_vars) - def __init__(self, generated_dir, steer_ratio=15, stiffness_factor=1, angle_offset=0): # pylint: disable=super-init-not-called + def __init__(self, generated_dir, steer_ratio=15, stiffness_factor=1, angle_offset=0, P_initial=None): # pylint: disable=super-init-not-called dim_state = self.initial_x.shape[0] dim_state_err = self.P_initial.shape[0] x_init = self.initial_x @@ -157,6 +168,8 @@ class CarKalman(KalmanFilter): x_init[States.STIFFNESS] = stiffness_factor x_init[States.ANGLE_OFFSET] = angle_offset + if P_initial is not None: + self.P_initial = P_initial # init filter self.filter = EKF_sym(generated_dir, self.name, self.Q, self.initial_x, self.P_initial, dim_state, dim_state_err, global_vars=self.global_vars, logger=cloudlog) diff --git a/selfdrive/locationd/models/constants.py b/selfdrive/locationd/models/constants.py index 7450f76be..f22f503ee 100644 --- a/selfdrive/locationd/models/constants.py +++ b/selfdrive/locationd/models/constants.py @@ -38,6 +38,7 @@ class ObservationKind: STIFFNESS = 28 # [-] STEER_RATIO = 29 # [-] ROAD_FRAME_X_SPEED = 30 # (x) [m/s] + ROAD_ROLL = 31 # [rad] names = [ 'Unknown', @@ -69,6 +70,8 @@ class ObservationKind: 'Fast Angle Offset', 'Stiffness', 'Steer Ratio', + 'Road Frame x speed', + 'Road Roll', ] @classmethod diff --git a/selfdrive/locationd/models/live_kf.py b/selfdrive/locationd/models/live_kf.py index fa5294593..023479d10 100755 --- a/selfdrive/locationd/models/live_kf.py +++ b/selfdrive/locationd/models/live_kf.py @@ -158,7 +158,7 @@ class LiveKalman(): delta_x = sp.MatrixSymbol('delta_x', dim_state_err, 1) err_function_sym = sp.Matrix(np.zeros((dim_state, 1))) - delta_quat = sp.Matrix(np.ones((4))) + delta_quat = sp.Matrix(np.ones(4)) delta_quat[1:, :] = sp.Matrix(0.5 * delta_x[States.ECEF_ORIENTATION_ERR, :]) err_function_sym[States.ECEF_POS, :] = sp.Matrix(nom_x[States.ECEF_POS, :] + delta_x[States.ECEF_POS_ERR, :]) err_function_sym[States.ECEF_ORIENTATION, 0] = quat_matrix_r(nom_x[States.ECEF_ORIENTATION, 0]) * delta_quat diff --git a/selfdrive/locationd/paramsd.py b/selfdrive/locationd/paramsd.py index 914e0d022..0efb4d04b 100755 --- a/selfdrive/locationd/paramsd.py +++ b/selfdrive/locationd/paramsd.py @@ -16,10 +16,12 @@ from selfdrive.swaglog import cloudlog MAX_ANGLE_OFFSET_DELTA = 20 * DT_MDL # Max 20 deg/s +ROLL_MAX_DELTA = np.radians(20.0) * DT_MDL # 20deg in 1 second is well within curvature limits +ROLL_MIN, ROLL_MAX = math.radians(-10), math.radians(10) class ParamsLearner: - def __init__(self, CP, steer_ratio, stiffness_factor, angle_offset): - self.kf = CarKalman(GENERATED_DIR, steer_ratio, stiffness_factor, angle_offset) + def __init__(self, CP, steer_ratio, stiffness_factor, angle_offset, P_initial=None): + self.kf = CarKalman(GENERATED_DIR, steer_ratio, stiffness_factor, angle_offset, P_initial) self.kf.filter.set_global("mass", CP.mass) self.kf.filter.set_global("rotational_inertia", CP.rotationalInertia) @@ -30,9 +32,10 @@ class ParamsLearner: self.active = False - self.speed = 0 + self.speed = 0.0 + self.roll = 0.0 self.steering_pressed = False - self.steering_angle = 0 + self.steering_angle = 0.0 self.valid = True @@ -41,18 +44,46 @@ class ParamsLearner: yaw_rate = msg.angularVelocityCalibrated.value[2] yaw_rate_std = msg.angularVelocityCalibrated.std[2] + localizer_roll = msg.orientationNED.value[0] + localizer_roll_std = np.radians(1) if np.isnan(msg.orientationNED.std[0]) else msg.orientationNED.std[0] + roll_valid = msg.orientationNED.valid and ROLL_MIN < localizer_roll < ROLL_MAX + if roll_valid: + roll = localizer_roll + # Experimentally found multiplier of 2 to be best trade-off between stability and accuracy or similar? + roll_std = 2 * localizer_roll_std + else: + # This is done to bound the road roll estimate when localizer values are invalid + roll = 0.0 + roll_std = np.radians(10.0) + self.roll = clip(roll, self.roll - ROLL_MAX_DELTA, self.roll + ROLL_MAX_DELTA) + yaw_rate_valid = msg.angularVelocityCalibrated.valid yaw_rate_valid = yaw_rate_valid and 0 < yaw_rate_std < 10 # rad/s yaw_rate_valid = yaw_rate_valid and abs(yaw_rate) < 1 # rad/s if self.active: - if msg.inputsOK and msg.posenetOK and yaw_rate_valid: + if msg.inputsOK and msg.posenetOK: + + if yaw_rate_valid: + self.kf.predict_and_observe(t, + ObservationKind.ROAD_FRAME_YAW_RATE, + np.array([[-yaw_rate]]), + np.array([np.atleast_2d(yaw_rate_std**2)])) + self.kf.predict_and_observe(t, - ObservationKind.ROAD_FRAME_YAW_RATE, - np.array([[-yaw_rate]]), - np.array([np.atleast_2d(yaw_rate_std**2)])) + ObservationKind.ROAD_ROLL, + np.array([[self.roll]]), + np.array([np.atleast_2d(roll_std**2)])) self.kf.predict_and_observe(t, ObservationKind.ANGLE_OFFSET_FAST, np.array([[0]])) + # We observe the current stiffness and steer ratio (with a high observation noise) to bound + # the respective estimate STD. Otherwise the STDs keep increasing, causing rapid changes in the + # states in longer routes (especially straight stretches). + stiffness = float(self.kf.x[States.STIFFNESS]) + steer_ratio = float(self.kf.x[States.STEER_RATIO]) + self.kf.predict_and_observe(t, ObservationKind.STIFFNESS, np.array([[stiffness]])) + self.kf.predict_and_observe(t, ObservationKind.STEER_RATIO, np.array([[steer_ratio]])) + elif which == 'carState': self.steering_angle = msg.steeringAngleDeg self.steering_pressed = msg.steeringPressed @@ -148,29 +179,31 @@ def main(sm=None, pm=None): msg = messaging.new_message('liveParameters') msg.logMonoTime = sm.logMonoTime['carState'] - msg.liveParameters.posenetValid = True - msg.liveParameters.sensorValid = True - msg.liveParameters.steerRatio = float(x[States.STEER_RATIO]) - msg.liveParameters.stiffnessFactor = float(x[States.STIFFNESS]) - msg.liveParameters.angleOffsetAverageDeg = angle_offset_average - msg.liveParameters.angleOffsetDeg = angle_offset - msg.liveParameters.valid = all(( - abs(msg.liveParameters.angleOffsetAverageDeg) < 10.0, - abs(msg.liveParameters.angleOffsetDeg) < 10.0, - 0.2 <= msg.liveParameters.stiffnessFactor <= 5.0, - min_sr <= msg.liveParameters.steerRatio <= max_sr, + liveParameters = msg.liveParameters + liveParameters.posenetValid = True + liveParameters.sensorValid = True + liveParameters.steerRatio = float(x[States.STEER_RATIO]) + liveParameters.stiffnessFactor = float(x[States.STIFFNESS]) + liveParameters.roll = float(x[States.ROAD_ROLL]) + liveParameters.angleOffsetAverageDeg = angle_offset_average + liveParameters.angleOffsetDeg = angle_offset + liveParameters.valid = all(( + abs(liveParameters.angleOffsetAverageDeg) < 10.0, + abs(liveParameters.angleOffsetDeg) < 10.0, + 0.2 <= liveParameters.stiffnessFactor <= 5.0, + min_sr <= liveParameters.steerRatio <= max_sr, )) - msg.liveParameters.steerRatioStd = float(P[States.STEER_RATIO]) - msg.liveParameters.stiffnessFactorStd = float(P[States.STIFFNESS]) - msg.liveParameters.angleOffsetAverageStd = float(P[States.ANGLE_OFFSET]) - msg.liveParameters.angleOffsetFastStd = float(P[States.ANGLE_OFFSET_FAST]) + liveParameters.steerRatioStd = float(P[States.STEER_RATIO]) + liveParameters.stiffnessFactorStd = float(P[States.STIFFNESS]) + liveParameters.angleOffsetAverageStd = float(P[States.ANGLE_OFFSET]) + liveParameters.angleOffsetFastStd = float(P[States.ANGLE_OFFSET_FAST]) if sm.frame % 1200 == 0: # once a minute params = { 'carFingerprint': CP.carFingerprint, - 'steerRatio': msg.liveParameters.steerRatio, - 'stiffnessFactor': msg.liveParameters.stiffnessFactor, - 'angleOffsetAverageDeg': msg.liveParameters.angleOffsetAverageDeg, + 'steerRatio': liveParameters.steerRatio, + 'stiffnessFactor': liveParameters.stiffnessFactor, + 'angleOffsetAverageDeg': liveParameters.angleOffsetAverageDeg, } put_nonblocking("LiveParameters", json.dumps(params)) diff --git a/selfdrive/locationd/ublox_msg.h b/selfdrive/locationd/ublox_msg.h index b8a48ad2d..da1c180c0 100644 --- a/selfdrive/locationd/ublox_msg.h +++ b/selfdrive/locationd/ublox_msg.h @@ -23,11 +23,6 @@ namespace ublox { const int UBLOX_CHECKSUM_SIZE = 2; const int UBLOX_MAX_MSG_SIZE = 65536; - // Boardd still uses these: - const uint8_t CLASS_NAV = 0x01; - const uint8_t CLASS_RXM = 0x02; - const uint8_t CLASS_MON = 0x0A; - struct ubx_mga_ini_time_utc_t { uint8_t type; uint8_t version; diff --git a/selfdrive/logcatd/logcatd_android.cc b/selfdrive/logcatd/logcatd_android.cc index 1a982a0fe..8c2524d94 100644 --- a/selfdrive/logcatd/logcatd_android.cc +++ b/selfdrive/logcatd/logcatd_android.cc @@ -1,72 +1,51 @@ -#include -#include - #include #include #include +#include + +#include #include "cereal/messaging/messaging.h" -#include "selfdrive/common/util.h" + +#undef LOG_ID_KERNEL +#define LOG_ID_KERNEL 5 int main() { + std::signal(SIGINT, exit); + std::signal(SIGTERM, exit); setpriority(PRIO_PROCESS, 0, -15); - ExitHandler do_exit; + // setup android logging + logger_list *logger_list = android_logger_list_alloc(ANDROID_LOG_RDONLY, 0, 0); + assert(logger_list); + for (auto log_id : {LOG_ID_MAIN, LOG_ID_RADIO, LOG_ID_SYSTEM, LOG_ID_CRASH, (log_id_t)LOG_ID_KERNEL}) { + logger *logger = android_logger_open(logger_list, log_id); + assert(logger); + } + PubMaster pm({"androidLog"}); - log_time last_log_time = {}; - logger_list *logger_list = android_logger_list_alloc(ANDROID_LOG_RDONLY | ANDROID_LOG_NONBLOCK, 0, 0); + while (true) { + log_msg log_msg; + int err = android_logger_list_read(logger_list, &log_msg); + if (err <= 0) break; - while (!do_exit) { - // setup android logging - if (!logger_list) { - logger_list = android_logger_list_alloc_time(ANDROID_LOG_RDONLY | ANDROID_LOG_NONBLOCK, last_log_time, 0); - } - assert(logger_list); + AndroidLogEntry entry; + err = android_log_processLogBuffer(&log_msg.entry_v1, &entry); + if (err < 0) continue; - struct logger *main_logger = android_logger_open(logger_list, LOG_ID_MAIN); - assert(main_logger); - struct logger *radio_logger = android_logger_open(logger_list, LOG_ID_RADIO); - assert(radio_logger); - struct logger *system_logger = android_logger_open(logger_list, LOG_ID_SYSTEM); - assert(system_logger); - struct logger *crash_logger = android_logger_open(logger_list, LOG_ID_CRASH); - assert(crash_logger); - struct logger *kernel_logger = android_logger_open(logger_list, (log_id_t)5); // LOG_ID_KERNEL - assert(kernel_logger); - - while (!do_exit) { - log_msg log_msg; - int err = android_logger_list_read(logger_list, &log_msg); - if (err <= 0) break; - - AndroidLogEntry entry; - err = android_log_processLogBuffer(&log_msg.entry_v1, &entry); - if (err < 0) continue; - last_log_time.tv_sec = entry.tv_sec; - last_log_time.tv_nsec = entry.tv_nsec; - - MessageBuilder msg; - auto androidEntry = msg.initEvent().initAndroidLog(); - androidEntry.setId(log_msg.id()); - androidEntry.setTs(entry.tv_sec * 1000000000ULL + entry.tv_nsec); - androidEntry.setPriority(entry.priority); - androidEntry.setPid(entry.pid); - androidEntry.setTid(entry.tid); - androidEntry.setTag(entry.tag); - androidEntry.setMessage(entry.message); - - pm.send("androidLog", msg); - } - - android_logger_list_free(logger_list); - logger_list = NULL; - util::sleep_for(500); - } - - if (logger_list) { - android_logger_list_free(logger_list); + MessageBuilder msg; + auto androidEntry = msg.initEvent().initAndroidLog(); + androidEntry.setId(log_msg.id()); + androidEntry.setTs(entry.tv_sec * NS_PER_SEC + entry.tv_nsec); + androidEntry.setPriority(entry.priority); + androidEntry.setPid(entry.pid); + androidEntry.setTid(entry.tid); + androidEntry.setTag(entry.tag); + androidEntry.setMessage(entry.message); + pm.send("androidLog", msg); } + android_logger_list_free(logger_list); return 0; } diff --git a/selfdrive/logcatd/logcatd_systemd.cc b/selfdrive/logcatd/logcatd_systemd.cc index 7c7800dfe..dabb11adc 100644 --- a/selfdrive/logcatd/logcatd_systemd.cc +++ b/selfdrive/logcatd/logcatd_systemd.cc @@ -24,6 +24,10 @@ int main(int argc, char *argv[]) { err = sd_journal_seek_tail(journal); assert(err >= 0); + // workaround for bug https://github.com/systemd/systemd/issues/9934 + // call sd_journal_previous_skip after sd_journal_seek_tail (like journalctl -f does) to makes things work. + sd_journal_previous_skip(journal, 1); + while (!do_exit) { err = sd_journal_next(journal); assert(err >= 0); diff --git a/selfdrive/loggerd/SConscript b/selfdrive/loggerd/SConscript index 2adcfb846..76fbcae6c 100644 --- a/selfdrive/loggerd/SConscript +++ b/selfdrive/loggerd/SConscript @@ -1,13 +1,12 @@ Import('env', 'arch', 'cereal', 'messaging', 'common', 'visionipc', 'gpucommon') -logger_lib = env.Library('logger', ["logger.cc"]) -libs = [logger_lib, common, cereal, messaging, visionipc, +libs = [common, cereal, messaging, visionipc, 'zmq', 'capnp', 'kj', 'z', 'avformat', 'avcodec', 'swscale', 'avutil', 'yuv', 'bz2', 'OpenCL'] -src = ['loggerd.cc'] +src = ['logger.cc', 'loggerd.cc'] if arch in ["aarch64", "larch64"]: src += ['omx_encoder.cc'] libs += ['OmxCore', 'gsl', 'CB'] + gpucommon @@ -24,8 +23,11 @@ if arch == "Darwin": del libs[libs.index('OpenCL')] env['FRAMEWORKS'] = ['OpenCL'] -env.Program('loggerd', ['main.cc'] + src, LIBS=libs) +logger_lib = env.Library('logger', src) +libs.insert(0, logger_lib) + +env.Program('loggerd', ['main.cc'], LIBS=libs) env.Program('bootlog.cc', LIBS=libs) if GetOption('test'): - env.Program('tests/test_logger', ['tests/test_runner.cc', 'tests/test_loggerd.cc', 'tests/test_logger.cc', env.Object('logger_util', '#/selfdrive/ui/replay/util.cc')] + src, LIBS=[libs] + ['curl', 'crypto', 'bz2']) + env.Program('tests/test_logger', ['tests/test_runner.cc', 'tests/test_loggerd.cc', 'tests/test_logger.cc', env.Object('logger_util', '#/selfdrive/ui/replay/util.cc')], LIBS=libs + ['curl', 'crypto']) diff --git a/selfdrive/loggerd/bootlog.cc b/selfdrive/loggerd/bootlog.cc index 520995837..c5897091d 100644 --- a/selfdrive/loggerd/bootlog.cc +++ b/selfdrive/loggerd/bootlog.cc @@ -11,6 +11,8 @@ static kj::Array build_boot_log() { if (Hardware::TICI()) { bootlog_commands.push_back("journalctl"); bootlog_commands.push_back("sudo nvme smart-log --output-format=json /dev/nvme0"); + } else if (Hardware::EON()) { + bootlog_commands.push_back("logcat -d"); } MessageBuilder msg; @@ -21,20 +23,13 @@ static kj::Array build_boot_log() { std::string pstore = "/sys/fs/pstore"; std::map pstore_map = util::read_files_in_dir(pstore); - const std::vector log_keywords = {"Kernel panic"}; - auto lpstore = boot.initPstore().initEntries(pstore_map.size()); int i = 0; + auto lpstore = boot.initPstore().initEntries(pstore_map.size()); for (auto& kv : pstore_map) { auto lentry = lpstore[i]; lentry.setKey(kv.first); lentry.setValue(capnp::Data::Reader((const kj::byte*)kv.second.data(), kv.second.size())); i++; - - for (auto &k : log_keywords) { - if (kv.second.find(k) != std::string::npos) { - LOGE("%s: found '%s'", kv.first.c_str(), k.c_str()); - } - } } // Gather output of commands diff --git a/selfdrive/loggerd/config.py b/selfdrive/loggerd/config.py index b626073ce..6cd20a68a 100644 --- a/selfdrive/loggerd/config.py +++ b/selfdrive/loggerd/config.py @@ -13,6 +13,13 @@ else: CAMERA_FPS = 20 SEGMENT_LENGTH = 60 +STATS_DIR_FILE_LIMIT = 10000 +STATS_SOCKET = "ipc:///tmp/stats" +if PC: + STATS_DIR = os.path.join(str(Path.home()), ".comma", "stats") +else: + STATS_DIR = "/data/stats/" +STATS_FLUSH_TIME_S = 60 def get_available_percent(default=None): try: diff --git a/selfdrive/loggerd/deleter.py b/selfdrive/loggerd/deleter.py index 16083ec92..e7006a08c 100644 --- a/selfdrive/loggerd/deleter.py +++ b/selfdrive/loggerd/deleter.py @@ -27,11 +27,11 @@ def deleter_thread(exit_event): continue try: - cloudlog.info("deleting %s" % delete_path) + cloudlog.info(f"deleting {delete_path}") shutil.rmtree(delete_path) break except OSError: - cloudlog.exception("issue deleting %s" % delete_path) + cloudlog.exception(f"issue deleting {delete_path}") exit_event.wait(.1) else: exit_event.wait(30) diff --git a/selfdrive/loggerd/loggerd.cc b/selfdrive/loggerd/loggerd.cc index 37f03ef4e..d402c5787 100644 --- a/selfdrive/loggerd/loggerd.cc +++ b/selfdrive/loggerd/loggerd.cc @@ -11,14 +11,14 @@ bool sync_encoders(LoggerdState *s, CameraType cam_type, uint32_t frame_id) { update_max_atomic(s->start_frame_id, frame_id + 2); if (std::exchange(s->camera_ready[cam_type], true) == false) { ++s->encoders_ready; - LOGE("camera %d encoder ready", cam_type); + LOGD("camera %d encoder ready", cam_type); } return false; } else { if (s->max_waiting == 1) update_max_atomic(s->start_frame_id, frame_id); bool synced = frame_id >= s->start_frame_id; s->camera_synced[cam_type] = synced; - if (!synced) LOGE("camera %d waiting for frame %d, cur %d", cam_type, (int)s->start_frame_id, frame_id); + if (!synced) LOGD("camera %d waiting for frame %d, cur %d", cam_type, (int)s->start_frame_id, frame_id); return synced; } } @@ -244,7 +244,7 @@ void loggerd_thread() { count++; if (count >= 200) { - LOGE("large volume of '%s' messages", qs.name.c_str()); + LOGD("large volume of '%s' messages", qs.name.c_str()); break; } } diff --git a/selfdrive/loggerd/loggerd.h b/selfdrive/loggerd/loggerd.h index bdf5ef8f9..caacbc591 100644 --- a/selfdrive/loggerd/loggerd.h +++ b/selfdrive/loggerd/loggerd.h @@ -80,7 +80,7 @@ const LogCameraInfo cameras_logged[] = { .downscale = false, .has_qcamera = false, .trigger_rotate = Hardware::TICI(), - .enable = !Hardware::PC(), + .enable = true, .record = Params().getBool("RecordFront"), }, { diff --git a/selfdrive/loggerd/raw_logger.cc b/selfdrive/loggerd/raw_logger.cc index b0f9f7a9c..f103822a1 100644 --- a/selfdrive/loggerd/raw_logger.cc +++ b/selfdrive/loggerd/raw_logger.cc @@ -11,6 +11,8 @@ #define __STDC_CONSTANT_MACROS +#include "libyuv.h" + extern "C" { #include #include @@ -55,6 +57,10 @@ RawLogger::RawLogger(const char* filename, int width, int height, int fps, frame->linesize[0] = width; frame->linesize[1] = width/2; frame->linesize[2] = width/2; + + if (downscale) { + downscale_buf.resize(width * height * 3 / 2); + } } RawLogger::~RawLogger() { @@ -64,7 +70,7 @@ RawLogger::~RawLogger() { } void RawLogger::encoder_open(const char* path) { - vid_path = util::string_format("%s/%s.mkv", path, filename); + vid_path = util::string_format("%s/%s", path, filename); // create camera lock file lock_path = util::string_format("%s/%s.lock", path, filename); @@ -76,7 +82,7 @@ void RawLogger::encoder_open(const char* path) { close(lock_fd); format_ctx = NULL; - avformat_alloc_output_context2(&format_ctx, NULL, NULL, vid_path.c_str()); + avformat_alloc_output_context2(&format_ctx, NULL, "matroska", vid_path.c_str()); assert(format_ctx); stream = avformat_new_stream(format_ctx, codec); @@ -124,9 +130,27 @@ int RawLogger::encode_frame(const uint8_t *y_ptr, const uint8_t *u_ptr, const ui pkt.data = NULL; pkt.size = 0; - frame->data[0] = (uint8_t*)y_ptr; - frame->data[1] = (uint8_t*)u_ptr; - frame->data[2] = (uint8_t*)v_ptr; + if (downscale_buf.size() > 0) { + uint8_t *out_y = downscale_buf.data(); + uint8_t *out_u = out_y + codec_ctx->width * codec_ctx->height; + uint8_t *out_v = out_u + (codec_ctx->width / 2) * (codec_ctx->height / 2); + libyuv::I420Scale(y_ptr, in_width, + u_ptr, in_width/2, + v_ptr, in_width/2, + in_width, in_height, + out_y, codec_ctx->width, + out_u, codec_ctx->width/2, + out_v, codec_ctx->width/2, + codec_ctx->width, codec_ctx->height, + libyuv::kFilterNone); + frame->data[0] = out_y; + frame->data[1] = out_u; + frame->data[2] = out_v; + } else { + frame->data[0] = (uint8_t*)y_ptr; + frame->data[1] = (uint8_t*)u_ptr; + frame->data[2] = (uint8_t*)v_ptr; + } frame->pts = counter; int ret = counter; diff --git a/selfdrive/loggerd/raw_logger.h b/selfdrive/loggerd/raw_logger.h index 9cef7ddca..75d906784 100644 --- a/selfdrive/loggerd/raw_logger.h +++ b/selfdrive/loggerd/raw_logger.h @@ -39,4 +39,5 @@ private: AVFormatContext *format_ctx = NULL; AVFrame *frame = NULL; + std::vector downscale_buf; }; diff --git a/selfdrive/loggerd/uploader.py b/selfdrive/loggerd/uploader.py index 10bf218b0..2013a522b 100644 --- a/selfdrive/loggerd/uploader.py +++ b/selfdrive/loggerd/uploader.py @@ -140,7 +140,7 @@ class Uploader(): cloudlog.debug("upload_url v1.4 %s %s", url, str(headers)) if fake_upload: - cloudlog.debug("*** WARNING, THIS IS A FAKE UPLOAD TO %s ***" % url) + cloudlog.debug(f"*** WARNING, THIS IS A FAKE UPLOAD TO {url} ***") class FakeResponse(): def __init__(self): @@ -165,16 +165,14 @@ class Uploader(): return self.last_resp - def upload(self, key, fn): + def upload(self, key, fn, network_type): try: sz = os.path.getsize(fn) except OSError: cloudlog.exception("upload: getsize failed") return False - cloudlog.event("upload", key=key, fn=fn, sz=sz) - - cloudlog.debug("checking %r with size %r", key, sz) + cloudlog.event("upload_start", key=key, fn=fn, sz=sz, network_type=network_type) if sz == 0: try: @@ -185,10 +183,8 @@ class Uploader(): success = True else: start_time = time.monotonic() - cloudlog.debug("uploading %r", fn) stat = self.normal_upload(key, fn) if stat is not None and stat.status_code in (200, 201, 403, 412): - cloudlog.event("upload_success" if stat.status_code != 412 else "upload_ignored", key=key, fn=fn, sz=sz, debug=True) try: # tag file as uploaded setxattr(fn, UPLOAD_ATTR_NAME, UPLOAD_ATTR_VALUE) @@ -199,9 +195,10 @@ class Uploader(): self.last_time = time.monotonic() - start_time self.last_speed = (sz / 1e6) / self.last_time success = True + cloudlog.event("upload_success" if stat.status_code != 412 else "upload_ignored", key=key, fn=fn, sz=sz, network_type=network_type) else: - cloudlog.event("upload_failed", stat=stat, exc=self.last_exc, key=key, fn=fn, sz=sz, debug=True) success = False + cloudlog.event("upload_failed", stat=stat, exc=self.last_exc, key=key, fn=fn, sz=sz, network_type=network_type) return success @@ -248,8 +245,7 @@ def uploader_fn(exit_event): key, fn = d - cloudlog.debug("upload %r over %s", d, network_type) - success = uploader.upload(key, fn) + success = uploader.upload(key, fn, sm['deviceState'].networkType.raw) if success: backoff = 0.1 elif allow_sleep: @@ -258,7 +254,6 @@ def uploader_fn(exit_event): backoff = min(backoff*2, 120) pm.send("uploaderState", uploader.get_msg()) - cloudlog.info("upload done, success=%r", success) def main(): uploader_fn(threading.Event()) diff --git a/selfdrive/loggerd/xattr_cache.py b/selfdrive/loggerd/xattr_cache.py index aa97f0c77..e72169250 100644 --- a/selfdrive/loggerd/xattr_cache.py +++ b/selfdrive/loggerd/xattr_cache.py @@ -1,13 +1,15 @@ +from typing import Dict, Tuple + from common.xattr import getxattr as getattr1 from common.xattr import setxattr as setattr1 -cached_attributes = {} -def getxattr(path, attr_name): +cached_attributes: Dict[Tuple, bytes] = {} +def getxattr(path: str, attr_name: bytes) -> bytes: if (path, attr_name) not in cached_attributes: response = getattr1(path, attr_name) cached_attributes[(path, attr_name)] = response return cached_attributes[(path, attr_name)] -def setxattr(path, attr_name, attr_value): +def setxattr(path: str, attr_name: str, attr_value: bytes) -> None: cached_attributes.pop((path, attr_name), None) return setattr1(path, attr_name, attr_value) diff --git a/selfdrive/logmessaged.py b/selfdrive/logmessaged.py index 9c4097656..1d1fab516 100755 --- a/selfdrive/logmessaged.py +++ b/selfdrive/logmessaged.py @@ -17,7 +17,8 @@ def main() -> NoReturn: sock.bind("ipc:///tmp/logmessage") # and we publish them - pub_sock = messaging.pub_sock('logMessage') + log_message_sock = messaging.pub_sock('logMessage') + error_log_message_sock = messaging.pub_sock('errorLogMessage') while True: dat = b''.join(sock.recv_multipart()) @@ -29,7 +30,12 @@ def main() -> NoReturn: # then we publish them msg = messaging.new_message() msg.logMessage = record - pub_sock.send(msg.to_bytes()) + log_message_sock.send(msg.to_bytes()) + + if level >= 40: # logging.ERROR + msg = messaging.new_message() + msg.errorLogMessage = record + error_log_message_sock.send(msg.to_bytes()) if __name__ == "__main__": diff --git a/selfdrive/manager/build.py b/selfdrive/manager/build.py index 078f18fd2..4b97855f3 100755 --- a/selfdrive/manager/build.py +++ b/selfdrive/manager/build.py @@ -12,7 +12,7 @@ from common.spinner import Spinner from common.text_window import TextWindow from selfdrive.hardware import TICI from selfdrive.swaglog import cloudlog, add_file_handler -from selfdrive.version import get_dirty +from selfdrive.version import is_dirty MAX_CACHE_SIZE = 4e9 if "CI" in os.environ else 2e9 CACHE_DIR = Path("/data/scons_cache" if TICI else "/tmp/scons_cache") @@ -22,7 +22,7 @@ MAX_BUILD_PROGRESS = 100 PREBUILT = os.path.exists(os.path.join(BASEDIR, 'prebuilt')) -def build(spinner, dirty=False): +def build(spinner: Spinner, dirty: bool = False) -> None: env = os.environ.copy() env['SCONS_PROGRESS'] = "1" nproc = os.cpu_count() @@ -30,6 +30,7 @@ def build(spinner, dirty=False): for retry in [True, False]: scons = subprocess.Popen(["scons", j_flag, "--cache-populate"], cwd=BASEDIR, env=env, stderr=subprocess.PIPE) + assert scons.stderr is not None compile_output = [] @@ -98,4 +99,4 @@ def build(spinner, dirty=False): if __name__ == "__main__" and not PREBUILT: spinner = Spinner() spinner.update_progress(0, 100) - build(spinner, get_dirty()) + build(spinner, is_dirty()) diff --git a/selfdrive/manager/helpers.py b/selfdrive/manager/helpers.py index fdda0deb9..b07362dd4 100644 --- a/selfdrive/manager/helpers.py +++ b/selfdrive/manager/helpers.py @@ -5,7 +5,7 @@ import errno import signal -def unblock_stdout(): +def unblock_stdout() -> None: # get a non-blocking stdout child_pid, child_pty = os.forkpty() if child_pid != 0: # parent @@ -29,7 +29,7 @@ def unblock_stdout(): try: sys.stdout.write(dat.decode('utf8')) - except (OSError, IOError, UnicodeDecodeError): + except (OSError, UnicodeDecodeError): pass # os.wait() returns a tuple with the pid and a 16 bit value diff --git a/selfdrive/manager/manager.py b/selfdrive/manager/manager.py index 386876b69..21b8cb965 100755 --- a/selfdrive/manager/manager.py +++ b/selfdrive/manager/manager.py @@ -5,9 +5,10 @@ import signal import subprocess import sys import traceback +from typing import List, Tuple, Union import cereal.messaging as messaging -import selfdrive.crash as crash +import selfdrive.sentry as sentry from common.basedir import BASEDIR from common.params import Params, ParamKeyType from common.text_window import TextWindow @@ -18,14 +19,14 @@ from selfdrive.manager.process import ensure_running from selfdrive.manager.process_config import managed_processes from selfdrive.athena.registration import register, UNREGISTERED_DONGLE_ID from selfdrive.swaglog import cloudlog, add_file_handler -from selfdrive.version import get_dirty, get_commit, get_version, get_origin, get_short_branch, \ - terms_version, training_version, get_comma_remote +from selfdrive.version import is_dirty, get_commit, get_version, get_origin, get_short_branch, \ + terms_version, training_version sys.path.append(os.path.join(BASEDIR, "pyextra")) -def manager_init(): +def manager_init() -> None: # update system time from panda set_time(cloudlog) @@ -35,7 +36,7 @@ def manager_init(): params = Params() params.clear_all(ParamKeyType.CLEAR_ON_MANAGER_START) - default_params = [ + default_params: List[Tuple[str, Union[str, bytes]]] = [ ("CompletedTrainingVersion", "0"), ("HasAcceptedTerms", "0"), ("OpenpilotEnabledToggle", "1"), @@ -56,7 +57,7 @@ def manager_init(): # is this dashcam? if os.getenv("PASSIVE") is not None: - params.put_bool("Passive", bool(int(os.getenv("PASSIVE")))) + params.put_bool("Passive", bool(int(os.getenv("PASSIVE", "0")))) if params.get("Passive") is None: raise Exception("Passive must be set to continue") @@ -86,25 +87,21 @@ def manager_init(): raise Exception(f"Registration failed for device {serial}") os.environ['DONGLE_ID'] = dongle_id # Needed for swaglog - if not get_dirty(): + if not is_dirty(): os.environ['CLEAN'] = '1' - cloudlog.bind_global(dongle_id=dongle_id, version=get_version(), dirty=get_dirty(), + # init logging + sentry.init(sentry.SentryProject.SELFDRIVE) + cloudlog.bind_global(dongle_id=dongle_id, version=get_version(), dirty=is_dirty(), device=HARDWARE.get_device_type()) - if get_comma_remote() and not (os.getenv("NOLOG") or os.getenv("NOCRASH") or PC): - crash.init() - crash.bind_user(id=dongle_id) - crash.bind_extra(dirty=get_dirty(), origin=get_origin(), branch=get_short_branch(), commit=get_commit(), - device=HARDWARE.get_device_type()) - -def manager_prepare(): +def manager_prepare() -> None: for p in managed_processes.values(): p.prepare() -def manager_cleanup(): +def manager_cleanup() -> None: # send signals to kill all procs for p in managed_processes.values(): p.stop(block=False) @@ -116,19 +113,19 @@ def manager_cleanup(): cloudlog.info("everything is dead") -def manager_thread(): +def manager_thread() -> None: + cloudlog.bind(daemon="manager") cloudlog.info("manager start") cloudlog.info({"environ": os.environ}) params = Params() - ignore = [] - if params.get("DongleId", encoding='utf8') == UNREGISTERED_DONGLE_ID: + ignore: List[str] = [] + if params.get("DongleId", encoding='utf8') in (None, UNREGISTERED_DONGLE_ID): ignore += ["manage_athenad", "uploader"] if os.getenv("NOBOARD") is not None: ignore.append("pandad") - if os.getenv("BLOCK") is not None: - ignore += os.getenv("BLOCK").split(",") + ignore += [x for x in os.getenv("BLOCK", "").split(",") if len(x) > 0] ensure_running(managed_processes.values(), started=False, not_run=ignore) @@ -140,9 +137,6 @@ def manager_thread(): sm.update() not_run = ignore[:] - if sm['deviceState'].freeSpacePercent < 5: - not_run.append("loggerd") - started = sm['deviceState'].started driverview = params.get_bool("IsDriverViewEnabled") ensure_running(managed_processes.values(), started, driverview, not_run) @@ -168,14 +162,15 @@ def manager_thread(): shutdown = False for param in ("DoUninstall", "DoShutdown", "DoReboot"): if params.get_bool(param): - cloudlog.warning(f"Shutting down manager - {param} set") shutdown = True + params.put("LastManagerExitReason", param) + cloudlog.warning(f"Shutting down manager - {param} set") if shutdown: break -def main(): +def main() -> None: prepare_only = os.getenv("PREPAREONLY") is not None manager_init() @@ -196,7 +191,7 @@ def main(): manager_thread() except Exception: traceback.print_exc() - crash.capture_exception() + sentry.capture_exception() finally: manager_cleanup() @@ -221,6 +216,11 @@ if __name__ == "__main__": add_file_handler(cloudlog) cloudlog.exception("Manager failed to start") + try: + managed_processes['ui'].stop() + except Exception: + pass + # Show last 3 lines of traceback error = traceback.format_exc(-3) error = "Manager failed to start\n\n" + error diff --git a/selfdrive/manager/process.py b/selfdrive/manager/process.py index d9a161941..ebdd2a90b 100644 --- a/selfdrive/manager/process.py +++ b/selfdrive/manager/process.py @@ -4,13 +4,14 @@ import signal import struct import time import subprocess +from typing import Optional, List, ValuesView from abc import ABC, abstractmethod from multiprocessing import Process from setproctitle import setproctitle # pylint: disable=no-name-in-module import cereal.messaging as messaging -import selfdrive.crash as crash +import selfdrive.sentry as sentry from common.basedir import BASEDIR from common.params import Params from common.realtime import sec_since_boot @@ -22,7 +23,7 @@ WATCHDOG_FN = "/dev/shm/wd_" ENABLE_WATCHDOG = os.getenv("NO_WATCHDOG") is None -def launcher(proc): +def launcher(proc: str, name: str) -> None: try: # import the process mod = importlib.import_module(proc) @@ -33,24 +34,30 @@ def launcher(proc): # create new context since we forked messaging.context = messaging.Context() + # add daemon name tag to logs + cloudlog.bind(daemon=name) + sentry.set_tag("daemon", name) + # exec the process - mod.main() + getattr(mod, 'main')() except KeyboardInterrupt: - cloudlog.warning("child %s got SIGINT" % proc) + cloudlog.warning(f"child {proc} got SIGINT") except Exception: # can't install the crash handler because sys.excepthook doesn't play nice # with threads, so catch it here. - crash.capture_exception() + sentry.capture_exception() raise -def nativelauncher(pargs, cwd): +def nativelauncher(pargs: List[str], cwd: str, name: str) -> None: + os.environ['MANAGER_DAEMON'] = name + # exec the process os.chdir(cwd) os.execvp(pargs[0], pargs) -def join_process(process, timeout): +def join_process(process: Process, timeout: float) -> None: # Process().join(timeout) will hang due to a python 3 bug: https://bugs.python.org/issue28382 # We have to poll the exitcode instead t = time.monotonic() @@ -62,7 +69,9 @@ class ManagerProcess(ABC): unkillable = False daemon = False sigkill = False - proc = None + persistent = False + driverview = False + proc: Optional[Process] = None enabled = True name = "" @@ -72,24 +81,25 @@ class ManagerProcess(ABC): shutting_down = False @abstractmethod - def prepare(self): + def prepare(self) -> None: pass @abstractmethod - def start(self): + def start(self) -> None: pass - def restart(self): + def restart(self) -> None: self.stop() self.start() - def check_watchdog(self, started): + def check_watchdog(self, started: bool) -> None: if self.watchdog_max_dt is None or self.proc is None: return try: fn = WATCHDOG_FN + str(self.proc.pid) - self.last_watchdog_time = struct.unpack('Q', open(fn, "rb").read())[0] + # TODO: why can't pylint find struct.unpack? + self.last_watchdog_time = struct.unpack('Q', open(fn, "rb").read())[0] # pylint: disable=no-member except Exception: pass @@ -103,9 +113,9 @@ class ManagerProcess(ABC): else: self.watchdog_seen = True - def stop(self, retry=True, block=True): + def stop(self, retry: bool=True, block: bool=True) -> Optional[int]: if self.proc is None: - return + return None if self.proc.exitcode is None: if not self.shutting_down: @@ -115,7 +125,7 @@ class ManagerProcess(ABC): self.shutting_down = True if not block: - return + return None join_process(self.proc, 5) @@ -145,7 +155,7 @@ class ManagerProcess(ABC): return ret - def signal(self, sig): + def signal(self, sig: int) -> None: if self.proc is None: return @@ -153,6 +163,10 @@ class ManagerProcess(ABC): if self.proc.exitcode is not None and self.proc.pid is not None: return + # Can't signal if we don't have a pid + if self.proc.pid is None: + return + cloudlog.info(f"sending signal {sig} to {self.name}") os.kill(self.proc.pid, sig) @@ -179,10 +193,10 @@ class NativeProcess(ManagerProcess): self.sigkill = sigkill self.watchdog_max_dt = watchdog_max_dt - def prepare(self): + def prepare(self) -> None: pass - def start(self): + def start(self) -> None: # In case we only tried a non blocking stop we need to stop it before restarting if self.shutting_down: self.stop() @@ -191,8 +205,8 @@ class NativeProcess(ManagerProcess): return cwd = os.path.join(BASEDIR, self.cwd) - cloudlog.info("starting process %s" % self.name) - self.proc = Process(name=self.name, target=nativelauncher, args=(self.cmdline, cwd)) + cloudlog.info(f"starting process {self.name}") + self.proc = Process(name=self.name, target=nativelauncher, args=(self.cmdline, cwd, self.name)) self.proc.start() self.watchdog_seen = False self.shutting_down = False @@ -209,12 +223,12 @@ class PythonProcess(ManagerProcess): self.sigkill = sigkill self.watchdog_max_dt = watchdog_max_dt - def prepare(self): + def prepare(self) -> None: if self.enabled: - cloudlog.info("preimporting %s" % self.module) + cloudlog.info(f"preimporting {self.module}") importlib.import_module(self.module) - def start(self): + def start(self) -> None: # In case we only tried a non blocking stop we need to stop it before restarting if self.shutting_down: self.stop() @@ -222,8 +236,8 @@ class PythonProcess(ManagerProcess): if self.proc is not None: return - cloudlog.info("starting python %s" % self.module) - self.proc = Process(name=self.name, target=launcher, args=(self.module,)) + cloudlog.info(f"starting python {self.module}") + self.proc = Process(name=self.name, target=launcher, args=(self.module, self.name)) self.proc.start() self.watchdog_seen = False self.shutting_down = False @@ -239,10 +253,10 @@ class DaemonProcess(ManagerProcess): self.enabled = enabled self.persistent = True - def prepare(self): + def prepare(self) -> None: pass - def start(self): + def start(self) -> None: params = Params() pid = params.get(self.param_name, encoding='utf-8') @@ -257,20 +271,20 @@ class DaemonProcess(ManagerProcess): # process is dead pass - cloudlog.info("starting daemon %s" % self.name) + cloudlog.info(f"starting daemon {self.name}") proc = subprocess.Popen(['python', '-m', self.module], # pylint: disable=subprocess-popen-preexec-fn - stdin=open('/dev/null', 'r'), + stdin=open('/dev/null'), stdout=open('/dev/null', 'w'), stderr=open('/dev/null', 'w'), preexec_fn=os.setpgrp) params.put(self.param_name, str(proc.pid)) - def stop(self, retry=True, block=True): + def stop(self, retry=True, block=True) -> None: pass -def ensure_running(procs, started, driverview=False, not_run=None): +def ensure_running(procs: ValuesView[ManagerProcess], started: bool, driverview: bool=False, not_run: Optional[List[str]]=None) -> None: if not_run is None: not_run = [] diff --git a/selfdrive/manager/process_config.py b/selfdrive/manager/process_config.py index 2e3741350..c017e48fa 100644 --- a/selfdrive/manager/process_config.py +++ b/selfdrive/manager/process_config.py @@ -1,7 +1,7 @@ import os -from selfdrive.manager.process import PythonProcess, NativeProcess, DaemonProcess from selfdrive.hardware import EON, TICI, PC +from selfdrive.manager.process import PythonProcess, NativeProcess, DaemonProcess WEBCAM = os.getenv("USE_WEBCAM") is not None @@ -36,9 +36,11 @@ procs = [ PythonProcess("tombstoned", "selfdrive.tombstoned", enabled=not PC, persistent=True), PythonProcess("updated", "selfdrive.updated", enabled=not PC, persistent=True), PythonProcess("uploader", "selfdrive.loggerd.uploader", persistent=True), + PythonProcess("statsd", "selfdrive.statsd", persistent=True), # EON only PythonProcess("rtshield", "selfdrive.rtshield", enabled=EON), + PythonProcess("shutdownd", "selfdrive.hardware.eon.shutdownd", enabled=EON), PythonProcess("androidd", "selfdrive.hardware.eon.androidd", enabled=EON, persistent=True), ] diff --git a/selfdrive/modeld/modeld.cc b/selfdrive/modeld/modeld.cc index 9e1750eea..0facf3fa0 100644 --- a/selfdrive/modeld/modeld.cc +++ b/selfdrive/modeld/modeld.cc @@ -14,64 +14,46 @@ #include "selfdrive/modeld/models/driving.h" ExitHandler do_exit; -// globals -bool live_calib_seen; -mat3 cur_transform; -std::mutex transform_lock; - -void calibration_thread(bool wide_camera) { - util::set_thread_name("calibration"); - util::set_realtime_priority(50); - - SubMaster sm({"liveCalibration"}); +mat3 update_calibration(cereal::LiveCalibrationData::Reader live_calib, bool wide_camera) { /* import numpy as np from common.transformations.model import medmodel_frame_from_road_frame medmodel_frame_from_ground = medmodel_frame_from_road_frame[:, (0, 1, 3)] ground_from_medmodel_frame = np.linalg.inv(medmodel_frame_from_ground) */ - Eigen::Matrix ground_from_medmodel_frame; - ground_from_medmodel_frame << + static const auto ground_from_medmodel_frame = (Eigen::Matrix() << 0.00000000e+00, 0.00000000e+00, 1.00000000e+00, -1.09890110e-03, 0.00000000e+00, 2.81318681e-01, - -1.84808520e-20, 9.00738606e-04,-4.28751576e-02; + -1.84808520e-20, 9.00738606e-04, -4.28751576e-02).finished(); - Eigen::Matrix cam_intrinsics = Eigen::Matrix(wide_camera ? ecam_intrinsic_matrix.v : fcam_intrinsic_matrix.v); - const mat3 yuv_transform = get_model_yuv_transform(); + static const auto cam_intrinsics = Eigen::Matrix(wide_camera ? ecam_intrinsic_matrix.v : fcam_intrinsic_matrix.v); + static const mat3 yuv_transform = get_model_yuv_transform(); - while (!do_exit) { - sm.update(100); - if(sm.updated("liveCalibration")) { - auto extrinsic_matrix = sm["liveCalibration"].getLiveCalibration().getExtrinsicMatrix(); - Eigen::Matrix extrinsic_matrix_eigen; - for (int i = 0; i < 4*3; i++) { - extrinsic_matrix_eigen(i / 4, i % 4) = extrinsic_matrix[i]; - } - - auto camera_frame_from_road_frame = cam_intrinsics * extrinsic_matrix_eigen; - Eigen::Matrix camera_frame_from_ground; - camera_frame_from_ground.col(0) = camera_frame_from_road_frame.col(0); - camera_frame_from_ground.col(1) = camera_frame_from_road_frame.col(1); - camera_frame_from_ground.col(2) = camera_frame_from_road_frame.col(3); - - auto warp_matrix = camera_frame_from_ground * ground_from_medmodel_frame; - mat3 transform = {}; - for (int i=0; i<3*3; i++) { - transform.v[i] = warp_matrix(i / 3, i % 3); - } - mat3 model_transform = matmul3(yuv_transform, transform); - std::lock_guard lk(transform_lock); - cur_transform = model_transform; - live_calib_seen = true; - } + auto extrinsic_matrix = live_calib.getExtrinsicMatrix(); + Eigen::Matrix extrinsic_matrix_eigen; + for (int i = 0; i < 4*3; i++) { + extrinsic_matrix_eigen(i / 4, i % 4) = extrinsic_matrix[i]; } + + auto camera_frame_from_road_frame = cam_intrinsics * extrinsic_matrix_eigen; + Eigen::Matrix camera_frame_from_ground; + camera_frame_from_ground.col(0) = camera_frame_from_road_frame.col(0); + camera_frame_from_ground.col(1) = camera_frame_from_road_frame.col(1); + camera_frame_from_ground.col(2) = camera_frame_from_road_frame.col(3); + + auto warp_matrix = camera_frame_from_ground * ground_from_medmodel_frame; + mat3 transform = {}; + for (int i=0; i<3*3; i++) { + transform.v[i] = warp_matrix(i / 3, i % 3); + } + return matmul3(yuv_transform, transform); } -void run_model(ModelState &model, VisionIpcClient &vipc_client) { +void run_model(ModelState &model, VisionIpcClient &vipc_client, bool wide_camera) { // messaging PubMaster pm({"modelV2", "cameraOdometry"}); - SubMaster sm({"lateralPlan", "roadCameraState"}); + SubMaster sm({"lateralPlan", "roadCameraState", "liveCalibration"}); // setup filter to track dropped frames FirstOrderFilter frame_dropped_filter(0., 10., 1. / MODEL_FREQ); @@ -80,53 +62,52 @@ void run_model(ModelState &model, VisionIpcClient &vipc_client) { double last = 0; uint32_t run_count = 0; + mat3 model_transform = {}; + bool live_calib_seen = false; + while (!do_exit) { VisionIpcBufExtra extra = {}; VisionBuf *buf = vipc_client.recv(&extra); if (buf == nullptr) continue; - transform_lock.lock(); - mat3 model_transform = cur_transform; - const bool run_model_this_iter = live_calib_seen; - transform_lock.unlock(); - // TODO: path planner timeout? sm.update(0); int desire = ((int)sm["lateralPlan"].getLateralPlan().getDesire()); frame_id = sm["roadCameraState"].getRoadCameraState().getFrameId(); - - if (run_model_this_iter) { - run_count++; - - float vec_desire[DESIRE_LEN] = {0}; - if (desire >= 0 && desire < DESIRE_LEN) { - vec_desire[desire] = 1.0; - } - - double mt1 = millis_since_boot(); - ModelOutput *model_output = model_eval_frame(&model, buf->buf_cl, buf->width, buf->height, - model_transform, vec_desire); - double mt2 = millis_since_boot(); - float model_execution_time = (mt2 - mt1) / 1000.0; - - // tracked dropped frames - uint32_t vipc_dropped_frames = extra.frame_id - last_vipc_frame_id - 1; - float frames_dropped = frame_dropped_filter.update((float)std::min(vipc_dropped_frames, 10U)); - if (run_count < 10) { // let frame drops warm up - frame_dropped_filter.reset(0); - frames_dropped = 0.; - } - - float frame_drop_ratio = frames_dropped / (1 + frames_dropped); - - model_publish(pm, extra.frame_id, frame_id, frame_drop_ratio, *model_output, extra.timestamp_eof, model_execution_time, - kj::ArrayPtr(model.output.data(), model.output.size())); - posenet_publish(pm, extra.frame_id, vipc_dropped_frames, *model_output, extra.timestamp_eof); - - //printf("model process: %.2fms, from last %.2fms, vipc_frame_id %u, frame_id, %u, frame_drop %.3f\n", mt2 - mt1, mt1 - last, extra.frame_id, frame_id, frame_drop_ratio); - last = mt1; - last_vipc_frame_id = extra.frame_id; + if (sm.updated("liveCalibration")) { + model_transform = update_calibration(sm["liveCalibration"].getLiveCalibration(), wide_camera); + live_calib_seen = true; } + + float vec_desire[DESIRE_LEN] = {0}; + if (desire >= 0 && desire < DESIRE_LEN) { + vec_desire[desire] = 1.0; + } + + double mt1 = millis_since_boot(); + ModelOutput *model_output = model_eval_frame(&model, buf->buf_cl, buf->width, buf->height, + model_transform, vec_desire); + double mt2 = millis_since_boot(); + float model_execution_time = (mt2 - mt1) / 1000.0; + + // tracked dropped frames + uint32_t vipc_dropped_frames = extra.frame_id - last_vipc_frame_id - 1; + float frames_dropped = frame_dropped_filter.update((float)std::min(vipc_dropped_frames, 10U)); + if (run_count < 10) { // let frame drops warm up + frame_dropped_filter.reset(0); + frames_dropped = 0.; + } + run_count++; + + float frame_drop_ratio = frames_dropped / (1 + frames_dropped); + + model_publish(pm, extra.frame_id, frame_id, frame_drop_ratio, *model_output, extra.timestamp_eof, model_execution_time, + kj::ArrayPtr(model.output.data(), model.output.size()), live_calib_seen); + posenet_publish(pm, extra.frame_id, vipc_dropped_frames, *model_output, extra.timestamp_eof, live_calib_seen); + + //printf("model process: %.2fms, from last %.2fms, vipc_frame_id %u, frame_id, %u, frame_drop %.3f\n", mt2 - mt1, mt1 - last, extra.frame_id, frame_id, frame_drop_ratio); + last = mt1; + last_vipc_frame_id = extra.frame_id; } } @@ -141,9 +122,6 @@ int main(int argc, char **argv) { bool wide_camera = Hardware::TICI() ? Params().getBool("EnableWideCamera") : false; - // start calibration thread - std::thread thread = std::thread(calibration_thread, wide_camera); - // cl init cl_device_id device_id = cl_get_device_id(CL_DEVICE_TYPE_DEFAULT); cl_context context = CL_CHECK_ERR(clCreateContext(NULL, 1, &device_id, NULL, NULL, &err)); @@ -163,12 +141,10 @@ int main(int argc, char **argv) { if (vipc_client.connected) { const VisionBuf *b = &vipc_client.buffers[0]; LOGW("connected with buffer size: %d (%d x %d)", b->len, b->width, b->height); - run_model(model, vipc_client); + run_model(model, vipc_client, wide_camera); } model_free(&model); - LOG("joining calibration thread"); - thread.join(); CL_CHECK(clReleaseContext(context)); return 0; } diff --git a/selfdrive/modeld/models/driving.cc b/selfdrive/modeld/models/driving.cc index 629e1d7ed..69aeb91be 100644 --- a/selfdrive/modeld/models/driving.cc +++ b/selfdrive/modeld/models/driving.cc @@ -308,10 +308,10 @@ void fill_model(cereal::ModelDataV2::Builder &framed, const ModelOutput &net_out void model_publish(PubMaster &pm, uint32_t vipc_frame_id, uint32_t frame_id, float frame_drop, const ModelOutput &net_outputs, uint64_t timestamp_eof, - float model_execution_time, kj::ArrayPtr raw_pred) { + float model_execution_time, kj::ArrayPtr raw_pred, const bool valid) { const uint32_t frame_age = (frame_id > vipc_frame_id) ? (frame_id - vipc_frame_id) : 0; MessageBuilder msg; - auto framed = msg.initEvent().initModelV2(); + auto framed = msg.initEvent(valid).initModelV2(); framed.setFrameId(vipc_frame_id); framed.setFrameAge(frame_age); framed.setFrameDropPerc(frame_drop * 100); @@ -325,14 +325,14 @@ void model_publish(PubMaster &pm, uint32_t vipc_frame_id, uint32_t frame_id, flo } void posenet_publish(PubMaster &pm, uint32_t vipc_frame_id, uint32_t vipc_dropped_frames, - const ModelOutput &net_outputs, uint64_t timestamp_eof) { + const ModelOutput &net_outputs, uint64_t timestamp_eof, const bool valid) { MessageBuilder msg; - auto v_mean = net_outputs.pose.velocity_mean; - auto r_mean = net_outputs.pose.rotation_mean; - auto v_std = net_outputs.pose.velocity_std; - auto r_std = net_outputs.pose.rotation_std; + const auto &v_mean = net_outputs.pose.velocity_mean; + const auto &r_mean = net_outputs.pose.rotation_mean; + const auto &v_std = net_outputs.pose.velocity_std; + const auto &r_std = net_outputs.pose.rotation_std; - auto posenetd = msg.initEvent(vipc_dropped_frames < 1).initCameraOdometry(); + auto posenetd = msg.initEvent(valid && (vipc_dropped_frames < 1)).initCameraOdometry(); posenetd.setTrans({v_mean.x, v_mean.y, v_mean.z}); posenetd.setRot({r_mean.x, r_mean.y, r_mean.z}); posenetd.setTransStd({exp(v_std.x), exp(v_std.y), exp(v_std.z)}); diff --git a/selfdrive/modeld/models/driving.h b/selfdrive/modeld/models/driving.h index 5749fb5ec..14645dcfa 100644 --- a/selfdrive/modeld/models/driving.h +++ b/selfdrive/modeld/models/driving.h @@ -235,9 +235,8 @@ void model_init(ModelState* s, cl_device_id device_id, cl_context context); ModelOutput *model_eval_frame(ModelState* s, cl_mem yuv_cl, int width, int height, const mat3 &transform, float *desire_in); void model_free(ModelState* s); -void poly_fit(float *in_pts, float *in_stds, float *out); void model_publish(PubMaster &pm, uint32_t vipc_frame_id, uint32_t frame_id, float frame_drop, const ModelOutput &net_outputs, uint64_t timestamp_eof, - float model_execution_time, kj::ArrayPtr raw_pred); + float model_execution_time, kj::ArrayPtr raw_pred, const bool valid); void posenet_publish(PubMaster &pm, uint32_t vipc_frame_id, uint32_t vipc_dropped_frames, - const ModelOutput &net_outputs, uint64_t timestamp_eof); + const ModelOutput &net_outputs, uint64_t timestamp_eof, const bool valid); diff --git a/selfdrive/monitoring/dmonitoringd.py b/selfdrive/monitoring/dmonitoringd.py index f11d72266..f1b0c42bd 100755 --- a/selfdrive/monitoring/dmonitoringd.py +++ b/selfdrive/monitoring/dmonitoringd.py @@ -1,13 +1,19 @@ #!/usr/bin/env python3 +import gc + +import cereal.messaging as messaging from cereal import car from common.params import Params -import cereal.messaging as messaging +from common.realtime import set_realtime_priority from selfdrive.controls.lib.events import Events -from selfdrive.monitoring.driver_monitor import DriverStatus from selfdrive.locationd.calibrationd import Calibration +from selfdrive.monitoring.driver_monitor import DriverStatus def dmonitoringd_thread(sm=None, pm=None): + gc.disable() + set_realtime_priority(2) + if pm is None: pm = messaging.PubMaster(['driverMonitoringState']) @@ -38,12 +44,10 @@ def dmonitoringd_thread(sm=None, pm=None): v_cruise != v_cruise_last or \ sm['carState'].steeringPressed or \ sm['carState'].gasPressed - if driver_engaged: - driver_status.update(Events(), True, sm['controlsState'].enabled, sm['carState'].standstill) v_cruise_last = v_cruise if sm.updated['modelV2']: - driver_status.set_policy(sm['modelV2']) + driver_status.set_policy(sm['modelV2'], sm['carState'].vEgo) # Get data from dmonitoringmodeld events = Events() @@ -77,8 +81,10 @@ def dmonitoringd_thread(sm=None, pm=None): } pm.send('driverMonitoringState', dat) + def main(sm=None, pm=None): dmonitoringd_thread(sm, pm) + if __name__ == '__main__': main() diff --git a/selfdrive/monitoring/driver_monitor.py b/selfdrive/monitoring/driver_monitor.py index e4018d66f..efb00ecb7 100644 --- a/selfdrive/monitoring/driver_monitor.py +++ b/selfdrive/monitoring/driver_monitor.py @@ -32,15 +32,21 @@ class DRIVER_MONITOR_SETTINGS(): self._BLINK_THRESHOLD = 0.82 if TICI else 0.588 self._BLINK_THRESHOLD_SLACK = 0.9 if TICI else 0.77 self._BLINK_THRESHOLD_STRICT = self._BLINK_THRESHOLD - self._PITCH_WEIGHT = 1.35 # pitch matters a lot more + + self._POSE_PITCH_THRESHOLD = 0.3237 + self._POSE_PITCH_THRESHOLD_SLACK = 0.3657 + self._POSE_PITCH_THRESHOLD_STRICT = self._POSE_PITCH_THRESHOLD + self._POSE_YAW_THRESHOLD = 0.3109 + self._POSE_YAW_THRESHOLD_SLACK = 0.4294 + self._POSE_YAW_THRESHOLD_STRICT = self._POSE_YAW_THRESHOLD + self._PITCH_NATURAL_OFFSET = 0.057 # initial value before offset is learned + self._YAW_NATURAL_OFFSET = 0.11 # initial value before offset is learned + self._PITCH_MAX_OFFSET = 0.124 + self._PITCH_MIN_OFFSET = -0.0881 + self._YAW_MAX_OFFSET = 0.289 + self._YAW_MIN_OFFSET = -0.0246 + self._POSESTD_THRESHOLD = 0.38 if TICI else 0.3 - - self._METRIC_THRESHOLD = 0.48 - self._METRIC_THRESHOLD_SLACK = 0.66 - self._METRIC_THRESHOLD_STRICT = self._METRIC_THRESHOLD - self._PITCH_NATURAL_OFFSET = 0.02 # people don't seem to look straight when they drive relaxed, rather a bit up - self._YAW_NATURAL_OFFSET = 0.08 # people don't seem to look straight when they drive relaxed, rather a bit to the right (center of car) - self._HI_STD_FALLBACK_TIME = int(10 / self._DT_DMON) # fall back to wheel touch if model is uncertain for 10s self._DISTRACTED_FILTER_TS = 0.25 # 0.6Hz @@ -93,7 +99,8 @@ class DriverPose(): self.pitch_offseter = RunningStatFilter(max_trackable=max_trackable) self.yaw_offseter = RunningStatFilter(max_trackable=max_trackable) self.low_std = True - self.cfactor = 1. + self.cfactor_pitch = 1. + self.cfactor_yaw = 1. class DriverBlink(): def __init__(self): @@ -164,34 +171,42 @@ class DriverStatus(): pitch_error = pose.pitch - self.settings._PITCH_NATURAL_OFFSET yaw_error = pose.yaw - self.settings._YAW_NATURAL_OFFSET else: - pitch_error = pose.pitch - self.pose.pitch_offseter.filtered_stat.mean() - yaw_error = pose.yaw - self.pose.yaw_offseter.filtered_stat.mean() + pitch_error = pose.pitch - min(max(self.pose.pitch_offseter.filtered_stat.mean(), + self.settings._PITCH_MIN_OFFSET), self.settings._PITCH_MAX_OFFSET) + yaw_error = pose.yaw - min(max(self.pose.yaw_offseter.filtered_stat.mean(), + self.settings._YAW_MIN_OFFSET), self.settings._YAW_MAX_OFFSET) pitch_error = 0 if pitch_error > 0 else abs(pitch_error) # no positive pitch limit yaw_error = abs(yaw_error) - if pitch_error*self.settings._PITCH_WEIGHT > self.settings._METRIC_THRESHOLD*pose.cfactor or \ - yaw_error > self.settings._METRIC_THRESHOLD*pose.cfactor: + if pitch_error > self.settings._POSE_PITCH_THRESHOLD*pose.cfactor_pitch or \ + yaw_error > self.settings._POSE_YAW_THRESHOLD*pose.cfactor_yaw: return DistractedType.BAD_POSE elif (blink.left_blink + blink.right_blink)*0.5 > self.settings._BLINK_THRESHOLD*blink.cfactor: return DistractedType.BAD_BLINK else: return DistractedType.NOT_DISTRACTED - def set_policy(self, model_data): - ep = min(model_data.meta.engagedProb, 0.8) / 0.8 - self.pose.cfactor = interp(ep, [0, 0.5, 1], - [self.settings._METRIC_THRESHOLD_STRICT, - self.settings. _METRIC_THRESHOLD, - self.settings._METRIC_THRESHOLD_SLACK]) / self.settings._METRIC_THRESHOLD + def set_policy(self, model_data, car_speed): + ep = min(model_data.meta.engagedProb, 0.8) / 0.8 # engaged prob + bp = model_data.meta.disengagePredictions.brakeDisengageProbs[0] # brake disengage prob in next 2s + # TODO: retune adaptive blink self.blink.cfactor = interp(ep, [0, 0.5, 1], [self.settings._BLINK_THRESHOLD_STRICT, self.settings._BLINK_THRESHOLD, self.settings._BLINK_THRESHOLD_SLACK]) / self.settings._BLINK_THRESHOLD + k1 = max(-0.00156*((car_speed-16)**2)+0.6, 0.2) + bp_normal = max(min(bp / k1, 0.5),0) + self.pose.cfactor_pitch = interp(bp_normal, [0, 0.5], + [self.settings._POSE_PITCH_THRESHOLD_SLACK, + self.settings._POSE_PITCH_THRESHOLD_STRICT]) / self.settings._POSE_PITCH_THRESHOLD + self.pose.cfactor_yaw = interp(bp_normal, [0, 0.5], + [self.settings._POSE_YAW_THRESHOLD_SLACK, + self.settings._POSE_YAW_THRESHOLD_STRICT]) / self.settings._POSE_YAW_THRESHOLD def get_pose(self, driver_state, cal_rpy, car_speed, op_engaged): - if not all(len(x) > 0 for x in [driver_state.faceOrientation, driver_state.facePosition, - driver_state.faceOrientationStd, driver_state.facePositionStd]): + if not all(len(x) > 0 for x in (driver_state.faceOrientation, driver_state.facePosition, + driver_state.faceOrientationStd, driver_state.facePositionStd)): return self.face_partial = driver_state.partialFace > self.settings._PARTIAL_FACE_THRESHOLD diff --git a/selfdrive/pandad.py b/selfdrive/pandad.py index b725ca9dd..1f9fddab7 100755 --- a/selfdrive/pandad.py +++ b/selfdrive/pandad.py @@ -4,7 +4,7 @@ import os import usb1 import time import subprocess -from typing import List +from typing import NoReturn from functools import cmp_to_key from panda import DEFAULT_FW_FN, DEFAULT_H7_FW_FN, MCU_TYPE_H7, Panda, PandaDFU @@ -13,7 +13,7 @@ from common.params import Params from selfdrive.swaglog import cloudlog -def get_expected_signature(panda : Panda) -> bytes: +def get_expected_signature(panda: Panda) -> bytes: fn = DEFAULT_H7_FW_FN if (panda.get_mcu_type() == MCU_TYPE_H7) else DEFAULT_FW_FN try: @@ -23,19 +23,14 @@ def get_expected_signature(panda : Panda) -> bytes: return b"" -def flash_panda(panda_serial : str) -> Panda: +def flash_panda(panda_serial: str) -> Panda: panda = Panda(panda_serial) fw_signature = get_expected_signature(panda) panda_version = "bootstub" if panda.bootstub else panda.get_version() panda_signature = b"" if panda.bootstub else panda.get_signature() - cloudlog.warning("Panda %s connected, version: %s, signature %s, expected %s" % ( - panda_serial, - panda_version, - panda_signature.hex()[:16], - fw_signature.hex()[:16], - )) + cloudlog.warning(f"Panda {panda_serial} connected, version: {panda_version}, signature {panda_signature.hex()[:16]}, expected {fw_signature.hex()[:16]}") if panda.bootstub or panda_signature != fw_signature: cloudlog.info("Panda firmware out of date, update required") @@ -59,7 +54,8 @@ def flash_panda(panda_serial : str) -> Panda: return panda -def panda_sort_cmp(a : Panda, b : Panda): + +def panda_sort_cmp(a: Panda, b: Panda): a_type = a.get_type() b_type = b.get_type() @@ -72,13 +68,19 @@ def panda_sort_cmp(a : Panda, b : Panda): # sort by hardware type if a_type != b_type: return a_type < b_type - + # last resort: sort by serial number return a.get_usb_serial() < b.get_usb_serial() -def main() -> None: + +def main() -> NoReturn: + first_run = True + params = Params() + while True: try: + params.delete("PandaSignatures") + # Flash all Pandas in DFU mode for p in PandaDFU.list(): cloudlog.info(f"Panda in DFU mode found, flashing recovery {p}") @@ -100,16 +102,20 @@ def main() -> None: for panda in pandas: health = panda.health() if health["heartbeat_lost"]: - Params().put_bool("PandaHeartbeatLost", True) + params.put_bool("PandaHeartbeatLost", True) cloudlog.event("heartbeat lost", deviceState=health, serial=panda.get_usb_serial()) - cloudlog.info(f"Resetting panda {panda.get_usb_serial()}") - panda.reset() + if first_run: + cloudlog.info(f"Resetting panda {panda.get_usb_serial()}") + panda.reset() # sort pandas to have deterministic order pandas.sort(key=cmp_to_key(panda_sort_cmp)) panda_serials = list(map(lambda p: p.get_usb_serial(), pandas)) + # log panda fw versions + params.put("PandaSignatures", b','.join(p.get_signature() for p in pandas)) + # close all pandas for p in pandas: p.close() @@ -118,6 +124,8 @@ def main() -> None: cloudlog.exception("Panda USB exception while setting up") continue + first_run = False + # run boardd with all connected serials as arguments os.chdir(os.path.join(BASEDIR, "selfdrive/boardd")) subprocess.run(["./boardd", *panda_serials], check=True) diff --git a/selfdrive/sentry.py b/selfdrive/sentry.py new file mode 100644 index 000000000..5f22bf18e --- /dev/null +++ b/selfdrive/sentry.py @@ -0,0 +1,75 @@ +"""Install exception handler for process crash.""" +import sentry_sdk +from enum import Enum +from sentry_sdk.integrations.threading import ThreadingIntegration + +from common.params import Params +from selfdrive.athena.registration import is_registered_device +from selfdrive.hardware import HARDWARE, PC +from selfdrive.swaglog import cloudlog +from selfdrive.version import get_branch, get_commit, get_origin, get_version, \ + is_comma_remote, is_dirty, is_tested_branch + + +class SentryProject(Enum): + # python project + SELFDRIVE = "https://6f3c7076c1e14b2aa10f5dde6dda0cc4@o33823.ingest.sentry.io/77924" + # native project + SELFDRIVE_NATIVE = "https://3e4b586ed21a4479ad5d85083b639bc6@o33823.ingest.sentry.io/157615" + + +def report_tombstone(fn: str, message: str, contents: str) -> None: + cloudlog.error({'tombstone': message}) + + with sentry_sdk.configure_scope() as scope: + scope.set_extra("tombstone_fn", fn) + scope.set_extra("tombstone", contents) + sentry_sdk.capture_message(message=message) + sentry_sdk.flush() + + +def capture_exception(*args, **kwargs) -> None: + cloudlog.error("crash", exc_info=kwargs.get('exc_info', 1)) + + try: + sentry_sdk.capture_exception(*args, **kwargs) + sentry_sdk.flush() # https://github.com/getsentry/sentry-python/issues/291 + except Exception: + cloudlog.exception("sentry exception") + + +def set_tag(key: str, value: str) -> None: + sentry_sdk.set_tag(key, value) + + +def init(project: SentryProject) -> None: + # forks like to mess with this, so double check + comma_remote = is_comma_remote() and "commaai" in get_origin(default="") + if not comma_remote or not is_registered_device() or PC: + return + + env = "release" if is_tested_branch() else "master" + dongle_id = Params().get("DongleId", encoding='utf-8') + + integrations = [] + if project == SentryProject.SELFDRIVE: + integrations.append(ThreadingIntegration(propagate_hub=True)) + else: + sentry_sdk.utils.MAX_STRING_LENGTH = 8192 + + sentry_sdk.init(project.value, + default_integrations=False, + release=get_version(), + integrations=integrations, + traces_sample_rate=1.0, + environment=env) + + sentry_sdk.set_user({"id": dongle_id}) + sentry_sdk.set_tag("dirty", is_dirty()) + sentry_sdk.set_tag("origin", get_origin()) + sentry_sdk.set_tag("branch", get_branch()) + sentry_sdk.set_tag("commit", get_commit()) + sentry_sdk.set_tag("device", HARDWARE.get_device_type()) + + if project == SentryProject.SELFDRIVE: + sentry_sdk.Hub.current.start_session() diff --git a/selfdrive/statsd.py b/selfdrive/statsd.py new file mode 100755 index 000000000..2e62e3253 --- /dev/null +++ b/selfdrive/statsd.py @@ -0,0 +1,126 @@ +#!/usr/bin/env python3 +import os +import zmq +import time +from pathlib import Path +from datetime import datetime, timezone +from typing import NoReturn + +from common.params import Params +from cereal.messaging import SubMaster +from selfdrive.swaglog import cloudlog +from selfdrive.hardware import HARDWARE +from common.file_helpers import atomic_write_in_dir +from selfdrive.version import get_normalized_origin, get_short_branch, get_short_version, is_dirty +from selfdrive.loggerd.config import STATS_DIR, STATS_DIR_FILE_LIMIT, STATS_SOCKET, STATS_FLUSH_TIME_S + + +class METRIC_TYPE: + GAUGE = 'g' + +class StatLog: + def __init__(self): + self.pid = None + + def connect(self) -> None: + self.zctx = zmq.Context() + self.sock = self.zctx.socket(zmq.PUSH) + self.sock.setsockopt(zmq.LINGER, 10) + self.sock.connect(STATS_SOCKET) + self.pid = os.getpid() + + def _send(self, metric: str) -> None: + if os.getpid() != self.pid: + self.connect() + + try: + self.sock.send_string(metric, zmq.NOBLOCK) + except zmq.error.Again: + # drop :/ + pass + + def gauge(self, name: str, value: float) -> None: + self._send(f"{name}:{value}|{METRIC_TYPE.GAUGE}") + + +def main() -> NoReturn: + dongle_id = Params().get("DongleId", encoding='utf-8') + def get_influxdb_line(measurement: str, value: float, timestamp: datetime, tags: dict) -> str: + res = f"{measurement}" + for k, v in tags.items(): + res += f",{k}={str(v)}" + res += f" value={value},dongle_id=\"{dongle_id}\" {int(timestamp.timestamp() * 1e9)}\n" + return res + + # open statistics socket + ctx = zmq.Context().instance() + sock = ctx.socket(zmq.PULL) + sock.bind(STATS_SOCKET) + + # initialize stats directory + Path(STATS_DIR).mkdir(parents=True, exist_ok=True) + + # initialize tags + tags = { + 'started': False, + 'version': get_short_version(), + 'branch': get_short_branch(), + 'dirty': is_dirty(), + 'origin': get_normalized_origin(), + 'deviceType': HARDWARE.get_device_type(), + } + + # subscribe to deviceState for started state + sm = SubMaster(['deviceState']) + + last_flush_time = time.monotonic() + gauges = {} + while True: + started_prev = sm['deviceState'].started + sm.update() + + # Update metrics + while True: + try: + metric = sock.recv_string(zmq.NOBLOCK) + try: + metric_type = metric.split('|')[1] + metric_name = metric.split(':')[0] + metric_value = metric.split('|')[0].split(':')[1] + + if metric_type == METRIC_TYPE.GAUGE: + gauges[metric_name] = metric_value + else: + cloudlog.event("unknown metric type", metric_type=metric_type) + except Exception: + cloudlog.event("malformed metric", metric=metric) + except zmq.error.Again: + break + + # flush when started state changes or after FLUSH_TIME_S + if (time.monotonic() > last_flush_time + STATS_FLUSH_TIME_S) or (sm['deviceState'].started != started_prev): + result = "" + current_time = datetime.utcnow().replace(tzinfo=timezone.utc) + tags['started'] = sm['deviceState'].started + + for gauge_key in gauges: + result += get_influxdb_line(f"gauge.{gauge_key}", gauges[gauge_key], current_time, tags) + + # clear intermediate data + gauges = {} + last_flush_time = time.monotonic() + + # check that we aren't filling up the drive + if len(os.listdir(STATS_DIR)) < STATS_DIR_FILE_LIMIT: + if len(result) > 0: + stats_path = os.path.join(STATS_DIR, str(int(current_time.timestamp()))) + with atomic_write_in_dir(stats_path) as f: + f.write(result) + else: + cloudlog.error("stats dir full") + + +if __name__ == "__main__": + main() +else: + statlog = StatLog() diff --git a/selfdrive/test/helpers.py b/selfdrive/test/helpers.py index 0bb475c92..5abc0d964 100644 --- a/selfdrive/test/helpers.py +++ b/selfdrive/test/helpers.py @@ -13,7 +13,6 @@ def set_params_enabled(): params.put("HasAcceptedTerms", terms_version) params.put("CompletedTrainingVersion", training_version) params.put_bool("OpenpilotEnabledToggle", True) - params.put_bool("CommunityFeaturesToggle", True) params.put_bool("Passive", False) diff --git a/selfdrive/test/test_fingerprints.py b/selfdrive/test/test_fingerprints.py index 07e477482..01c7d753c 100755 --- a/selfdrive/test/test_fingerprints.py +++ b/selfdrive/test/test_fingerprints.py @@ -1,6 +1,8 @@ #!/usr/bin/env python3 import os import sys +from typing import Dict, List + from common.basedir import BASEDIR # messages reserved for CAN based ignition (see can_ignition_hook function in panda/board/drivers/can) @@ -18,8 +20,8 @@ def _get_fingerprints(): for car_folder in [x[0] for x in os.walk(BASEDIR + '/selfdrive/car')]: car_name = car_folder.split('/')[-1] try: - fingerprints[car_name] = __import__('selfdrive.car.%s.values' % car_name, fromlist=['FINGERPRINTS']).FINGERPRINTS - except (ImportError, IOError, AttributeError): + fingerprints[car_name] = __import__(f'selfdrive.car.{car_name}.values', fromlist=['FINGERPRINTS']).FINGERPRINTS + except (ImportError, OSError, AttributeError): pass return fingerprints @@ -62,7 +64,7 @@ def check_can_ignition_conflicts(fingerprints, brands): if __name__ == "__main__": fingerprints = _get_fingerprints() - fingerprints_flat = [] + fingerprints_flat: List[Dict] = [] car_names = [] brand_names = [] for brand in fingerprints: @@ -80,14 +82,14 @@ if __name__ == "__main__": for idx2, f2 in enumerate(fingerprints_flat): if idx1 < idx2 and not check_fingerprint_consistency(f1, f2): valid = False - print("Those two fingerprints are inconsistent {0} {1}".format(car_names[idx1], car_names[idx2])) + print(f"Those two fingerprints are inconsistent {car_names[idx1]} {car_names[idx2]}") print("") print(', '.join("%d: %d" % v for v in sorted(f1.items()))) print("") print(', '.join("%d: %d" % v for v in sorted(f2.items()))) print("") - print("Found {0} individual fingerprints".format(len(fingerprints_flat))) + print(f"Found {len(fingerprints_flat)} individual fingerprints") if not valid or len(fingerprints_flat) == 0: print("TEST FAILED") sys.exit(1) diff --git a/selfdrive/test/test_onroad.py b/selfdrive/test/test_onroad.py index bc44aa3ea..d0a1ad956 100755 --- a/selfdrive/test/test_onroad.py +++ b/selfdrive/test/test_onroad.py @@ -22,7 +22,7 @@ from tools.lib.logreader import LogReader # Baseline CPU usage by process PROCS = { - "selfdrive.controls.controlsd": 50.0, + "selfdrive.controls.controlsd": 55.0, "./loggerd": 45.0, "./locationd": 9.1, "selfdrive.controls.plannerd": 22.6, @@ -30,11 +30,11 @@ PROCS = { "selfdrive.locationd.paramsd": 9.1, "./camerad": 7.07, "./_sensord": 6.17, - "selfdrive.controls.radard": 5.67, + "selfdrive.controls.radard": 7.0, "./_modeld": 4.48, "./boardd": 3.63, "./_dmonitoringmodeld": 2.67, - "selfdrive.thermald.thermald": 2.41, + "selfdrive.thermald.thermald": 5.36, "selfdrive.locationd.calibrationd": 2.0, "./_soundd": 1.0, "selfdrive.monitoring.dmonitoringd": 1.90, @@ -49,19 +49,20 @@ PROCS = { if EON: PROCS.update({ "selfdrive.hardware.eon.androidd": 0.4, + "selfdrive.hardware.eon.shutdownd": 0.4, }) if TICI: PROCS.update({ "./loggerd": 70.0, - "selfdrive.controls.controlsd": 28.0, + "selfdrive.controls.controlsd": 31.0, "./camerad": 31.0, - "./_ui": 30.2, + "./_ui": 33.0, "selfdrive.controls.plannerd": 11.7, "./_dmonitoringmodeld": 10.0, "selfdrive.locationd.paramsd": 5.0, - "selfdrive.controls.radard": 3.6, - "selfdrive.thermald.thermald": 1.5, + "selfdrive.controls.radard": 4.5, + "selfdrive.thermald.thermald": 3.87, }) @@ -204,6 +205,22 @@ class TestOnroad(unittest.TestCase): cpu_ok = check_cpu_usage(proclogs[0], proclogs[-1]) self.assertTrue(cpu_ok) + def test_mpc_execution_timings(self): + result = "\n" + result += "------------------------------------------------\n" + result += "----------------- MPC Timing ------------------\n" + result += "------------------------------------------------\n" + + cfgs = [("lateralPlan", 0.05, 0.05), ("longitudinalPlan", 0.05, 0.05)] + for (s, instant_max, avg_max) in cfgs: + ts = [getattr(getattr(m, s), "solverExecutionTime") for m in self.lr if m.which() == s] + self.assertLess(min(ts), instant_max, f"high '{s}' execution time: {min(ts)}") + self.assertLess(np.mean(ts), avg_max, f"high avg '{s}' execution time: {np.mean(ts)}") + result += f"'{s}' execution time: {min(ts)}\n" + result += f"'{s}' avg execution time: {np.mean(ts)}\n" + result += "------------------------------------------------\n" + print(result) + def test_model_execution_timings(self): result = "\n" result += "------------------------------------------------\n" diff --git a/selfdrive/thermald/power_monitoring.py b/selfdrive/thermald/power_monitoring.py index 9c0736391..0dc4c5a1d 100644 --- a/selfdrive/thermald/power_monitoring.py +++ b/selfdrive/thermald/power_monitoring.py @@ -2,12 +2,14 @@ import random import threading import time from statistics import mean +from typing import Optional from cereal import log from common.params import Params, put_nonblocking from common.realtime import sec_since_boot from selfdrive.hardware import HARDWARE from selfdrive.swaglog import cloudlog +from selfdrive.statsd import statlog CAR_VOLTAGE_LOW_PASS_K = 0.091 # LPF gain for 5s tau (dt/tau / (dt/tau + 1)) @@ -55,6 +57,7 @@ class PowerMonitoring: # Low-pass battery voltage self.car_voltage_instant_mV = peripheralState.voltage self.car_voltage_mV = ((peripheralState.voltage * CAR_VOLTAGE_LOW_PASS_K) + (self.car_voltage_mV * (1 - CAR_VOLTAGE_LOW_PASS_K))) + statlog.gauge("car_voltage", self.car_voltage_mV / 1e3) # Cap the car battery power and save it in a param every 10-ish seconds self.car_battery_capacity_uWh = max(self.car_battery_capacity_uWh, 0) @@ -135,7 +138,7 @@ class PowerMonitoring: except Exception: cloudlog.exception("Power monitoring calculation failed") - def _perform_integration(self, t, current_power): + def _perform_integration(self, t: float, current_power: float) -> None: with self.integration_lock: try: if self.last_measurement_time: @@ -150,14 +153,14 @@ class PowerMonitoring: cloudlog.exception("Integration failed") # Get the power usage - def get_power_used(self): + def get_power_used(self) -> int: return int(self.power_used_uWh) - def get_car_battery_capacity(self): + def get_car_battery_capacity(self) -> int: return int(self.car_battery_capacity_uWh) # See if we need to disable charging - def should_disable_charging(self, ignition, in_car, offroad_timestamp): + def should_disable_charging(self, ignition: bool, in_car: bool, offroad_timestamp: Optional[float]) -> bool: if offroad_timestamp is None: return False diff --git a/selfdrive/thermald/thermald.py b/selfdrive/thermald/thermald.py index 1b467f962..113ffaa04 100755 --- a/selfdrive/thermald/thermald.py +++ b/selfdrive/thermald/thermald.py @@ -1,25 +1,28 @@ #!/usr/bin/env python3 import datetime import os +import queue +import threading import time +from collections import OrderedDict, namedtuple from pathlib import Path from typing import Dict, Optional, Tuple -from collections import namedtuple, OrderedDict import psutil from smbus2 import SMBus import cereal.messaging as messaging from cereal import log +from common.dict_helpers import strip_deprecated_keys from common.filter_simple import FirstOrderFilter from common.numpy_fast import interp -from common.params import Params, ParamKeyType +from common.params import Params from common.realtime import DT_TRML, sec_since_boot -from common.dict_helpers import strip_deprecated_keys from selfdrive.controls.lib.alertmanager import set_offroad_alert from selfdrive.controls.lib.pid import PIController -from selfdrive.hardware import EON, TICI, PC, HARDWARE +from selfdrive.hardware import EON, HARDWARE, PC, TICI from selfdrive.loggerd.config import get_available_percent +from selfdrive.statsd import statlog from selfdrive.swaglog import cloudlog from selfdrive.thermald.power_monitoring import PowerMonitoring from selfdrive.version import terms_version, training_version @@ -30,8 +33,10 @@ NetworkStrength = log.DeviceState.NetworkStrength CURRENT_TAU = 15. # 15s time constant TEMP_TAU = 5. # 5s time constant DISCONNECT_TIMEOUT = 5. # wait 5 seconds before going offroad after disconnect so you get an alert +PANDA_STATES_TIMEOUT = int(1000 * 2.5 * DT_TRML) # 2.5x the expected pandaState frequency ThermalBand = namedtuple("ThermalBand", ['min_temp', 'max_temp']) +HardwareState = namedtuple("HardwareState", ['network_type', 'network_strength', 'network_info', 'nvme_temps', 'modem_temps']) # List of thermal bands. We will stay within this region as long as we are within the bounds. # When exiting the bounds, we'll jump to the lower or higher band. Bands are ordered in the dict. @@ -81,7 +86,7 @@ def set_eon_fan(val): try: i = [0x1, 0x3 | 0, 0x3 | 0x08, 0x3 | 0x10][val] bus.write_i2c_block_data(0x3d, 0, [i]) - except IOError: + except OSError: # tusb320 if val == 0: bus.write_i2c_block_data(0x67, 0xa, [0]) @@ -152,22 +157,59 @@ def set_offroad_alert_if_changed(offroad_alert: str, show_alert: bool, extra_tex set_offroad_alert(offroad_alert, show_alert, extra_text) -def thermald_thread(): +def hw_state_thread(end_event, hw_queue): + """Handles non critical hardware state, and sends over queue""" + count = 0 + registered_count = 0 + while not end_event.is_set(): + # these are expensive calls. update every 10s + if (count % int(10. / DT_TRML)) == 0: + try: + network_type = HARDWARE.get_network_type() + + hw_state = HardwareState( + network_type=network_type, + network_strength=HARDWARE.get_network_strength(network_type), + network_info=HARDWARE.get_network_info(), + nvme_temps=HARDWARE.get_nvme_temperatures(), + modem_temps=HARDWARE.get_modem_temperatures(), + ) + + try: + hw_queue.put_nowait(hw_state) + except queue.Full: + pass + + if TICI and (hw_state.network_info is not None) and (hw_state.network_info.get('state', None) == "REGISTERED"): + registered_count += 1 + else: + registered_count = 0 + + if registered_count > 10: + cloudlog.warning(f"Modem stuck in registered state {hw_state.network_info}. nmcli conn up lte") + os.system("nmcli conn up lte") + registered_count = 0 + + except Exception: + cloudlog.exception("Error getting network status") + + count += 1 + time.sleep(DT_TRML) + + +def thermald_thread(end_event, hw_queue): pm = messaging.PubMaster(['deviceState']) - - pandaState_timeout = int(1000 * 2.5 * DT_TRML) # 2.5x the expected pandaState frequency - pandaState_sock = messaging.sub_sock('pandaStates', timeout=pandaState_timeout) - sm = messaging.SubMaster(["peripheralState", "gpsLocationExternal", "managerState"]) + sm = messaging.SubMaster(["peripheralState", "gpsLocationExternal", "controlsState", "pandaStates"], poll=["pandaStates"]) fan_speed = 0 count = 0 - onroad_conditions = { + onroad_conditions: Dict[str, bool] = { "ignition": False, } - startup_conditions = {} - startup_conditions_prev = {} + startup_conditions: Dict[str, bool] = {} + startup_conditions_prev: Dict[str, bool] = {} off_ts = None started_ts = None @@ -175,26 +217,24 @@ def thermald_thread(): thermal_status = ThermalStatus.green usb_power = True - network_type = NetworkType.none - network_strength = NetworkStrength.unknown - network_info = None - modem_version = None - registered_count = 0 - nvme_temps = None - modem_temps = None + last_hw_state = HardwareState( + network_type=NetworkType.none, + network_strength=NetworkStrength.unknown, + network_info=None, + nvme_temps=[], + modem_temps=[], + ) current_filter = FirstOrderFilter(0., CURRENT_TAU, DT_TRML) temp_filter = FirstOrderFilter(0., TEMP_TAU, DT_TRML) - pandaState_prev = None should_start_prev = False in_car = False handle_fan = None is_uno = False - ui_running_prev = False + engaged_prev = False params = Params() power_monitor = PowerMonitoring() - no_panda_cnt = 0 HARDWARE.initialize_hardware() thermal_config = HARDWARE.get_thermal_config() @@ -202,31 +242,20 @@ def thermald_thread(): # TODO: use PI controller for UNO controller = PIController(k_p=0, k_i=2e-3, neg_limit=-80, pos_limit=0, rate=(1 / DT_TRML)) - # Leave flag for loggerd to indicate device was left onroad - if params.get_bool("IsOnroad"): - params.put_bool("BootedOnroad", True) + while not end_event.is_set(): + sm.update(PANDA_STATES_TIMEOUT) - while True: - pandaStates = messaging.recv_sock(pandaState_sock, wait=True) - - sm.update(0) + pandaStates = sm['pandaStates'] peripheralState = sm['peripheralState'] msg = read_thermal(thermal_config) - if pandaStates is not None and len(pandaStates.pandaStates) > 0: - pandaState = pandaStates.pandaStates[0] + if sm.updated['pandaStates'] and len(pandaStates) > 0: - # If we lose connection to the panda, wait 5 seconds before going offroad - if pandaState.pandaType == log.PandaState.PandaType.unknown: - no_panda_cnt += 1 - if no_panda_cnt > DISCONNECT_TIMEOUT / DT_TRML: - if onroad_conditions["ignition"]: - cloudlog.error("Lost panda connection while onroad") - onroad_conditions["ignition"] = False - else: - no_panda_cnt = 0 - onroad_conditions["ignition"] = pandaState.ignitionLine or pandaState.ignitionCan + # Set ignition based on any panda connected + onroad_conditions["ignition"] = any(ps.ignitionLine or ps.ignitionCan for ps in pandaStates if ps.pandaType != log.PandaState.PandaType.unknown) + + pandaState = pandaStates[0] in_car = pandaState.harnessStatus != log.PandaState.HarnessStatus.notConnected usb_power = peripheralState.usbPowerMode != log.PeripheralState.UsbPowerMode.client @@ -246,53 +275,23 @@ def thermald_thread(): setup_eon_fan() handle_fan = handle_fan_eon - # Handle disconnect - if pandaState_prev is not None: - if pandaState.pandaType == log.PandaState.PandaType.unknown and \ - pandaState_prev.pandaType != log.PandaState.PandaType.unknown: - params.clear_all(ParamKeyType.CLEAR_ON_PANDA_DISCONNECT) - pandaState_prev = pandaState - - # these are expensive calls. update every 10s - if (count % int(10. / DT_TRML)) == 0: - try: - network_type = HARDWARE.get_network_type() - network_strength = HARDWARE.get_network_strength(network_type) - network_info = HARDWARE.get_network_info() # pylint: disable=assignment-from-none - nvme_temps = HARDWARE.get_nvme_temperatures() - modem_temps = HARDWARE.get_modem_temperatures() - - # Log modem version once - if modem_version is None: - modem_version = HARDWARE.get_modem_version() # pylint: disable=assignment-from-none - if modem_version is not None: - cloudlog.warning(f"Modem version: {modem_version}") - - if TICI and (network_info.get('state', None) == "REGISTERED"): - registered_count += 1 - else: - registered_count = 0 - - if registered_count > 10: - cloudlog.warning(f"Modem stuck in registered state {network_info}. nmcli conn up lte") - os.system("nmcli conn up lte") - registered_count = 0 - - except Exception: - cloudlog.exception("Error getting network status") + try: + last_hw_state = hw_queue.get_nowait() + except queue.Empty: + pass msg.deviceState.freeSpacePercent = get_available_percent(default=100.0) msg.deviceState.memoryUsagePercent = int(round(psutil.virtual_memory().percent)) msg.deviceState.cpuUsagePercent = [int(round(n)) for n in psutil.cpu_percent(percpu=True)] msg.deviceState.gpuUsagePercent = int(round(HARDWARE.get_gpu_usage_percent())) - msg.deviceState.networkType = network_type - msg.deviceState.networkStrength = network_strength - if network_info is not None: - msg.deviceState.networkInfo = network_info - if nvme_temps is not None: - msg.deviceState.nvmeTempC = nvme_temps - if modem_temps is not None: - msg.deviceState.modemTempC = modem_temps + + msg.deviceState.networkType = last_hw_state.network_type + msg.deviceState.networkStrength = last_hw_state.network_strength + if last_hw_state.network_info is not None: + msg.deviceState.networkInfo = last_hw_state.network_info + + msg.deviceState.nvmeTempC = last_hw_state.nvme_temps + msg.deviceState.modemTempC = last_hw_state.modem_temps msg.deviceState.screenBrightnessPercent = HARDWARE.get_screen_brightness() msg.deviceState.batteryPercent = HARDWARE.get_battery_capacity() @@ -344,7 +343,8 @@ def thermald_thread(): set_offroad_alert_if_changed("Offroad_TemperatureTooHigh", (not onroad_conditions["device_temp_good"])) if TICI: - set_offroad_alert_if_changed("Offroad_StorageMissing", (not Path("/data/media").is_mount())) + missing = (not Path("/data/media").is_mount()) and (not os.path.isfile("/persist/comma/living-in-the-moment")) + set_offroad_alert_if_changed("Offroad_StorageMissing", missing) # Handle offroad/onroad transition should_start = all(onroad_conditions.values()) @@ -354,8 +354,23 @@ def thermald_thread(): if should_start != should_start_prev or (count == 0): params.put_bool("IsOnroad", should_start) params.put_bool("IsOffroad", not should_start) + + params.put_bool("IsEngaged", False) + engaged_prev = False HARDWARE.set_power_save(not should_start) + if sm.updated['controlsState']: + engaged = sm['controlsState'].enabled + if engaged != engaged_prev: + params.put_bool("IsEngaged", engaged) + engaged_prev = engaged + + try: + with open('/dev/kmsg', 'w') as kmsg: + kmsg.write(f"<3>[thermald] engaged: {engaged}\n") + except Exception: + pass + if should_start: off_ts = None if started_ts is None: @@ -381,16 +396,8 @@ def thermald_thread(): # Check if we need to shut down if power_monitor.should_shutdown(peripheralState, onroad_conditions["ignition"], in_car, off_ts, started_seen): - cloudlog.info(f"shutting device down, offroad since {off_ts}") - # TODO: add function for blocking cloudlog instead of sleep - time.sleep(10) - HARDWARE.shutdown() - - # If UI has crashed, set the brightness to reasonable non-zero value - ui_running = "ui" in (p.name for p in sm["managerState"].processes if p.running) - if ui_running_prev and not ui_running: - HARDWARE.set_screen_brightness(20) - ui_running_prev = ui_running + cloudlog.warning(f"shutting device down, offroad since {off_ts}") + params.put_bool("DoShutdown", True) msg.deviceState.chargingError = current_filter.x > 0. and msg.deviceState.batteryPercent < 90 # if current is positive, then battery is being discharged msg.deviceState.started = started_ts is not None @@ -409,6 +416,27 @@ def thermald_thread(): should_start_prev = should_start startup_conditions_prev = startup_conditions.copy() + # Log to statsd + statlog.gauge("free_space_percent", msg.deviceState.freeSpacePercent) + statlog.gauge("gpu_usage_percent", msg.deviceState.gpuUsagePercent) + statlog.gauge("memory_usage_percent", msg.deviceState.memoryUsagePercent) + for i, usage in enumerate(msg.deviceState.cpuUsagePercent): + statlog.gauge(f"cpu{i}_usage_percent", usage) + for i, temp in enumerate(msg.deviceState.cpuTempC): + statlog.gauge(f"cpu{i}_temperature", temp) + for i, temp in enumerate(msg.deviceState.gpuTempC): + statlog.gauge(f"gpu{i}_temperature", temp) + statlog.gauge("memory_temperature", msg.deviceState.memoryTempC) + statlog.gauge("ambient_temperature", msg.deviceState.ambientTempC) + for i, temp in enumerate(msg.deviceState.pmicTempC): + statlog.gauge(f"pmic{i}_temperature", temp) + for i, temp in enumerate(last_hw_state.nvme_temps): + statlog.gauge(f"nvme_temperature{i}", temp) + for i, temp in enumerate(last_hw_state.modem_temps): + statlog.gauge(f"modem_temperature{i}", temp) + statlog.gauge("fan_speed_percent_desired", msg.deviceState.fanSpeedPercentDesired) + statlog.gauge("screen_brightness_percent", msg.deviceState.screenBrightnessPercent) + # report to server once every 10 minutes if (count % int(600. / DT_TRML)) == 0: if EON and started_ts is None and msg.deviceState.memoryUsagePercent > 40: @@ -416,7 +444,7 @@ def thermald_thread(): cloudlog.event("STATUS_PACKET", count=count, - pandaStates=(strip_deprecated_keys(pandaStates.to_dict()) if pandaStates else None), + pandaStates=[strip_deprecated_keys(p.to_dict()) for p in pandaStates], peripheralState=strip_deprecated_keys(peripheralState.to_dict()), location=(strip_deprecated_keys(sm["gpsLocationExternal"].to_dict()) if sm.alive["gpsLocationExternal"] else None), deviceState=strip_deprecated_keys(msg.to_dict())) @@ -425,7 +453,27 @@ def thermald_thread(): def main(): - thermald_thread() + hw_queue = queue.Queue(maxsize=1) + end_event = threading.Event() + + threads = [ + threading.Thread(target=hw_state_thread, args=(end_event, hw_queue)), + threading.Thread(target=thermald_thread, args=(end_event, hw_queue)), + ] + + for t in threads: + t.start() + + try: + while True: + time.sleep(1) + if not all(t.is_alive() for t in threads): + break + finally: + end_event.set() + + for t in threads: + t.join() if __name__ == "__main__": diff --git a/selfdrive/timezoned.py b/selfdrive/timezoned.py index 74da5fe35..6a7e9122c 100755 --- a/selfdrive/timezoned.py +++ b/selfdrive/timezoned.py @@ -3,6 +3,7 @@ import json import os import time import subprocess +from typing import NoReturn import requests from timezonefinder import TimezoneFinder @@ -30,7 +31,7 @@ def set_timezone(valid_timezones, timezone): cloudlog.exception(f"Error setting timezone to {timezone}") -def main(): +def main() -> NoReturn: params = Params() tf = TimezoneFinder() diff --git a/selfdrive/tombstoned.py b/selfdrive/tombstoned.py index a301725ba..459ab2f0f 100755 --- a/selfdrive/tombstoned.py +++ b/selfdrive/tombstoned.py @@ -7,15 +7,14 @@ import signal import subprocess import time import glob +from typing import NoReturn -import sentry_sdk - -from common.params import Params from common.file_helpers import mkdirs_exists_ok -from selfdrive.hardware import TICI, HARDWARE +from selfdrive.hardware import TICI from selfdrive.loggerd.config import ROOT +import selfdrive.sentry as sentry from selfdrive.swaglog import cloudlog -from selfdrive.version import get_branch, get_commit, get_dirty, get_origin, get_version +from selfdrive.version import get_commit MAX_SIZE = 100000 * 10 # mal size is 40-100k, allow up to 1M if TICI: @@ -31,16 +30,6 @@ def safe_fn(s): return "".join(c for c in s if c.isalnum() or c in extra).rstrip() -def sentry_report(fn, message, contents): - cloudlog.error({'tombstone': message}) - - with sentry_sdk.configure_scope() as scope: - scope.set_extra("tombstone_fn", fn) - scope.set_extra("tombstone", contents) - sentry_sdk.capture_message(message=message) - sentry_sdk.flush() - - def clear_apport_folder(): for f in glob.glob(APPORT_DIR + '*'): try: @@ -103,7 +92,7 @@ def report_tombstone_android(fn): if fault_idx >= 0: message = message[:fault_idx] - sentry_report(fn, message, contents) + sentry.report_tombstone(fn, message, contents) # Copy crashlog to upload folder clean_path = executable.replace('./', '').replace('/', '_') @@ -177,7 +166,7 @@ def report_tombstone_apport(fn): contents = stacktrace + "\n\n" + contents message = message + " - " + crash_function - sentry_report(fn, message, contents) + sentry.report_tombstone(fn, message, contents) # Copy crashlog to upload folder clean_path = path.replace('/', '_') @@ -197,22 +186,13 @@ def report_tombstone_apport(fn): pass -def main(): - clear_apport_folder() # Clear apport folder on start, otherwise duplicate crashes won't register +def main() -> NoReturn: + sentry.init(sentry.SentryProject.SELFDRIVE_NATIVE) + + # Clear apport folder on start, otherwise duplicate crashes won't register + clear_apport_folder() initial_tombstones = set(get_tombstones()) - sentry_sdk.utils.MAX_STRING_LENGTH = 8192 - sentry_sdk.init("https://a40f22e13cbc4261873333c125fc9d38@o33823.ingest.sentry.io/157615", - default_integrations=False, release=get_version()) - - dongle_id = Params().get("DongleId", encoding='utf-8') - sentry_sdk.set_user({"id": dongle_id}) - sentry_sdk.set_tag("dirty", get_dirty()) - sentry_sdk.set_tag("origin", get_origin()) - sentry_sdk.set_tag("branch", get_branch()) - sentry_sdk.set_tag("commit", get_commit()) - sentry_sdk.set_tag("device", HARDWARE.get_device_type()) - while True: now_tombstones = set(get_tombstones()) diff --git a/selfdrive/ui/.gitignore b/selfdrive/ui/.gitignore index 5d656f889..5f8a96edf 100644 --- a/selfdrive/ui/.gitignore +++ b/selfdrive/ui/.gitignore @@ -1,6 +1,7 @@ moc_* *.moc +_mui watch3 installer/installers/* replay/replay diff --git a/selfdrive/ui/SConscript b/selfdrive/ui/SConscript index 52e4e0c42..00d528e63 100644 --- a/selfdrive/ui/SConscript +++ b/selfdrive/ui/SConscript @@ -47,7 +47,7 @@ asset_obj = qt_env.Object("assets", assets) qt_env.Program("soundd/_soundd", ["soundd/main.cc", "soundd/sound.cc"], LIBS=qt_libs) if GetOption('test'): qt_env.Program("tests/playsound", "tests/playsound.cc", LIBS=base_libs) - qt_env.Program('tests/test_sound', ['tests/test_runner.cc', 'soundd/sound.cc', 'tests/test_sound.cc'], LIBS=[base_libs]) + qt_env.Program('tests/test_sound', ['tests/test_runner.cc', 'soundd/sound.cc', 'tests/test_sound.cc'], LIBS=qt_libs) qt_env.SharedLibrary("qt/python_helpers", ["qt/qt_window.cc"], LIBS=qt_libs) @@ -73,6 +73,9 @@ if GetOption('extras'): # buidl updater UI qt_env.Program("qt/setup/updater", ["qt/setup/updater.cc", asset_obj], LIBS=qt_libs) + # build mui + qt_env.Program("_mui", ["mui.cc"], LIBS=qt_libs) + # build installers senv = qt_env.Clone() senv['LINKFLAGS'].append('-Wl,-strip-debug') @@ -112,13 +115,12 @@ if GetOption('extras'): if arch in ['x86_64', 'Darwin'] or GetOption('extras'): qt_env['CXXFLAGS'] += ["-Wno-deprecated-declarations"] - replay_lib_src = ["replay/replay.cc", "replay/camera.cc", "replay/filereader.cc", "replay/logreader.cc", "replay/framereader.cc", "replay/route.cc", "replay/util.cc"] + replay_lib_src = ["replay/replay.cc", "replay/consoleui.cc", "replay/camera.cc", "replay/filereader.cc", "replay/logreader.cc", "replay/framereader.cc", "replay/route.cc", "replay/util.cc"] replay_lib = qt_env.Library("qt_replay", replay_lib_src, LIBS=base_libs) - replay_libs = [replay_lib, 'avutil', 'avcodec', 'avformat', 'bz2', 'curl', 'yuv'] + qt_libs + replay_libs = [replay_lib, 'avutil', 'avcodec', 'avformat', 'bz2', 'curl', 'yuv', 'ncurses'] + qt_libs qt_env.Program("replay/replay", ["replay/main.cc"], LIBS=replay_libs) - - qt_env.Program("watch3", ["watch3.cc"], LIBS=qt_libs + ['common', 'json11']) + qt_env.Program("watch3", ["watch3.cc"], LIBS=qt_libs + ['common', 'json11', 'zmq', 'visionipc', 'messaging']) if GetOption('test'): qt_env.Program('replay/tests/test_replay', ['replay/tests/test_runner.cc', 'replay/tests/test_replay.cc'], LIBS=[replay_libs]) diff --git a/selfdrive/ui/mui.cc b/selfdrive/ui/mui.cc new file mode 100644 index 000000000..55b9a4747 --- /dev/null +++ b/selfdrive/ui/mui.cc @@ -0,0 +1,138 @@ +#include +#include +#include +#include + +#include "cereal/messaging/messaging.h" +#include "selfdrive/ui/ui.h" +#include "selfdrive/ui/qt/qt_window.h" + +class StatusBar : public QGraphicsRectItem { + private: + QLinearGradient linear_gradient; + QRadialGradient radial_gradient; + QTimer animation_timer; + const int animation_length = 10; + int animation_index = 0; + + public: + StatusBar(double x, double y, double width, double height) : QGraphicsRectItem {x, y, width, height} { + linear_gradient = QLinearGradient(0, 0, 0, height/2); + linear_gradient.setSpread(QGradient::ReflectSpread); + + radial_gradient = QRadialGradient(width/2, height/2, width/8); + QObject::connect(&animation_timer, &QTimer::timeout, [=]() { + animation_index++; + animation_index %= animation_length; + }); + animation_timer.start(50); + } + + void solidColor(QColor color) { + QColor dark_color = QColor(color); + dark_color.setAlphaF(0.5); + + linear_gradient.setColorAt(0, dark_color); + linear_gradient.setColorAt(1, color); + setBrush(QBrush(linear_gradient)); + } + + // these need to be called continuously for the animations to work. + // can probably clean that up with some more abstractions + void blinkingColor(QColor color) { + QColor dark_color = QColor(color); + dark_color.setAlphaF(0.1); + + int radius = (rect().width() / animation_length) * animation_index; + QPoint center = QPoint(rect().width()/2, rect().height()/2); + radial_gradient.setCenter(center); + radial_gradient.setFocalPoint(center); + radial_gradient.setRadius(radius); + + radial_gradient.setColorAt(1, dark_color); + radial_gradient.setColorAt(0, color); + setBrush(QBrush(radial_gradient)); + } + + void laneChange(cereal::LateralPlan::LaneChangeDirection direction) { + QColor dark_color = QColor(bg_colors[STATUS_ENGAGED]); + dark_color.setAlphaF(0.1); + + int x = (rect().width() / animation_length) * animation_index; + QPoint center = QPoint(((direction == cereal::LateralPlan::LaneChangeDirection::RIGHT) ? x : (rect().width() - x)), rect().height()/2); + radial_gradient.setCenter(center); + radial_gradient.setFocalPoint(center); + radial_gradient.setRadius(rect().width()/5); + + radial_gradient.setColorAt(1, dark_color); + radial_gradient.setColorAt(0, bg_colors[STATUS_ENGAGED]); + setBrush(QBrush(radial_gradient)); + } + + void paint(QPainter *painter, const QStyleOptionGraphicsItem *option, QWidget *widget = nullptr) override { + painter->setPen(QPen()); + painter->setBrush(brush()); + + double rounding_radius = rect().height()/2; + painter->drawRoundedRect(rect(), rounding_radius, rounding_radius); + } +}; + +int main(int argc, char *argv[]) { + QApplication a(argc, argv); + QWidget w; + setMainWindow(&w); + + w.setStyleSheet("background-color: black;"); + + // our beautiful UI + QVBoxLayout *layout = new QVBoxLayout(&w); + + QGraphicsScene *scene = new QGraphicsScene(); + StatusBar *status_bar = new StatusBar(0, 0, 1000, 50); + scene->addItem(status_bar); + + QGraphicsView *graphics_view = new QGraphicsView(scene); + layout->insertSpacing(0, 400); + layout->addWidget(graphics_view, 0, Qt::AlignCenter); + + QTimer timer; + QObject::connect(&timer, &QTimer::timeout, [=]() { + static SubMaster sm({"deviceState", "controlsState", "lateralPlan"}); + + bool onroad_prev = sm.allAliveAndValid({"deviceState"}) && + sm["deviceState"].getDeviceState().getStarted(); + sm.update(0); + + bool onroad = sm.allAliveAndValid({"deviceState"}) && + sm["deviceState"].getDeviceState().getStarted(); + + if (onroad) { + auto cs = sm["controlsState"].getControlsState(); + UIStatus status = cs.getEnabled() ? STATUS_ENGAGED : STATUS_DISENGAGED; + if (cs.getAlertStatus() == cereal::ControlsState::AlertStatus::USER_PROMPT) { + status = STATUS_WARNING; + } else if (cs.getAlertStatus() == cereal::ControlsState::AlertStatus::CRITICAL) { + status = STATUS_ALERT; + } + + auto lp = sm["lateralPlan"].getLateralPlan(); + if (lp.getLaneChangeState() == cereal::LateralPlan::LaneChangeState::PRE_LANE_CHANGE || status == STATUS_ALERT) { + status_bar->blinkingColor(bg_colors[status]); + } else if (lp.getLaneChangeState() == cereal::LateralPlan::LaneChangeState::LANE_CHANGE_STARTING || + lp.getLaneChangeState() == cereal::LateralPlan::LaneChangeState::LANE_CHANGE_FINISHING) { + status_bar->laneChange(lp.getLaneChangeDirection()); + } else { + status_bar->solidColor(bg_colors[status]); + } + } + + if ((onroad != onroad_prev) || sm.frame < 2) { + Hardware::set_brightness(50); + Hardware::set_display_power(onroad); + } + }); + timer.start(50); + + return a.exec(); +} diff --git a/selfdrive/ui/qt/home.cc b/selfdrive/ui/qt/home.cc index 1e8926495..df4f47494 100644 --- a/selfdrive/ui/qt/home.cc +++ b/selfdrive/ui/qt/home.cc @@ -19,7 +19,6 @@ HomeWindow::HomeWindow(QWidget* parent) : QWidget(parent) { sidebar = new Sidebar(this); main_layout->addWidget(sidebar); - QObject::connect(this, &HomeWindow::update, sidebar, &Sidebar::updateState); QObject::connect(sidebar, &Sidebar::openSettings, this, &HomeWindow::openSettings); slayout = new QStackedLayout(); @@ -31,15 +30,13 @@ HomeWindow::HomeWindow(QWidget* parent) : QWidget(parent) { onroad = new OnroadWindow(this); slayout->addWidget(onroad); - QObject::connect(this, &HomeWindow::update, onroad, &OnroadWindow::updateStateSignal); - QObject::connect(this, &HomeWindow::offroadTransitionSignal, onroad, &OnroadWindow::offroadTransitionSignal); - driver_view = new DriverViewWindow(this); connect(driver_view, &DriverViewWindow::done, [=] { showDriverView(false); }); slayout->addWidget(driver_view); setAttribute(Qt::WA_NoSystemBackground); + QObject::connect(uiState(), &UIState::offroadTransition, this, &HomeWindow::offroadTransition); } void HomeWindow::showSidebar(bool show) { @@ -53,7 +50,6 @@ void HomeWindow::offroadTransition(bool offroad) { } else { slayout->setCurrentWidget(onroad); } - emit offroadTransitionSignal(offroad); } void HomeWindow::showDriverView(bool show) { diff --git a/selfdrive/ui/qt/home.h b/selfdrive/ui/qt/home.h index 0e65ef05e..732071c15 100644 --- a/selfdrive/ui/qt/home.h +++ b/selfdrive/ui/qt/home.h @@ -43,10 +43,6 @@ signals: void openSettings(); void closeSettings(); - // forwarded signals - void update(const UIState &s); - void offroadTransitionSignal(bool offroad); - public slots: void offroadTransition(bool offroad); void showDriverView(bool show); diff --git a/selfdrive/ui/qt/maps/map.cc b/selfdrive/ui/qt/maps/map.cc index e1bfe96c8..5e5fdb40c 100644 --- a/selfdrive/ui/qt/maps/map.cc +++ b/selfdrive/ui/qt/maps/map.cc @@ -106,7 +106,7 @@ void MapWindow::initLayers() { } void MapWindow::timerUpdate() { - if (!QUIState::ui_state.scene.started) { + if (!uiState()->scene.started) { return; } @@ -387,7 +387,7 @@ void MapInstructions::updateDistance(float d) { d = std::max(d, 0.0f); QString distance_str; - if (QUIState::ui_state.scene.is_metric) { + if (uiState()->scene.is_metric) { if (d > 500) { distance_str.setNum(d / 1000, 'f', 1); distance_str += " km"; @@ -498,10 +498,9 @@ void MapInstructions::updateInstructions(cereal::NavInstruction::Reader instruct fn += "turn_straight"; } - QPixmap pix(fn + ICON_SUFFIX); auto icon = new QLabel; int wh = active ? 125 : 75; - icon->setPixmap(pix.scaled(wh, wh, Qt::IgnoreAspectRatio, Qt::SmoothTransformation)); + icon->setPixmap(loadPixmap(fn + ICON_SUFFIX, {wh, wh}, Qt::IgnoreAspectRatio)); icon->setSizePolicy(QSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed)); lane_layout->addWidget(icon); } @@ -620,7 +619,7 @@ void MapETA::updateETA(float s, float s_typical, float d) { // Distance QString distance_str; float num = 0; - if (QUIState::ui_state.scene.is_metric) { + if (uiState()->scene.is_metric) { num = d / 1000.0; distance_unit->setText("km"); } else { diff --git a/selfdrive/ui/qt/offroad/driverview.cc b/selfdrive/ui/qt/offroad/driverview.cc index 6f03e2ed4..3ab5b999b 100644 --- a/selfdrive/ui/qt/offroad/driverview.cc +++ b/selfdrive/ui/qt/offroad/driverview.cc @@ -26,7 +26,7 @@ void DriverViewWindow::mouseReleaseEvent(QMouseEvent* e) { } DriverViewScene::DriverViewScene(QWidget* parent) : sm({"driverState"}), QWidget(parent) { - face_img = QImage("../assets/img_driver_face.png").scaled(FACE_IMG_SIZE, FACE_IMG_SIZE, Qt::KeepAspectRatio, Qt::SmoothTransformation); + face_img = loadPixmap("../assets/img_driver_face.png", {FACE_IMG_SIZE, FACE_IMG_SIZE}); } void DriverViewScene::showEvent(QShowEvent* event) { @@ -97,5 +97,5 @@ void DriverViewScene::paintEvent(QPaintEvent* event) { const int img_x = is_rhd ? rect2.right() - FACE_IMG_SIZE - img_offset : rect2.left() + img_offset; const int img_y = rect2.bottom() - FACE_IMG_SIZE - img_offset; p.setOpacity(face_detected ? 1.0 : 0.3); - p.drawImage(img_x, img_y, face_img); + p.drawPixmap(img_x, img_y, face_img); } diff --git a/selfdrive/ui/qt/offroad/driverview.h b/selfdrive/ui/qt/offroad/driverview.h index 8eab76a3d..4d4a4358e 100644 --- a/selfdrive/ui/qt/offroad/driverview.h +++ b/selfdrive/ui/qt/offroad/driverview.h @@ -24,7 +24,7 @@ protected: private: Params params; SubMaster sm; - QImage face_img; + QPixmap face_img; bool is_rhd = false; bool frame_updated = false; }; diff --git a/selfdrive/ui/qt/offroad/networking.cc b/selfdrive/ui/qt/offroad/networking.cc index dd519dd66..9c2088b1d 100644 --- a/selfdrive/ui/qt/offroad/networking.cc +++ b/selfdrive/ui/qt/offroad/networking.cc @@ -99,14 +99,12 @@ void Networking::wrongPassword(const QString &ssid) { } } -void Networking::showEvent(QShowEvent* event) { - // Wait to refresh to avoid delay when showing Networking widget - QTimer::singleShot(300, this, [=]() { - if (this->isVisible()) { - wifi->refreshNetworks(); - refresh(); - } - }); +void Networking::showEvent(QShowEvent *event) { + wifi->start(); +} + +void Networking::hideEvent(QHideEvent *event) { + wifi->stop(); } // AdvancedNetworking functions @@ -158,7 +156,7 @@ AdvancedNetworking::AdvancedNetworking(QWidget* parent, WifiManager* wifi): QWid list->addItem(roamingToggle); // APN settings - ButtonControl *editApnButton = new ButtonControl("APN settings", "EDIT"); + ButtonControl *editApnButton = new ButtonControl("APN Setting", "EDIT"); connect(editApnButton, &ButtonControl::clicked, [=]() { const bool roamingEnabled = params.getBool("GsmRoaming"); const QString cur_apn = QString::fromStdString(params.get("GsmApn")); diff --git a/selfdrive/ui/qt/offroad/networking.h b/selfdrive/ui/qt/offroad/networking.h index 037ef82f6..e78d65ef0 100644 --- a/selfdrive/ui/qt/offroad/networking.h +++ b/selfdrive/ui/qt/offroad/networking.h @@ -65,6 +65,7 @@ private: protected: void showEvent(QShowEvent* event) override; + void hideEvent(QHideEvent* event) override; public slots: void refresh(); diff --git a/selfdrive/ui/qt/offroad/settings.cc b/selfdrive/ui/qt/offroad/settings.cc index 72bfd2eb8..f3584460d 100644 --- a/selfdrive/ui/qt/offroad/settings.cc +++ b/selfdrive/ui/qt/offroad/settings.cc @@ -38,7 +38,7 @@ TogglesPanel::TogglesPanel(SettingsWindow *parent) : ListWidget(parent) { { "IsLdwEnabled", "Enable Lane Departure Warnings", - "Receive alerts to steer back into the lane when your vehicle drifts over a detected lane line without a turn signal activated while driving over 31mph (50kph).", + "Receive alerts to steer back into the lane when your vehicle drifts over a detected lane line without a turn signal activated while driving over 31 mph (50 km/h).", "../assets/offroad/icon_warning.png", }, { @@ -53,12 +53,6 @@ TogglesPanel::TogglesPanel(SettingsWindow *parent) : ListWidget(parent) { "Display speed in km/h instead of mph.", "../assets/offroad/icon_metric.png", }, - { - "CommunityFeaturesToggle", - "Enable Community Features", - "Use features, such as community supported hardware, from the open source community that are not maintained or supported by comma.ai and have not been confirmed to meet the standard safety model. Be extra cautious when using these features", - "../assets/offroad/icon_shell.png", - }, { "RecordFront", "Record and Upload Driver Camera", @@ -98,7 +92,7 @@ TogglesPanel::TogglesPanel(SettingsWindow *parent) : ListWidget(parent) { bool locked = params.getBool((param + "Lock").toStdString()); toggle->setEnabled(!locked); if (!locked) { - connect(parent, &SettingsWindow::offroadTransition, toggle, &ParamControl::setEnabled); + connect(uiState(), &UIState::offroadTransition, toggle, &ParamControl::setEnabled); } addItem(toggle); } @@ -144,7 +138,7 @@ DevicePanel::DevicePanel(SettingsWindow *parent) : ListWidget(parent) { addItem(regulatoryBtn); } - QObject::connect(parent, &SettingsWindow::offroadTransition, [=](bool offroad) { + QObject::connect(uiState(), &UIState::offroadTransition, [=](bool offroad) { for (auto btn : findChildren()) { btn->setEnabled(offroad); } @@ -164,6 +158,10 @@ DevicePanel::DevicePanel(SettingsWindow *parent) : ListWidget(parent) { power_layout->addWidget(poweroff_btn); QObject::connect(poweroff_btn, &QPushButton::clicked, this, &DevicePanel::poweroff); + if (Hardware::TICI()) { + connect(uiState(), &UIState::offroadTransition, poweroff_btn, &QPushButton::setVisible); + } + setStyleSheet(R"( #reboot_btn { height: 120px; border-radius: 15px; background-color: #393939; } #reboot_btn:pressed { background-color: #4a4a4a; } @@ -176,7 +174,7 @@ DevicePanel::DevicePanel(SettingsWindow *parent) : ListWidget(parent) { void DevicePanel::updateCalibDescription() { QString desc = "openpilot requires the device to be mounted within 4° left or right and " - "within 5° up or down. openpilot is continuously calibrating, resetting is rarely required."; + "within 5° up or 8° down. openpilot is continuously calibrating, resetting is rarely required."; std::string calib_bytes = Params().get("CalibrationParams"); if (!calib_bytes.empty()) { try { @@ -187,8 +185,8 @@ void DevicePanel::updateCalibDescription() { double pitch = calib.getRpyCalib()[1] * (180 / M_PI); double yaw = calib.getRpyCalib()[2] * (180 / M_PI); desc += QString(" Your device is pointed %1° %2 and %3° %4.") - .arg(QString::number(std::abs(pitch), 'g', 1), pitch > 0 ? "up" : "down", - QString::number(std::abs(yaw), 'g', 1), yaw > 0 ? "right" : "left"); + .arg(QString::number(std::abs(pitch), 'g', 1), pitch > 0 ? "down" : "up", + QString::number(std::abs(yaw), 'g', 1), yaw > 0 ? "left" : "right"); } } catch (kj::Exception) { qInfo() << "invalid CalibrationParams"; @@ -198,10 +196,10 @@ void DevicePanel::updateCalibDescription() { } void DevicePanel::reboot() { - if (QUIState::ui_state.status == UIStatus::STATUS_DISENGAGED) { + if (!uiState()->engaged()) { if (ConfirmationDialog::confirm("Are you sure you want to reboot?", this)) { // Check engaged again in case it changed while the dialog was open - if (QUIState::ui_state.status == UIStatus::STATUS_DISENGAGED) { + if (!uiState()->engaged()) { Params().putBool("DoReboot", true); } } @@ -211,10 +209,10 @@ void DevicePanel::reboot() { } void DevicePanel::poweroff() { - if (QUIState::ui_state.status == UIStatus::STATUS_DISENGAGED) { + if (!uiState()->engaged()) { if (ConfirmationDialog::confirm("Are you sure you want to power off?", this)) { // Check engaged again in case it changed while the dialog was open - if (QUIState::ui_state.status == UIStatus::STATUS_DISENGAGED) { + if (!uiState()->engaged()) { Params().putBool("DoShutdown", true); } } @@ -247,7 +245,7 @@ SoftwarePanel::SoftwarePanel(QWidget* parent) : ListWidget(parent) { params.putBool("DoUninstall", true); } }); - connect(parent, SIGNAL(offroadTransition(bool)), uninstallBtn, SLOT(setEnabled(bool))); + connect(uiState(), &UIState::offroadTransition, uninstallBtn, &QPushButton::setEnabled); QWidget *widgets[] = {versionLbl, lastUpdateLbl, updateBtn, gitBranchLbl, gitCommitLbl, osVersionLbl, uninstallBtn}; for (QWidget* w : widgets) { @@ -286,15 +284,14 @@ void SoftwarePanel::updateLabels() { osVersionLbl->setText(QString::fromStdString(Hardware::get_os_version()).trimmed()); } -QWidget * network_panel(QWidget * parent) { -#ifdef QCOM - QWidget *w = new QWidget(parent); - QVBoxLayout *layout = new QVBoxLayout(w); +C2NetworkPanel::C2NetworkPanel(QWidget *parent) : QWidget(parent) { + QVBoxLayout *layout = new QVBoxLayout(this); layout->setContentsMargins(50, 0, 50, 0); ListWidget *list = new ListWidget(); list->setSpacing(30); // wifi + tethering buttons +#ifdef QCOM auto wifiBtn = new ButtonControl("Wi-Fi Settings", "OPEN"); QObject::connect(wifiBtn, &ButtonControl::clicked, [=]() { HardwareEon::launch_wifi(); }); list->addItem(wifiBtn); @@ -302,17 +299,42 @@ QWidget * network_panel(QWidget * parent) { auto tetheringBtn = new ButtonControl("Tethering Settings", "OPEN"); QObject::connect(tetheringBtn, &ButtonControl::clicked, [=]() { HardwareEon::launch_tethering(); }); list->addItem(tetheringBtn); +#endif + ipaddress = new LabelControl("IP Address", ""); + list->addItem(ipaddress); // SSH key management list->addItem(new SshToggle()); list->addItem(new SshControl()); - layout->addWidget(list); layout->addStretch(1); +} + +void C2NetworkPanel::showEvent(QShowEvent *event) { + ipaddress->setText(getIPAddress()); +} + +QString C2NetworkPanel::getIPAddress() { + std::string result = util::check_output("ifconfig wlan0"); + if (result.empty()) return ""; + + const std::string inetaddrr = "inet addr:"; + std::string::size_type begin = result.find(inetaddrr); + if (begin == std::string::npos) return ""; + + begin += inetaddrr.length(); + std::string::size_type end = result.find(' ', begin); + if (end == std::string::npos) return ""; + + return result.substr(begin, end - begin).c_str(); +} + +QWidget *network_panel(QWidget *parent) { +#ifdef QCOM + return new C2NetworkPanel(parent); #else - Networking *w = new Networking(parent); + return new Networking(parent); #endif - return w; } void SettingsWindow::showEvent(QShowEvent *event) { diff --git a/selfdrive/ui/qt/offroad/settings.h b/selfdrive/ui/qt/offroad/settings.h index 7fc5a8581..c3acf3d94 100644 --- a/selfdrive/ui/qt/offroad/settings.h +++ b/selfdrive/ui/qt/offroad/settings.h @@ -24,7 +24,6 @@ protected: signals: void closeSettings(); - void offroadTransition(bool offroad); void reviewTrainingGuide(); void showDriverView(); @@ -77,3 +76,14 @@ private: Params params; QFileSystemWatcher *fs_watch; }; + +class C2NetworkPanel: public QWidget { + Q_OBJECT +public: + explicit C2NetworkPanel(QWidget* parent = nullptr); + +private: + void showEvent(QShowEvent *event) override; + QString getIPAddress(); + LabelControl *ipaddress; +}; diff --git a/selfdrive/ui/qt/offroad/wifiManager.cc b/selfdrive/ui/qt/offroad/wifiManager.cc index 097017392..1628f35d9 100644 --- a/selfdrive/ui/qt/offroad/wifiManager.cc +++ b/selfdrive/ui/qt/offroad/wifiManager.cc @@ -1,26 +1,12 @@ #include "selfdrive/ui/qt/offroad/wifiManager.h" -#include -#include -#include +#include "selfdrive/ui/ui.h" +#include "selfdrive/ui/qt/widgets/prime.h" #include "selfdrive/common/params.h" #include "selfdrive/common/swaglog.h" #include "selfdrive/ui/qt/util.h" -template -T get_response(const QDBusMessage &response) { - QVariant first = response.arguments().at(0); - QDBusVariant dbvFirst = first.value(); - QVariant vFirst = dbvFirst.variant(); - if (vFirst.canConvert()) { - return vFirst.value(); - } else { - LOGE("Variant unpacking failure"); - return T(); - } -} - bool compare_by_strength(const Network &a, const Network &b) { if (a.connected == ConnectedType::CONNECTED) return true; if (b.connected == ConnectedType::CONNECTED) return false; @@ -29,10 +15,34 @@ bool compare_by_strength(const Network &a, const Network &b) { return a.strength > b.strength; } -WifiManager::WifiManager(QWidget* parent) : QWidget(parent) { +template +T call(const QString &path, const QString &interface, const QString &method, Args &&...args) { + QDBusInterface nm = QDBusInterface(NM_DBUS_SERVICE, path, interface, QDBusConnection::systemBus()); + nm.setTimeout(DBUS_TIMEOUT); + QDBusMessage response = nm.call(method, args...); + if constexpr (std::is_same_v) { + return response; + } else if (response.arguments().count() >= 1) { + QVariant vFirst = response.arguments().at(0).value().variant(); + if (vFirst.canConvert()) { + return vFirst.value(); + } + QDebug critical = qCritical(); + critical << "Variant unpacking failure :" << method << ','; + (critical << ... << args); + } + return T(); +} + +template +QDBusPendingCall asyncCall(const QString &path, const QString &interface, const QString &method, Args &&...args) { + QDBusInterface nm = QDBusInterface(NM_DBUS_SERVICE, path, interface, QDBusConnection::systemBus()); + return nm.asyncCall(method, args...); +} + +WifiManager::WifiManager(QObject *parent) : QObject(parent) { qDBusRegisterMetaType(); qDBusRegisterMetaType(); - connecting_to_network = ""; // Set tethering ssid as "weedle" + first 4 characters of a dongle id tethering_ssid = "weedle"; @@ -44,97 +54,83 @@ WifiManager::WifiManager(QWidget* parent) : QWidget(parent) { if (!adapter.isEmpty()) { setup(); } else { - bus.connect(NM_DBUS_SERVICE, NM_DBUS_PATH, NM_DBUS_INTERFACE, "DeviceAdded", this, SLOT(deviceAdded(QDBusObjectPath))); + QDBusConnection::systemBus().connect(NM_DBUS_SERVICE, NM_DBUS_PATH, NM_DBUS_INTERFACE, "DeviceAdded", this, SLOT(deviceAdded(QDBusObjectPath))); } - QTimer* timer = new QTimer(this); - QObject::connect(timer, &QTimer::timeout, this, [=]() { - if (!adapter.isEmpty() && this->isVisible()) { - requestScan(); - } - }); - timer->start(5000); + timer.callOnTimeout(this, &WifiManager::requestScan); } void WifiManager::setup() { - QDBusInterface nm(NM_DBUS_SERVICE, adapter, NM_DBUS_INTERFACE_DEVICE, bus); + auto bus = QDBusConnection::systemBus(); bus.connect(NM_DBUS_SERVICE, adapter, NM_DBUS_INTERFACE_DEVICE, "StateChanged", this, SLOT(stateChange(unsigned int, unsigned int, unsigned int))); bus.connect(NM_DBUS_SERVICE, adapter, NM_DBUS_INTERFACE_PROPERTIES, "PropertiesChanged", this, SLOT(propertyChange(QString, QVariantMap, QStringList))); bus.connect(NM_DBUS_SERVICE, NM_DBUS_PATH_SETTINGS, NM_DBUS_INTERFACE_SETTINGS, "ConnectionRemoved", this, SLOT(connectionRemoved(QDBusObjectPath))); bus.connect(NM_DBUS_SERVICE, NM_DBUS_PATH_SETTINGS, NM_DBUS_INTERFACE_SETTINGS, "NewConnection", this, SLOT(newConnection(QDBusObjectPath))); - QDBusInterface device_props(NM_DBUS_SERVICE, adapter, NM_DBUS_INTERFACE_PROPERTIES, bus); - device_props.setTimeout(DBUS_TIMEOUT); - QDBusMessage response = device_props.call("Get", NM_DBUS_INTERFACE_DEVICE, "State"); - raw_adapter_state = get_response(response); + raw_adapter_state = call(adapter, NM_DBUS_INTERFACE_PROPERTIES, "Get", NM_DBUS_INTERFACE_DEVICE, "State"); + activeAp = call(adapter, NM_DBUS_INTERFACE_PROPERTIES, "Get", NM_DBUS_INTERFACE_DEVICE_WIRELESS, "ActiveAccessPoint").path(); - initActiveAp(); initConnections(); requestScan(); } -void WifiManager::refreshNetworks() { - if (adapter.isEmpty()) { - return; - } - seenNetworks.clear(); - ipv4_address = get_ipv4_address(); - - QDBusInterface nm(NM_DBUS_SERVICE, adapter, NM_DBUS_INTERFACE_DEVICE_WIRELESS, bus); - nm.setTimeout(DBUS_TIMEOUT); - - const QDBusReply> &response = nm.call("GetAllAccessPoints"); - for (const QDBusObjectPath &path : response.value()) { - const QByteArray &ssid = get_property(path.path(), "Ssid"); - unsigned int strength = get_ap_strength(path.path()); - if (ssid.isEmpty() || (seenNetworks.contains(ssid) && - strength <= seenNetworks.value(ssid).strength)) { - continue; - } - SecurityType security = getSecurityType(path.path()); - ConnectedType ctype; - QString activeSsid = (activeAp != "" && activeAp != "/") ? get_property(activeAp, "Ssid") : ""; - if (ssid != activeSsid) { - ctype = ConnectedType::DISCONNECTED; - } else { - if (ssid == connecting_to_network) { - ctype = ConnectedType::CONNECTING; - } else { - ctype = ConnectedType::CONNECTED; - } - } - Network network = {ssid, strength, ctype, security}; - seenNetworks[ssid] = network; - } +void WifiManager::start() { + timer.start(5000); + refreshNetworks(); } -QString WifiManager::get_ipv4_address() { - if (raw_adapter_state != NM_DEVICE_STATE_ACTIVATED) { - return ""; +void WifiManager::stop() { + timer.stop(); +} + +void WifiManager::refreshNetworks() { + if (adapter.isEmpty() || !timer.isActive()) return; + + QDBusPendingCall pending_call = asyncCall(adapter, NM_DBUS_INTERFACE_DEVICE_WIRELESS, "GetAllAccessPoints"); + QDBusPendingCallWatcher *watcher = new QDBusPendingCallWatcher(pending_call); + QObject::connect(watcher, &QDBusPendingCallWatcher::finished, this, &WifiManager::refreshFinished); +} + +void WifiManager::refreshFinished(QDBusPendingCallWatcher *watcher) { + ipv4_address = getIp4Address(); + seenNetworks.clear(); + + const QDBusReply> wather_reply = *watcher; + for (const QDBusObjectPath &path : wather_reply.value()) { + QDBusReply replay = call(path.path(), NM_DBUS_INTERFACE_PROPERTIES, "GetAll", NM_DBUS_INTERFACE_ACCESS_POINT); + auto properties = replay.value(); + + const QByteArray ssid = properties["Ssid"].toByteArray(); + uint32_t strength = properties["Strength"].toUInt(); + if (ssid.isEmpty() || (seenNetworks.contains(ssid) && strength <= seenNetworks[ssid].strength)) continue; + + SecurityType security = getSecurityType(properties); + ConnectedType ctype = ConnectedType::DISCONNECTED; + if (path.path() == activeAp) { + ctype = (ssid == connecting_to_network) ? ConnectedType::CONNECTING : ConnectedType::CONNECTED; + } + seenNetworks[ssid] = {ssid, strength, ctype, security}; } - QVector conns = get_active_connections(); - for (auto &p : conns) { - QDBusInterface nm(NM_DBUS_SERVICE, p.path(), NM_DBUS_INTERFACE_PROPERTIES, bus); - nm.setTimeout(DBUS_TIMEOUT); - QDBusObjectPath pth = get_response(nm.call("Get", NM_DBUS_INTERFACE_ACTIVE_CONNECTION, "Ip4Config")); - QString ip4config = pth.path(); + emit refreshSignal(); + watcher->deleteLater(); +} - QString type = get_response(nm.call("Get", NM_DBUS_INTERFACE_ACTIVE_CONNECTION, "Type")); +QString WifiManager::getIp4Address() { + if (raw_adapter_state != NM_DEVICE_STATE_ACTIVATED) return ""; + for (const auto &p : getActiveConnections()) { + QString type = call(p.path(), NM_DBUS_INTERFACE_PROPERTIES, "Get", NM_DBUS_INTERFACE_ACTIVE_CONNECTION, "Type"); if (type == "802-11-wireless") { - QDBusInterface nm2(NM_DBUS_SERVICE, ip4config, NM_DBUS_INTERFACE_PROPERTIES, bus); - nm2.setTimeout(DBUS_TIMEOUT); - - const QDBusArgument &arr = get_response(nm2.call("Get", NM_DBUS_INTERFACE_IP4_CONFIG, "AddressData")); - QMap pth2; + auto ip4config = call(p.path(), NM_DBUS_INTERFACE_PROPERTIES, "Get", NM_DBUS_INTERFACE_ACTIVE_CONNECTION, "Ip4Config"); + const auto &arr = call(ip4config.path(), NM_DBUS_INTERFACE_PROPERTIES, "Get", NM_DBUS_INTERFACE_IP4_CONFIG, "AddressData"); + QVariantMap path; arr.beginArray(); while (!arr.atEnd()) { - arr >> pth2; - QString ipv4 = pth2.value("address").value(); + arr >> path; arr.endArray(); - return ipv4; + return path.value("address").value(); } arr.endArray(); } @@ -142,10 +138,10 @@ QString WifiManager::get_ipv4_address() { return ""; } -SecurityType WifiManager::getSecurityType(const QString &path) { - int sflag = get_property(path, "Flags").toInt(); - int wpaflag = get_property(path, "WpaFlags").toInt(); - int rsnflag = get_property(path, "RsnFlags").toInt(); +SecurityType WifiManager::getSecurityType(const QVariantMap &properties) { + int sflag = properties["Flags"].toUInt(); + int wpaflag = properties["WpaFlags"].toUInt(); + int rsnflag = properties["RsnFlags"].toUInt(); int wpa_props = wpaflag | rsnflag; // obtained by looking at flags of networks in the office as reported by an Android phone @@ -161,32 +157,20 @@ SecurityType WifiManager::getSecurityType(const QString &path) { } } -void WifiManager::connect(const Network &n) { - return connect(n, "", ""); -} - -void WifiManager::connect(const Network &n, const QString &password) { - return connect(n, "", password); -} - -void WifiManager::connect(const Network &n, const QString &username, const QString &password) { +void WifiManager::connect(const Network &n, const QString &password, const QString &username) { connecting_to_network = n.ssid; - // disconnect(); - forgetConnection(n.ssid); //Clear all connections that may already exist to the network we are connecting - connect(n.ssid, username, password, n.security_type); -} - -void WifiManager::connect(const QByteArray &ssid, const QString &username, const QString &password, SecurityType security_type) { + seenNetworks[n.ssid].connected = ConnectedType::CONNECTING; + forgetConnection(n.ssid); // Clear all connections that may already exist to the network we are connecting Connection connection; connection["connection"]["type"] = "802-11-wireless"; connection["connection"]["uuid"] = QUuid::createUuid().toString().remove('{').remove('}'); - connection["connection"]["id"] = "openpilot connection "+QString::fromStdString(ssid.toStdString()); + connection["connection"]["id"] = "openpilot connection " + QString::fromStdString(n.ssid.toStdString()); connection["connection"]["autoconnect-retries"] = 0; - connection["802-11-wireless"]["ssid"] = ssid; + connection["802-11-wireless"]["ssid"] = n.ssid; connection["802-11-wireless"]["mode"] = "infrastructure"; - if (security_type == SecurityType::WPA) { + if (n.security_type == SecurityType::WPA) { connection["802-11-wireless-security"]["key-mgmt"] = "wpa-psk"; connection["802-11-wireless-security"]["auth-alg"] = "open"; connection["802-11-wireless-security"]["psk"] = password; @@ -196,43 +180,30 @@ void WifiManager::connect(const QByteArray &ssid, const QString &username, const connection["ipv4"]["dns-priority"] = 600; connection["ipv6"]["method"] = "ignore"; - QDBusInterface nm_settings(NM_DBUS_SERVICE, NM_DBUS_PATH_SETTINGS, NM_DBUS_INTERFACE_SETTINGS, bus); - nm_settings.setTimeout(DBUS_TIMEOUT); - - nm_settings.call("AddConnection", QVariant::fromValue(connection)); + call(NM_DBUS_PATH_SETTINGS, NM_DBUS_INTERFACE_SETTINGS, "AddConnection", QVariant::fromValue(connection)); } void WifiManager::deactivateConnectionBySsid(const QString &ssid) { - for (QDBusObjectPath active_connection_raw : get_active_connections()) { - QString active_connection = active_connection_raw.path(); - QDBusInterface nm(NM_DBUS_SERVICE, active_connection, NM_DBUS_INTERFACE_PROPERTIES, bus); - nm.setTimeout(DBUS_TIMEOUT); - - QDBusObjectPath pth = get_response(nm.call("Get", NM_DBUS_INTERFACE_ACTIVE_CONNECTION, "SpecificObject")); + for (QDBusObjectPath active_connection : getActiveConnections()) { + auto pth = call(active_connection.path(), NM_DBUS_INTERFACE_PROPERTIES, "Get", NM_DBUS_INTERFACE_ACTIVE_CONNECTION, "SpecificObject"); if (pth.path() != "" && pth.path() != "/") { QString Ssid = get_property(pth.path(), "Ssid"); if (Ssid == ssid) { - deactivateConnection(active_connection_raw); + deactivateConnection(active_connection); + return; } } } } void WifiManager::deactivateConnection(const QDBusObjectPath &path) { - QDBusInterface nm2(NM_DBUS_SERVICE, NM_DBUS_PATH, NM_DBUS_INTERFACE, bus); - nm2.setTimeout(DBUS_TIMEOUT); - nm2.call("DeactivateConnection", QVariant::fromValue(path)); + asyncCall(NM_DBUS_PATH, NM_DBUS_INTERFACE, "DeactivateConnection", QVariant::fromValue(path)); } -QVector WifiManager::get_active_connections() { - QDBusInterface nm(NM_DBUS_SERVICE, NM_DBUS_PATH, NM_DBUS_INTERFACE_PROPERTIES, bus); - nm.setTimeout(DBUS_TIMEOUT); - - QDBusMessage response = nm.call("Get", NM_DBUS_INTERFACE, "ActiveConnections"); - const QDBusArgument &arr = get_response(response); +QVector WifiManager::getActiveConnections() { QVector conns; - QDBusObjectPath path; + const QDBusArgument &arr = call(NM_DBUS_PATH, NM_DBUS_INTERFACE_PROPERTIES, "Get", NM_DBUS_INTERFACE, "ActiveConnections"); arr.beginArray(); while (!arr.atEnd()) { arr >> path; @@ -249,57 +220,26 @@ bool WifiManager::isKnownConnection(const QString &ssid) { void WifiManager::forgetConnection(const QString &ssid) { const QDBusObjectPath &path = getConnectionPath(ssid); if (!path.path().isEmpty()) { - QDBusInterface nm2(NM_DBUS_SERVICE, path.path(), NM_DBUS_INTERFACE_SETTINGS_CONNECTION, bus); - nm2.call("Delete"); + call(path.path(), NM_DBUS_INTERFACE_SETTINGS_CONNECTION, "Delete"); } } uint WifiManager::getAdapterType(const QDBusObjectPath &path) { - QDBusInterface device_props(NM_DBUS_SERVICE, path.path(), NM_DBUS_INTERFACE_PROPERTIES, bus); - device_props.setTimeout(DBUS_TIMEOUT); - return get_response(device_props.call("Get", NM_DBUS_INTERFACE_DEVICE, "DeviceType")); -} - -bool WifiManager::isWirelessAdapter(const QDBusObjectPath &path) { - return getAdapterType(path) == NM_DEVICE_TYPE_WIFI; + return call(path.path(), NM_DBUS_INTERFACE_PROPERTIES, "Get", NM_DBUS_INTERFACE_DEVICE, "DeviceType"); } void WifiManager::requestScan() { - QDBusInterface nm(NM_DBUS_SERVICE, adapter, NM_DBUS_INTERFACE_DEVICE_WIRELESS, bus); - nm.setTimeout(DBUS_TIMEOUT); - nm.call("RequestScan", QVariantMap()); -} - -uint WifiManager::get_wifi_device_state() { - QDBusInterface device_props(NM_DBUS_SERVICE, adapter, NM_DBUS_INTERFACE_PROPERTIES, bus); - device_props.setTimeout(DBUS_TIMEOUT); - - QDBusMessage response = device_props.call("Get", NM_DBUS_INTERFACE_DEVICE, "State"); - uint resp = get_response(response); - return resp; + if (!adapter.isEmpty()) { + asyncCall(adapter, NM_DBUS_INTERFACE_DEVICE_WIRELESS, "RequestScan", QVariantMap()); + } } QByteArray WifiManager::get_property(const QString &network_path , const QString &property) { - QDBusInterface device_props(NM_DBUS_SERVICE, network_path, NM_DBUS_INTERFACE_PROPERTIES, bus); - device_props.setTimeout(DBUS_TIMEOUT); - - QDBusMessage response = device_props.call("Get", NM_DBUS_INTERFACE_ACCESS_POINT, property); - return get_response(response); -} - -unsigned int WifiManager::get_ap_strength(const QString &network_path) { - QDBusInterface device_props(NM_DBUS_SERVICE, network_path, NM_DBUS_INTERFACE_PROPERTIES, bus); - device_props.setTimeout(DBUS_TIMEOUT); - - QDBusMessage response = device_props.call("Get", NM_DBUS_INTERFACE_ACCESS_POINT, "Strength"); - return get_response(response); + return call(network_path, NM_DBUS_INTERFACE_PROPERTIES, "Get", NM_DBUS_INTERFACE_ACCESS_POINT, property); } QString WifiManager::getAdapter(const uint adapter_type) { - QDBusInterface nm(NM_DBUS_SERVICE, NM_DBUS_PATH, NM_DBUS_INTERFACE, bus); - nm.setTimeout(DBUS_TIMEOUT); - - const QDBusReply> &response = nm.call("GetDevices"); + QDBusReply> response = call(NM_DBUS_PATH, NM_DBUS_INTERFACE, "GetDevices"); for (const QDBusObjectPath &path : response.value()) { if (getAdapterType(path) == adapter_type) { return path.path(); @@ -315,29 +255,21 @@ void WifiManager::stateChange(unsigned int new_state, unsigned int previous_stat emit wrongPassword(connecting_to_network); } else if (new_state == NM_DEVICE_STATE_ACTIVATED) { connecting_to_network = ""; - if (this->isVisible()) { - refreshNetworks(); - emit refreshSignal(); - } + refreshNetworks(); } } // https://developer.gnome.org/NetworkManager/stable/gdbus-org.freedesktop.NetworkManager.Device.Wireless.html void WifiManager::propertyChange(const QString &interface, const QVariantMap &props, const QStringList &invalidated_props) { if (interface == NM_DBUS_INTERFACE_DEVICE_WIRELESS && props.contains("LastScan")) { - if (this->isVisible() || firstScan) { - refreshNetworks(); - emit refreshSignal(); - firstScan = false; - } + refreshNetworks(); } else if (interface == NM_DBUS_INTERFACE_DEVICE_WIRELESS && props.contains("ActiveAccessPoint")) { - const QDBusObjectPath &path = props.value("ActiveAccessPoint").value(); - activeAp = path.path(); + activeAp = props.value("ActiveAccessPoint").value().path(); } } void WifiManager::deviceAdded(const QDBusObjectPath &path) { - if (isWirelessAdapter(path) && (adapter.isEmpty() || adapter == "/")) { + if (getAdapterType(path) == NM_DEVICE_TYPE_WIFI && (adapter.isEmpty() || adapter == "/")) { adapter = path.path(); setup(); } @@ -348,7 +280,7 @@ void WifiManager::connectionRemoved(const QDBusObjectPath &path) { } void WifiManager::newConnection(const QDBusObjectPath &path) { - const Connection &settings = getConnectionSettings(path); + Connection settings = getConnectionSettings(path); if (settings.value("connection").value("type") == "802-11-wireless") { knownConnections[path] = settings.value("802-11-wireless").value("ssid").toString(); if (knownConnections[path] != tethering_ssid) { @@ -357,34 +289,18 @@ void WifiManager::newConnection(const QDBusObjectPath &path) { } } -void WifiManager::disconnect() { - if (activeAp != "" && activeAp != "/") { - deactivateConnectionBySsid(get_property(activeAp, "Ssid")); - } -} - QDBusObjectPath WifiManager::getConnectionPath(const QString &ssid) { - for (const QString &conn_ssid : knownConnections) { - if (ssid == conn_ssid) { - return knownConnections.key(conn_ssid); - } - } - return QDBusObjectPath(); + return knownConnections.key(ssid); } Connection WifiManager::getConnectionSettings(const QDBusObjectPath &path) { - QDBusInterface nm(NM_DBUS_SERVICE, path.path(), NM_DBUS_INTERFACE_SETTINGS_CONNECTION, bus); - nm.setTimeout(DBUS_TIMEOUT); - return QDBusReply(nm.call("GetSettings")).value(); + return QDBusReply(call(path.path(), NM_DBUS_INTERFACE_SETTINGS_CONNECTION, "GetSettings")).value(); } void WifiManager::initConnections() { - QDBusInterface nm(NM_DBUS_SERVICE, NM_DBUS_PATH_SETTINGS, NM_DBUS_INTERFACE_SETTINGS, bus); - nm.setTimeout(DBUS_TIMEOUT); - - const QDBusReply> response = nm.call("ListConnections"); + const QDBusReply> response = call(NM_DBUS_PATH_SETTINGS, NM_DBUS_INTERFACE_SETTINGS, "ListConnections"); for (const QDBusObjectPath &path : response.value()) { - const Connection &settings = getConnectionSettings(path); + const Connection settings = getConnectionSettings(path); if (settings.value("connection").value("type") == "802-11-wireless") { knownConnections[path] = settings.value("802-11-wireless").value("ssid").toString(); } else if (path.path() != "/") { @@ -393,44 +309,34 @@ void WifiManager::initConnections() { } } -void WifiManager::activateWifiConnection(const QString &ssid) { +std::optional WifiManager::activateWifiConnection(const QString &ssid) { const QDBusObjectPath &path = getConnectionPath(ssid); if (!path.path().isEmpty()) { connecting_to_network = ssid; - QDBusInterface nm3(NM_DBUS_SERVICE, NM_DBUS_PATH, NM_DBUS_INTERFACE, bus); - nm3.setTimeout(DBUS_TIMEOUT); - nm3.call("ActivateConnection", QVariant::fromValue(path), QVariant::fromValue(QDBusObjectPath(adapter)), QVariant::fromValue(QDBusObjectPath("/"))); + return asyncCall(NM_DBUS_PATH, NM_DBUS_INTERFACE, "ActivateConnection", QVariant::fromValue(path), QVariant::fromValue(QDBusObjectPath(adapter)), QVariant::fromValue(QDBusObjectPath("/"))); } + return std::nullopt; } void WifiManager::activateModemConnection(const QDBusObjectPath &path) { QString modem = getAdapter(NM_DEVICE_TYPE_MODEM); if (!path.path().isEmpty() && !modem.isEmpty()) { - QDBusInterface nm3(NM_DBUS_SERVICE, NM_DBUS_PATH, NM_DBUS_INTERFACE, bus); - nm3.setTimeout(DBUS_TIMEOUT); - nm3.call("ActivateConnection", QVariant::fromValue(path), QVariant::fromValue(QDBusObjectPath(modem)), QVariant::fromValue(QDBusObjectPath("/"))); + asyncCall(NM_DBUS_PATH, NM_DBUS_INTERFACE, "ActivateConnection", QVariant::fromValue(path), QVariant::fromValue(QDBusObjectPath(modem)), QVariant::fromValue(QDBusObjectPath("/"))); } } // function matches tici/hardware.py NetworkType WifiManager::currentNetworkType() { - QDBusInterface nm(NM_DBUS_SERVICE, NM_DBUS_PATH, NM_DBUS_INTERFACE_PROPERTIES, bus); - nm.setTimeout(DBUS_TIMEOUT); - const QDBusObjectPath &primary_conn = get_response(nm.call("Get", NM_DBUS_INTERFACE, "PrimaryConnection")); - - QDBusInterface nm2(NM_DBUS_SERVICE, primary_conn.path(), NM_DBUS_INTERFACE_PROPERTIES, bus); - nm.setTimeout(DBUS_TIMEOUT); - const QString &primary_type = get_response(nm2.call("Get", NM_DBUS_INTERFACE_ACTIVE_CONNECTION, "Type")); + auto primary_conn = call(NM_DBUS_PATH, NM_DBUS_INTERFACE_PROPERTIES, "Get", NM_DBUS_INTERFACE, "PrimaryConnection"); + auto primary_type = call(primary_conn.path(), NM_DBUS_INTERFACE_PROPERTIES, "Get", NM_DBUS_INTERFACE_ACTIVE_CONNECTION, "Type"); if (primary_type == "802-3-ethernet") { return NetworkType::ETHERNET; } else if (primary_type == "802-11-wireless" && !isTetheringEnabled()) { return NetworkType::WIFI; } else { - for (const QDBusObjectPath &conn : get_active_connections()) { - QDBusInterface nm3(NM_DBUS_SERVICE, conn.path(), NM_DBUS_INTERFACE_PROPERTIES, bus); - nm3.setTimeout(DBUS_TIMEOUT); - const QString &type = get_response(nm3.call("Get", NM_DBUS_INTERFACE_ACTIVE_CONNECTION, "Type")); + for (const QDBusObjectPath &conn : getActiveConnections()) { + auto type = call(conn.path(), NM_DBUS_INTERFACE_PROPERTIES, "Get", NM_DBUS_INTERFACE_ACTIVE_CONNECTION, "Type"); if (type == "gsm") { return NetworkType::CELL; } @@ -441,13 +347,9 @@ NetworkType WifiManager::currentNetworkType() { void WifiManager::updateGsmSettings(bool roaming, QString apn) { if (!lteConnectionPath.path().isEmpty()) { - QDBusInterface nm(NM_DBUS_SERVICE, lteConnectionPath.path(), NM_DBUS_INTERFACE_SETTINGS_CONNECTION, bus); - nm.setTimeout(DBUS_TIMEOUT); - bool changes = false; bool auto_config = apn.isEmpty(); - Connection settings = QDBusReply(nm.call("GetSettings")).value(); - + Connection settings = getConnectionSettings(lteConnectionPath); if (settings.value("gsm").value("auto-config").toBool() != auto_config) { qWarning() << "Changing gsm.auto-config to" << auto_config; settings["gsm"]["auto-config"] = auto_config; @@ -467,7 +369,7 @@ void WifiManager::updateGsmSettings(bool roaming, QString apn) { } if (changes) { - nm.call("UpdateUnsaved", QVariant::fromValue(settings)); // update is temporary + call(lteConnectionPath.path(), NM_DBUS_INTERFACE_SETTINGS_CONNECTION, "UpdateUnsaved", QVariant::fromValue(settings)); // update is temporary deactivateConnection(lteConnectionPath); activateModemConnection(lteConnectionPath); } @@ -494,7 +396,7 @@ void WifiManager::addTetheringConnection() { connection["802-11-wireless-security"]["psk"] = defaultTetheringPassword; connection["ipv4"]["method"] = "shared"; - QMap address; + QVariantMap address; address["address"] = "192.168.43.1"; address["prefix"] = 24u; connection["ipv4"]["address-data"] = QVariant::fromValue(IpConfig() << address); @@ -502,9 +404,20 @@ void WifiManager::addTetheringConnection() { connection["ipv4"]["route-metric"] = 1100; connection["ipv6"]["method"] = "ignore"; - QDBusInterface nm_settings(NM_DBUS_SERVICE, NM_DBUS_PATH_SETTINGS, NM_DBUS_INTERFACE_SETTINGS, bus); - nm_settings.setTimeout(DBUS_TIMEOUT); - nm_settings.call("AddConnection", QVariant::fromValue(connection)); + call(NM_DBUS_PATH_SETTINGS, NM_DBUS_INTERFACE_SETTINGS, "AddConnection", QVariant::fromValue(connection)); +} + +void WifiManager::tetheringActivated(QDBusPendingCallWatcher *call) { + int prime_type = uiState()->prime_type; + int ipv4_forward = (prime_type == PrimeType::NONE || prime_type == PrimeType::LITE); + + if (!ipv4_forward) { + QTimer::singleShot(5000, this, [=] { + qWarning() << "net.ipv4.ip_forward = 0"; + std::system("sudo sysctl net.ipv4.ip_forward=0"); + }); + } + call->deleteLater(); } void WifiManager::setTetheringEnabled(bool enabled) { @@ -512,21 +425,19 @@ void WifiManager::setTetheringEnabled(bool enabled) { if (!isKnownConnection(tethering_ssid)) { addTetheringConnection(); } - activateWifiConnection(tethering_ssid); + + auto pending_call = activateWifiConnection(tethering_ssid); + + if (pending_call) { + QDBusPendingCallWatcher *watcher = new QDBusPendingCallWatcher(*pending_call); + QObject::connect(watcher, &QDBusPendingCallWatcher::finished, this, &WifiManager::tetheringActivated); + } + } else { deactivateConnectionBySsid(tethering_ssid); } } -void WifiManager::initActiveAp() { - QDBusInterface device_props(NM_DBUS_SERVICE, adapter, NM_DBUS_INTERFACE_PROPERTIES, bus); - device_props.setTimeout(DBUS_TIMEOUT); - - const QDBusMessage &response = device_props.call("Get", NM_DBUS_INTERFACE_DEVICE_WIRELESS, "ActiveAccessPoint"); - activeAp = get_response(response).path(); -} - - bool WifiManager::isTetheringEnabled() { if (activeAp != "" && activeAp != "/") { return get_property(activeAp, "Ssid") == tethering_ssid; @@ -540,10 +451,7 @@ QString WifiManager::getTetheringPassword() { } const QDBusObjectPath &path = getConnectionPath(tethering_ssid); if (!path.path().isEmpty()) { - QDBusInterface nm(NM_DBUS_INTERFACE, path.path(), NM_DBUS_INTERFACE_SETTINGS_CONNECTION, bus); - nm.setTimeout(DBUS_TIMEOUT); - - const QDBusReply>> response = nm.call("GetSecrets", "802-11-wireless-security"); + QDBusReply> response = call(path.path(), NM_DBUS_INTERFACE_SETTINGS_CONNECTION, "GetSecrets", "802-11-wireless-security"); return response.value().value("802-11-wireless-security").value("psk").toString(); } return ""; @@ -552,13 +460,9 @@ QString WifiManager::getTetheringPassword() { void WifiManager::changeTetheringPassword(const QString &newPassword) { const QDBusObjectPath &path = getConnectionPath(tethering_ssid); if (!path.path().isEmpty()) { - QDBusInterface nm(NM_DBUS_INTERFACE, path.path(), NM_DBUS_INTERFACE_SETTINGS_CONNECTION, bus); - nm.setTimeout(DBUS_TIMEOUT); - - Connection settings = QDBusReply(nm.call("GetSettings")).value(); + Connection settings = getConnectionSettings(path); settings["802-11-wireless-security"]["psk"] = newPassword; - nm.call("Update", QVariant::fromValue(settings)); - + call(path.path(), NM_DBUS_INTERFACE_SETTINGS_CONNECTION, "Update", QVariant::fromValue(settings)); if (isTetheringEnabled()) { activateWifiConnection(tethering_ssid); } diff --git a/selfdrive/ui/qt/offroad/wifiManager.h b/selfdrive/ui/qt/offroad/wifiManager.h index 04defd32d..07b982c2c 100644 --- a/selfdrive/ui/qt/offroad/wifiManager.h +++ b/selfdrive/ui/qt/offroad/wifiManager.h @@ -1,7 +1,8 @@ #pragma once +#include #include -#include +#include #include "selfdrive/ui/qt/offroad/networkmanager.h" @@ -22,8 +23,8 @@ enum class NetworkType { ETHERNET }; -typedef QMap> Connection; -typedef QVector> IpConfig; +typedef QMap Connection; +typedef QVector IpConfig; struct Network { QByteArray ssid; @@ -33,65 +34,58 @@ struct Network { }; bool compare_by_strength(const Network &a, const Network &b); -class WifiManager : public QWidget { +class WifiManager : public QObject { Q_OBJECT public: - explicit WifiManager(QWidget* parent); - - void requestScan(); QMap seenNetworks; QMap knownConnections; - QDBusObjectPath lteConnectionPath; QString ipv4_address; - void refreshNetworks(); + explicit WifiManager(QObject* parent); + void start(); + void stop(); + void requestScan(); void forgetConnection(const QString &ssid); bool isKnownConnection(const QString &ssid); - void activateWifiConnection(const QString &ssid); - void activateModemConnection(const QDBusObjectPath &path); + std::optional activateWifiConnection(const QString &ssid); NetworkType currentNetworkType(); void updateGsmSettings(bool roaming, QString apn); - - void connect(const Network &ssid); - void connect(const Network &ssid, const QString &password); - void connect(const Network &ssid, const QString &username, const QString &password); - void disconnect(); + void connect(const Network &ssid, const QString &password = {}, const QString &username = {}); // Tethering functions void setTetheringEnabled(bool enabled); bool isTetheringEnabled(); - void addTetheringConnection(); void changeTetheringPassword(const QString &newPassword); QString getTetheringPassword(); private: QString adapter; // Path to network manager wifi-device - QDBusConnection bus = QDBusConnection::systemBus(); + QTimer timer; unsigned int raw_adapter_state; // Connection status https://developer.gnome.org/NetworkManager/1.26/nm-dbus-types.html#NMDeviceState QString connecting_to_network; QString tethering_ssid; const QString defaultTetheringPassword = "swagswagcomma"; + QString activeAp; + QDBusObjectPath lteConnectionPath; - bool firstScan = true; QString getAdapter(const uint = NM_DEVICE_TYPE_WIFI); uint getAdapterType(const QDBusObjectPath &path); bool isWirelessAdapter(const QDBusObjectPath &path); - QString get_ipv4_address(); + QString getIp4Address(); void connect(const QByteArray &ssid, const QString &username, const QString &password, SecurityType security_type); - QString activeAp; - void initActiveAp(); void deactivateConnectionBySsid(const QString &ssid); void deactivateConnection(const QDBusObjectPath &path); - QVector get_active_connections(); - uint get_wifi_device_state(); + QVector getActiveConnections(); QByteArray get_property(const QString &network_path, const QString &property); - unsigned int get_ap_strength(const QString &network_path); - SecurityType getSecurityType(const QString &path); + SecurityType getSecurityType(const QVariantMap &properties); QDBusObjectPath getConnectionPath(const QString &ssid); Connection getConnectionSettings(const QDBusObjectPath &path); void initConnections(); void setup(); + void refreshNetworks(); + void activateModemConnection(const QDBusObjectPath &path); + void addTetheringConnection(); signals: void wrongPassword(const QString &ssid); @@ -103,4 +97,6 @@ private slots: void deviceAdded(const QDBusObjectPath &path); void connectionRemoved(const QDBusObjectPath &path); void newConnection(const QDBusObjectPath &path); + void refreshFinished(QDBusPendingCallWatcher *call); + void tetheringActivated(QDBusPendingCallWatcher *call); }; diff --git a/selfdrive/ui/qt/onroad.cc b/selfdrive/ui/qt/onroad.cc index 53cc96367..44dde8581 100644 --- a/selfdrive/ui/qt/onroad.cc +++ b/selfdrive/ui/qt/onroad.cc @@ -41,8 +41,8 @@ OnroadWindow::OnroadWindow(QWidget *parent) : QWidget(parent) { alerts->raise(); setAttribute(Qt::WA_OpaquePaintEvent); - QObject::connect(this, &OnroadWindow::updateStateSignal, this, &OnroadWindow::updateState); - QObject::connect(this, &OnroadWindow::offroadTransitionSignal, this, &OnroadWindow::offroadTransition); + QObject::connect(uiState(), &UIState::uiUpdate, this, &OnroadWindow::updateState); + QObject::connect(uiState(), &UIState::offroadTransition, this, &OnroadWindow::offroadTransition); } void OnroadWindow::updateState(const UIState &s) { @@ -51,6 +51,8 @@ void OnroadWindow::updateState(const UIState &s) { if (s.sm->updated("controlsState") || !alert.equal({})) { if (alert.type == "controlsUnresponsive") { bgColor = bg_colors[STATUS_ALERT]; + } else if (alert.type == "controlsUnresponsivePermanent") { + bgColor = bg_colors[STATUS_DISENGAGED]; } alerts->updateAlert(alert, bgColor); } @@ -76,12 +78,17 @@ void OnroadWindow::mousePressEvent(QMouseEvent* e) { void OnroadWindow::offroadTransition(bool offroad) { #ifdef ENABLE_MAPS if (!offroad) { - if (map == nullptr && (QUIState::ui_state.has_prime || !MAPBOX_TOKEN.isEmpty())) { + if (map == nullptr && (uiState()->prime_type || !MAPBOX_TOKEN.isEmpty())) { MapWindow * m = new MapWindow(get_mapbox_settings()); - m->setFixedWidth(topWidget(this)->width() / 2); - QObject::connect(this, &OnroadWindow::offroadTransitionSignal, m, &MapWindow::offroadTransition); - split->addWidget(m, 0, Qt::AlignRight); map = m; + + QObject::connect(uiState(), &UIState::offroadTransition, m, &MapWindow::offroadTransition); + + m->setFixedWidth(topWidget(this)->width() / 2); + split->addWidget(m, 0, Qt::AlignRight); + + // Make map visible after adding to split + m->offroadTransition(offroad); } } #endif @@ -162,8 +169,8 @@ void OnroadAlerts::paintEvent(QPaintEvent *event) { // OnroadHud OnroadHud::OnroadHud(QWidget *parent) : QWidget(parent) { - engage_img = QPixmap("../assets/img_chffr_wheel.png").scaled(img_size, img_size, Qt::KeepAspectRatio, Qt::SmoothTransformation); - dm_img = QPixmap("../assets/img_driver_face.png").scaled(img_size, img_size, Qt::KeepAspectRatio, Qt::SmoothTransformation); + engage_img = loadPixmap("../assets/img_chffr_wheel.png", {img_size, img_size}); + dm_img = loadPixmap("../assets/img_driver_face.png", {img_size, img_size}); connect(this, &OnroadHud::valueChanged, [=] { update(); }); } @@ -274,7 +281,7 @@ void NvgWindow::initializeGL() { void NvgWindow::updateFrameMat(int w, int h) { CameraViewWidget::updateFrameMat(w, h); - UIState *s = &QUIState::ui_state; + UIState *s = uiState(); s->fb_w = w; s->fb_h = h; auto intrinsic_matrix = s->wide_camera ? ecam_intrinsic_matrix : fcam_intrinsic_matrix; @@ -335,7 +342,7 @@ void NvgWindow::drawLead(QPainter &painter, const cereal::ModelDataV2::LeadDataV float g_xo = sz / 5; float g_yo = sz / 10; - QPointF glow[] = {{x + (sz * 1.35) + g_xo, y + sz + g_yo}, {x, y - g_xo}, {x - (sz * 1.35) - g_xo, y + sz + g_yo}}; + QPointF glow[] = {{x + (sz * 1.35) + g_xo, y + sz + g_yo}, {x, y - g_yo}, {x - (sz * 1.35) - g_xo, y + sz + g_yo}}; painter.setBrush(QColor(218, 202, 37, 255)); painter.drawPolygon(glow, std::size(glow)); @@ -348,8 +355,8 @@ void NvgWindow::drawLead(QPainter &painter, const cereal::ModelDataV2::LeadDataV void NvgWindow::paintGL() { CameraViewWidget::paintGL(); - UIState *s = &QUIState::ui_state; - if (s->scene.world_objects_visible) { + UIState *s = uiState(); + if (s->worldObjectsVisible()) { QPainter painter(this); painter.setRenderHint(QPainter::Antialiasing); painter.setPen(Qt::NoPen); @@ -379,6 +386,6 @@ void NvgWindow::paintGL() { void NvgWindow::showEvent(QShowEvent *event) { CameraViewWidget::showEvent(event); - ui_update_params(&QUIState::ui_state); + ui_update_params(uiState()); prev_draw_t = millis_since_boot(); } diff --git a/selfdrive/ui/qt/onroad.h b/selfdrive/ui/qt/onroad.h index 37460c8ba..05811c506 100644 --- a/selfdrive/ui/qt/onroad.h +++ b/selfdrive/ui/qt/onroad.h @@ -97,10 +97,6 @@ private: QWidget *map = nullptr; QHBoxLayout* split; -signals: - void updateStateSignal(const UIState &s); - void offroadTransitionSignal(bool offroad); - private slots: void offroadTransition(bool offroad); void updateState(const UIState &s); diff --git a/selfdrive/ui/qt/request_repeater.cc b/selfdrive/ui/qt/request_repeater.cc index d2c0f9bc3..7ef1c833a 100644 --- a/selfdrive/ui/qt/request_repeater.cc +++ b/selfdrive/ui/qt/request_repeater.cc @@ -5,7 +5,7 @@ RequestRepeater::RequestRepeater(QObject *parent, const QString &requestURL, con timer = new QTimer(this); timer->setTimerType(Qt::VeryCoarseTimer); QObject::connect(timer, &QTimer::timeout, [=]() { - if ((!QUIState::ui_state.scene.started || while_onroad) && QUIState::ui_state.awake && !active()) { + if ((!uiState()->scene.started || while_onroad) && uiState()->awake && !active()) { sendRequest(requestURL); } }); diff --git a/selfdrive/ui/qt/sidebar.cc b/selfdrive/ui/qt/sidebar.cc index 73c4e2f8c..cdff1fce8 100644 --- a/selfdrive/ui/qt/sidebar.cc +++ b/selfdrive/ui/qt/sidebar.cc @@ -26,14 +26,16 @@ void Sidebar::drawMetric(QPainter &p, const QString &label, QColor c, int y) { } Sidebar::Sidebar(QWidget *parent) : QFrame(parent) { - home_img = QImage("../assets/images/button_home.png").scaled(180, 180, Qt::KeepAspectRatio, Qt::SmoothTransformation); - settings_img = QImage("../assets/images/button_settings.png").scaled(settings_btn.width(), settings_btn.height(), Qt::IgnoreAspectRatio, Qt::SmoothTransformation); + home_img = loadPixmap("../assets/images/button_home.png", {180, 180}); + settings_img = loadPixmap("../assets/images/button_settings.png", settings_btn.size(), Qt::IgnoreAspectRatio); connect(this, &Sidebar::valueChanged, [=] { update(); }); setAttribute(Qt::WA_OpaquePaintEvent); setSizePolicy(QSizePolicy::Fixed, QSizePolicy::Expanding); setFixedWidth(300); + + QObject::connect(uiState(), &UIState::uiUpdate, this, &Sidebar::updateState); } void Sidebar::mouseReleaseEvent(QMouseEvent *event) { @@ -88,9 +90,9 @@ void Sidebar::paintEvent(QPaintEvent *event) { // static imgs p.setOpacity(0.65); - p.drawImage(settings_btn.x(), settings_btn.y(), settings_img); + p.drawPixmap(settings_btn.x(), settings_btn.y(), settings_img); p.setOpacity(1.0); - p.drawImage(60, 1080 - 180 - 40, home_img); + p.drawPixmap(60, 1080 - 180 - 40, home_img); // network int x = 58; diff --git a/selfdrive/ui/qt/sidebar.h b/selfdrive/ui/qt/sidebar.h index 6cea9bdb6..5d1b92175 100644 --- a/selfdrive/ui/qt/sidebar.h +++ b/selfdrive/ui/qt/sidebar.h @@ -32,7 +32,7 @@ protected: void mouseReleaseEvent(QMouseEvent *event) override; void drawMetric(QPainter &p, const QString &label, QColor c, int y); - QImage home_img, settings_img; + QPixmap home_img, settings_img; const QMap network_type = { {cereal::DeviceState::NetworkType::NONE, "--"}, {cereal::DeviceState::NetworkType::WIFI, "Wi-Fi"}, diff --git a/selfdrive/ui/qt/spinner.cc b/selfdrive/ui/qt/spinner.cc index 8948d2adb..b9868f603 100644 --- a/selfdrive/ui/qt/spinner.cc +++ b/selfdrive/ui/qt/spinner.cc @@ -19,8 +19,8 @@ TrackWidget::TrackWidget(QWidget *parent) : QWidget(parent) { setFixedSize(spinner_size); // pre-compute all the track imgs. make this a gif instead? - QPixmap comma_img = QPixmap("../assets/img_spinner_comma.png").scaled(spinner_size, Qt::KeepAspectRatio, Qt::SmoothTransformation); - QPixmap track_img = QPixmap("../assets/img_spinner_track.png").scaled(spinner_size, Qt::KeepAspectRatio, Qt::SmoothTransformation); + QPixmap comma_img = loadPixmap("../assets/img_spinner_comma.png", spinner_size); + QPixmap track_img = loadPixmap("../assets/img_spinner_track.png", spinner_size); QTransform transform(1, 0, 0, 1, width() / 2, height() / 2); QPixmap pm(spinner_size); diff --git a/selfdrive/ui/qt/util.cc b/selfdrive/ui/qt/util.cc index b1defb008..16d5c174b 100644 --- a/selfdrive/ui/qt/util.cc +++ b/selfdrive/ui/qt/util.cc @@ -98,21 +98,6 @@ void initApp() { } } -ClickableWidget::ClickableWidget(QWidget *parent) : QWidget(parent) { } - -void ClickableWidget::mouseReleaseEvent(QMouseEvent *event) { - emit clicked(); -} - -// Fix stylesheets -void ClickableWidget::paintEvent(QPaintEvent *) { - QStyleOption opt; - opt.init(this); - QPainter p(this); - style()->drawPrimitive(QStyle::PE_Widget, &opt, &p, this); -} - - void swagLogMessageHandler(QtMsgType type, const QMessageLogContext &context, const QString &msg) { static std::map levels = { {QtMsgType::QtDebugMsg, CLOUDLOG_DEBUG}, @@ -136,3 +121,11 @@ QWidget* topWidget (QWidget* widget) { while (widget->parentWidget() != nullptr) widget=widget->parentWidget(); return widget; } + +QPixmap loadPixmap(const QString &fileName, const QSize &size, Qt::AspectRatioMode aspectRatioMode) { + if (size.isEmpty()) { + return QPixmap(fileName); + } else { + return QPixmap(fileName).scaled(size, aspectRatioMode, Qt::SmoothTransformation); + } +} diff --git a/selfdrive/ui/qt/util.h b/selfdrive/ui/qt/util.h index 588dac704..1b9461fab 100644 --- a/selfdrive/ui/qt/util.h +++ b/selfdrive/ui/qt/util.h @@ -4,8 +4,8 @@ #include #include -#include #include +#include #include #include @@ -21,28 +21,4 @@ QString timeAgo(const QDateTime &date); void swagLogMessageHandler(QtMsgType type, const QMessageLogContext &context, const QString &msg); void initApp(); QWidget* topWidget (QWidget* widget); - - -// convenience class for wrapping layouts -class LayoutWidget : public QWidget { - Q_OBJECT - -public: - LayoutWidget(QLayout *l, QWidget *parent = nullptr) : QWidget(parent) { - setLayout(l); - }; -}; - -class ClickableWidget : public QWidget { - Q_OBJECT - -public: - ClickableWidget(QWidget *parent = nullptr); - -protected: - void mouseReleaseEvent(QMouseEvent *event) override; - void paintEvent(QPaintEvent *) override; - -signals: - void clicked(); -}; +QPixmap loadPixmap(const QString &fileName, const QSize &size = {}, Qt::AspectRatioMode aspectRatioMode = Qt::KeepAspectRatio); diff --git a/selfdrive/ui/qt/widgets/cameraview.cc b/selfdrive/ui/qt/widgets/cameraview.cc index a238f13c8..fbd425b02 100644 --- a/selfdrive/ui/qt/widgets/cameraview.cc +++ b/selfdrive/ui/qt/widgets/cameraview.cc @@ -31,8 +31,8 @@ const char frame_fragment_shader[] = "#version 150 core\n" #else "#version 300 es\n" -#endif "precision mediump float;\n" +#endif "uniform sampler2D uTexture;\n" "in vec4 vTexCoord;\n" "out vec4 colorOut;\n" @@ -199,13 +199,18 @@ void CameraViewWidget::updateFrameMat(int w, int h) { } void CameraViewWidget::paintGL() { - if (latest_texture_id == -1) { - glClearColor(bg.redF(), bg.greenF(), bg.blueF(), bg.alphaF()); - glClear(GL_STENCIL_BUFFER_BIT | GL_COLOR_BUFFER_BIT); - return; - } + glClearColor(bg.redF(), bg.greenF(), bg.blueF(), bg.alphaF()); + glClear(GL_STENCIL_BUFFER_BIT | GL_COLOR_BUFFER_BIT); + + std::lock_guard lk(lock); + + if (latest_texture_id == -1) return; glViewport(0, 0, width(), height()); + // sync with the PBO + if (wait_fence) { + wait_fence->wait(); + } glBindVertexArray(frame_vao); glActiveTexture(GL_TEXTURE0); @@ -290,20 +295,33 @@ void CameraViewWidget::vipcThread() { } if (VisionBuf *buf = vipc_client->recv(nullptr, 1000)) { - if (!Hardware::EON()) { - void *texture_buffer = gl_buffer->map(QOpenGLBuffer::WriteOnly); - memcpy(texture_buffer, buf->addr, buf->len); - gl_buffer->unmap(); + { + std::lock_guard lk(lock); + if (!Hardware::EON()) { + void *texture_buffer = gl_buffer->map(QOpenGLBuffer::WriteOnly); - // copy pixels from PBO to texture object - glBindTexture(GL_TEXTURE_2D, texture[buf->idx]->frame_tex); - glTexSubImage2D(GL_TEXTURE_2D, 0, 0, 0, buf->width, buf->height, GL_RGB, GL_UNSIGNED_BYTE, 0); - glBindTexture(GL_TEXTURE_2D, 0); - assert(glGetError() == GL_NO_ERROR); - // use glFinish to ensure that the texture has been uploaded. - glFinish(); + if (texture_buffer == nullptr) { + LOGE("gl_buffer->map returned nullptr"); + continue; + } + + memcpy(texture_buffer, buf->addr, buf->len); + gl_buffer->unmap(); + + // copy pixels from PBO to texture object + glBindTexture(GL_TEXTURE_2D, texture[buf->idx]->frame_tex); + glTexSubImage2D(GL_TEXTURE_2D, 0, 0, 0, buf->width, buf->height, GL_RGB, GL_UNSIGNED_BYTE, 0); + glBindTexture(GL_TEXTURE_2D, 0); + assert(glGetError() == GL_NO_ERROR); + + wait_fence.reset(new WaitFence()); + + // Ensure the fence is in the GPU command queue, or waiting on it might block + // https://www.khronos.org/opengl/wiki/Sync_Object#Flushing_and_contexts + glFlush(); + } + latest_texture_id = buf->idx; } - latest_texture_id = buf->idx; // Schedule update. update() will be invoked on the gui thread. QMetaObject::invokeMethod(this, "update"); diff --git a/selfdrive/ui/qt/widgets/cameraview.h b/selfdrive/ui/qt/widgets/cameraview.h index 4cfba3c6f..03709cbdd 100644 --- a/selfdrive/ui/qt/widgets/cameraview.h +++ b/selfdrive/ui/qt/widgets/cameraview.h @@ -36,11 +36,20 @@ protected: virtual void updateFrameMat(int w, int h); void vipcThread(); + struct WaitFence { + WaitFence() { sync = glFenceSync(GL_SYNC_GPU_COMMANDS_COMPLETE, 0); } + ~WaitFence() { glDeleteSync(sync); } + void wait() { glWaitSync(sync, 0, GL_TIMEOUT_IGNORED); } + GLsync sync = 0; + }; + bool zoomed_view; - std::atomic latest_texture_id = -1; + std::mutex lock; + int latest_texture_id = -1; GLuint frame_vao, frame_vbo, frame_ibo; mat4 frame_mat; std::unique_ptr texture[UI_BUF_COUNT]; + std::unique_ptr wait_fence; std::unique_ptr program; QColor bg = QColor("#000000"); @@ -50,7 +59,6 @@ protected: std::atomic stream_type; QThread *vipc_thread = nullptr; - protected slots: void vipcConnected(VisionIpcClient *vipc_client); }; diff --git a/selfdrive/ui/qt/widgets/controls.cc b/selfdrive/ui/qt/widgets/controls.cc index 8b09ba2bb..89c95843f 100644 --- a/selfdrive/ui/qt/widgets/controls.cc +++ b/selfdrive/ui/qt/widgets/controls.cc @@ -19,7 +19,7 @@ QFrame *horizontal_line(QWidget *parent) { AbstractControl::AbstractControl(const QString &title, const QString &desc, const QString &icon, QWidget *parent) : QFrame(parent) { setSizePolicy(QSizePolicy::Preferred, QSizePolicy::Minimum); - + QVBoxLayout *main_layout = new QVBoxLayout(this); main_layout->setMargin(0); @@ -121,3 +121,17 @@ void ElidedLabel::paintEvent(QPaintEvent *event) { opt.initFrom(this); style()->drawItemText(&painter, contentsRect(), alignment(), opt.palette, isEnabled(), elidedText_, foregroundRole()); } + +ClickableWidget::ClickableWidget(QWidget *parent) : QWidget(parent) { } + +void ClickableWidget::mouseReleaseEvent(QMouseEvent *event) { + emit clicked(); +} + +// Fix stylesheets +void ClickableWidget::paintEvent(QPaintEvent *) { + QStyleOption opt; + opt.init(this); + QPainter p(this); + style()->drawPrimitive(QStyle::PE_Widget, &opt, &p, this); +} diff --git a/selfdrive/ui/qt/widgets/controls.h b/selfdrive/ui/qt/widgets/controls.h index b79332605..13cd55ff3 100644 --- a/selfdrive/ui/qt/widgets/controls.h +++ b/selfdrive/ui/qt/widgets/controls.h @@ -161,3 +161,27 @@ private: QVBoxLayout outer_layout; QVBoxLayout inner_layout; }; + +// convenience class for wrapping layouts +class LayoutWidget : public QWidget { + Q_OBJECT + +public: + LayoutWidget(QLayout *l, QWidget *parent = nullptr) : QWidget(parent) { + setLayout(l); + }; +}; + +class ClickableWidget : public QWidget { + Q_OBJECT + +public: + ClickableWidget(QWidget *parent = nullptr); + +protected: + void mouseReleaseEvent(QMouseEvent *event) override; + void paintEvent(QPaintEvent *) override; + +signals: + void clicked(); +}; diff --git a/selfdrive/ui/qt/widgets/prime.cc b/selfdrive/ui/qt/widgets/prime.cc index ab6dc67d3..27d472535 100644 --- a/selfdrive/ui/qt/widgets/prime.cc +++ b/selfdrive/ui/qt/widgets/prime.cc @@ -307,19 +307,19 @@ void SetupWidget::replyFinished(const QString &response, bool success) { } QJsonObject json = doc.object(); + int prime_type = json["prime_type"].toInt(); + + if (uiState()->prime_type != prime_type) { + uiState()->prime_type = prime_type; + Params().put("PrimeType", std::to_string(prime_type)); + } + if (!json["is_paired"].toBool()) { mainLayout->setCurrentIndex(0); } else { popup->reject(); - bool prime = json["prime"].toBool(); - - if (QUIState::ui_state.has_prime != prime) { - QUIState::ui_state.has_prime = prime; - Params().putBool("HasPrime", prime); - } - - if (prime) { + if (prime_type) { mainLayout->setCurrentWidget(primeUser); } else { mainLayout->setCurrentWidget(primeAd); diff --git a/selfdrive/ui/qt/widgets/prime.h b/selfdrive/ui/qt/widgets/prime.h index f7470fe44..566238fc3 100644 --- a/selfdrive/ui/qt/widgets/prime.h +++ b/selfdrive/ui/qt/widgets/prime.h @@ -7,6 +7,12 @@ #include "selfdrive/ui/qt/widgets/input.h" +enum PrimeType { + NONE = 0, + MAGENTA, + LITE, +}; + // pairing QR code class PairingQRWidget : public QWidget { Q_OBJECT diff --git a/selfdrive/ui/qt/window.cc b/selfdrive/ui/qt/window.cc index 7fe87ce69..76d5a39d4 100644 --- a/selfdrive/ui/qt/window.cc +++ b/selfdrive/ui/qt/window.cc @@ -12,14 +12,10 @@ MainWindow::MainWindow(QWidget *parent) : QWidget(parent) { main_layout->addWidget(homeWindow); QObject::connect(homeWindow, &HomeWindow::openSettings, this, &MainWindow::openSettings); QObject::connect(homeWindow, &HomeWindow::closeSettings, this, &MainWindow::closeSettings); - QObject::connect(&qs, &QUIState::uiUpdate, homeWindow, &HomeWindow::update); - QObject::connect(&qs, &QUIState::offroadTransition, homeWindow, &HomeWindow::offroadTransition); - QObject::connect(&qs, &QUIState::offroadTransition, homeWindow, &HomeWindow::offroadTransitionSignal); settingsWindow = new SettingsWindow(this); main_layout->addWidget(settingsWindow); QObject::connect(settingsWindow, &SettingsWindow::closeSettings, this, &MainWindow::closeSettings); - QObject::connect(&qs, &QUIState::offroadTransition, settingsWindow, &SettingsWindow::offroadTransition); QObject::connect(settingsWindow, &SettingsWindow::reviewTrainingGuide, [=]() { onboardingWindow->showTrainingGuide(); main_layout->setCurrentWidget(onboardingWindow); @@ -37,17 +33,15 @@ MainWindow::MainWindow(QWidget *parent) : QWidget(parent) { main_layout->setCurrentWidget(onboardingWindow); } - device.setAwake(true, true); - QObject::connect(&qs, &QUIState::uiUpdate, &device, &Device::update); - QObject::connect(&qs, &QUIState::offroadTransition, [=](bool offroad) { + QObject::connect(uiState(), &UIState::offroadTransition, [=](bool offroad) { if (!offroad) { closeSettings(); } }); - QObject::connect(&device, &Device::displayPowerChanged, [=]() { - if(main_layout->currentWidget() != onboardingWindow) { - closeSettings(); - } + QObject::connect(&device, &Device::interactiveTimout, [=]() { + if (main_layout->currentWidget() == settingsWindow) { + closeSettings(); + } }); // load fonts @@ -80,26 +74,26 @@ void MainWindow::openSettings() { void MainWindow::closeSettings() { main_layout->setCurrentWidget(homeWindow); - if (QUIState::ui_state.scene.started) { + if (uiState()->scene.started) { homeWindow->showSidebar(false); } } bool MainWindow::eventFilter(QObject *obj, QEvent *event) { - // wake screen on tap - if (event->type() == QEvent::MouseButtonPress || event->type() == QEvent::TouchBegin) { - device.setAwake(true, true); - } + const static QSet evts({QEvent::MouseButtonPress, QEvent::MouseMove, + QEvent::TouchBegin, QEvent::TouchUpdate, QEvent::TouchEnd}); + if (evts.contains(event->type())) { + device.resetInteractiveTimout(); #ifdef QCOM - // filter out touches while in android activity - const static QSet filter_events({QEvent::MouseButtonPress, QEvent::MouseMove, QEvent::TouchBegin, QEvent::TouchUpdate, QEvent::TouchEnd}); - if (HardwareEon::launched_activity && filter_events.contains(event->type())) { - HardwareEon::check_activity(); + // filter out touches while in android activity if (HardwareEon::launched_activity) { - return true; + HardwareEon::check_activity(); + if (HardwareEon::launched_activity) { + return true; + } } - } #endif + } return false; } diff --git a/selfdrive/ui/qt/window.h b/selfdrive/ui/qt/window.h index 069831cff..0bd328aa8 100644 --- a/selfdrive/ui/qt/window.h +++ b/selfdrive/ui/qt/window.h @@ -19,7 +19,6 @@ private: void closeSettings(); Device device; - QUIState qs; QStackedLayout *main_layout; HomeWindow *homeWindow; diff --git a/selfdrive/ui/replay/camera.cc b/selfdrive/ui/replay/camera.cc index b37332ae7..9bcc00583 100644 --- a/selfdrive/ui/replay/camera.cc +++ b/selfdrive/ui/replay/camera.cc @@ -1,9 +1,7 @@ #include "selfdrive/ui/replay/camera.h" +#include "selfdrive/ui/replay/util.h" #include -#include - -const int YUV_BUF_COUNT = 50; CameraServer::CameraServer(std::pair camera_size[MAX_CAMERAS], bool send_yuv) : send_yuv(send_yuv) { for (int i = 0; i < MAX_CAMERAS; ++i) { @@ -26,10 +24,10 @@ void CameraServer::startVipcServer() { vipc_server_.reset(new VisionIpcServer("camerad")); for (auto &cam : cameras_) { if (cam.width > 0 && cam.height > 0) { - std::cout << "camera[" << cam.type << "] frame size " << cam.width << "x" << cam.height << std::endl; + rInfo("camera[%d] frame size %dx%d", cam.type, cam.width, cam.height); vipc_server_->create_buffers(cam.rgb_type, UI_BUF_COUNT, true, cam.width, cam.height); if (send_yuv) { - vipc_server_->create_buffers(cam.yuv_type, YUV_BUF_COUNT, false, cam.width, cam.height); + vipc_server_->create_buffers(cam.yuv_type, YUV_BUFFER_COUNT, false, cam.width, cam.height); } if (!cam.thread.joinable()) { cam.thread = std::thread(&CameraServer::cameraThread, this, std::ref(cam)); @@ -63,7 +61,7 @@ void CameraServer::cameraThread(Camera &cam) { if (rgb) vipc_server_->send(rgb, &extra, false); if (yuv) vipc_server_->send(yuv, &extra, false); } else { - std::cout << "camera[" << cam.type << "] failed to get frame:" << eidx.getSegmentId() << std::endl; + rError("camera[%d] failed to get frame:", cam.type, eidx.getSegmentId()); } cam.cached_id = id + 1; diff --git a/selfdrive/ui/replay/camera.h b/selfdrive/ui/replay/camera.h index 21e02292d..340a120e8 100644 --- a/selfdrive/ui/replay/camera.h +++ b/selfdrive/ui/replay/camera.h @@ -18,7 +18,7 @@ public: protected: struct Camera { CameraType type; - VisionStreamType rgb_type; + VisionStreamType rgb_type; VisionStreamType yuv_type; int width; int height; diff --git a/selfdrive/ui/replay/consoleui.cc b/selfdrive/ui/replay/consoleui.cc new file mode 100644 index 000000000..72e2fcf80 --- /dev/null +++ b/selfdrive/ui/replay/consoleui.cc @@ -0,0 +1,353 @@ +#include "selfdrive/ui/replay/consoleui.h" + +#include +#include + +#include "selfdrive/common/version.h" + +namespace { + +const int BORDER_SIZE = 3; + +const std::initializer_list> keyboard_shortcuts[] = { + { + {"s", "+10s"}, + {"shift+s", "-10s"}, + {"m", "+60s"}, + {"shift+m", "-60s"}, + {"space", "Pause/Resume"}, + {"e", "Next Engagement"}, + {"d", "Next Disengagement"}, + }, + { + {"enter", "Enter seek request"}, + {"x", "+/-Replay speed"}, + {"q", "Exit"}, + }, +}; + +enum Color { + Default, + Debug, + Yellow, + Green, + Red, + BrightWhite, + Engaged, + Disengaged, +}; + +void add_str(WINDOW *w, const char *str, Color color = Color::Default, bool bold = false) { + if (color != Color::Default) wattron(w, COLOR_PAIR(color)); + if (bold) wattron(w, A_BOLD); + waddstr(w, str); + if (bold) wattroff(w, A_BOLD); + if (color != Color::Default) wattroff(w, COLOR_PAIR(color)); +} + +std::string format_seconds(int s) { + int total_minutes = s / 60; + int seconds = s % 60; + int hours = total_minutes / 60; + int minutes = total_minutes % 60; + return util::string_format("%02d:%02d:%02d", hours, minutes, seconds); +} + +} // namespace + +ConsoleUI::ConsoleUI(Replay *replay, QObject *parent) : replay(replay), sm({"carState", "liveParameters"}), QObject(parent) { + // Initialize curses + initscr(); + clear(); + curs_set(false); + cbreak(); // Line buffering disabled. pass on everything + noecho(); + keypad(stdscr, true); + nodelay(stdscr, true); // non-blocking getchar() + + // Initialize all the colors. https://www.ditig.com/256-colors-cheat-sheet + start_color(); + init_pair(Color::Debug, 246, COLOR_BLACK); // #949494 + init_pair(Color::Yellow, 184, COLOR_BLACK); + init_pair(Color::Red, COLOR_RED, COLOR_BLACK); + init_pair(Color::BrightWhite, 15, COLOR_BLACK); + init_pair(Color::Disengaged, COLOR_BLUE, COLOR_BLUE); + init_pair(Color::Engaged, 28, 28); + init_pair(Color::Green, 34, COLOR_BLACK); + + initWindows(); + + qRegisterMetaType("uint64_t"); + qRegisterMetaType("ReplyMsgType"); + installMessageHandler([this](ReplyMsgType type, const std::string msg) { + emit logMessageSignal(type, QString::fromStdString(msg)); + }); + installDownloadProgressHandler([this](uint64_t cur, uint64_t total, bool success) { + emit updateProgressBarSignal(cur, total, success); + }); + + QObject::connect(replay, &Replay::streamStarted, this, &ConsoleUI::updateSummary); + QObject::connect(¬ifier, SIGNAL(activated(int)), SLOT(readyRead())); + QObject::connect(this, &ConsoleUI::updateProgressBarSignal, this, &ConsoleUI::updateProgressBar); + QObject::connect(this, &ConsoleUI::logMessageSignal, this, &ConsoleUI::logMessage); + + sm_timer.callOnTimeout(this, &ConsoleUI::updateStatus); + sm_timer.start(100); + getch_timer.start(1000, this); + readyRead(); +} + +ConsoleUI::~ConsoleUI() { + endwin(); +} + +void ConsoleUI::initWindows() { + getmaxyx(stdscr, max_height, max_width); + w.fill(nullptr); + w[Win::Title] = newwin(1, max_width, 0, 0); + w[Win::Stats] = newwin(2, max_width - 2 * BORDER_SIZE, 2, BORDER_SIZE); + w[Win::Timeline] = newwin(4, max_width - 2 * BORDER_SIZE, 5, BORDER_SIZE); + w[Win::TimelineDesc] = newwin(1, 100, 10, BORDER_SIZE); + w[Win::CarState] = newwin(3, 100, 12, BORDER_SIZE); + w[Win::DownloadBar] = newwin(1, 100, 16, BORDER_SIZE); + if (int log_height = max_height - 27; log_height > 4) { + w[Win::LogBorder] = newwin(log_height, max_width - 2 * (BORDER_SIZE - 1), 17, BORDER_SIZE - 1); + box(w[Win::LogBorder], 0, 0); + w[Win::Log] = newwin(log_height - 2, max_width - 2 * BORDER_SIZE, 18, BORDER_SIZE); + scrollok(w[Win::Log], true); + } + w[Win::Help] = newwin(5, max_width - (2 * BORDER_SIZE), max_height - 6, BORDER_SIZE); + + // set the title bar + wbkgd(w[Win::Title], A_REVERSE); + mvwprintw(w[Win::Title], 0, 3, "openpilot replay %s", COMMA_VERSION); + + // show windows on the real screen + refresh(); + displayTimelineDesc(); + displayHelp(); + updateSummary(); + updateTimeline(); + for (auto win : w) { + if (win) wrefresh(win); + } +} + +void ConsoleUI::timerEvent(QTimerEvent *ev) { + if (ev->timerId() != getch_timer.timerId()) return; + + if (is_term_resized(max_height, max_width)) { + for (auto win : w) { + if (win) delwin(win); + } + endwin(); + clear(); + refresh(); + initWindows(); + rWarning("resize term %dx%d", max_height, max_width); + } + updateTimeline(); +} + +void ConsoleUI::updateStatus() { + auto write_item = [this](int y, int x, const char *key, const std::string &value, const char *unit, + bool bold = false, Color color = Color::BrightWhite) { + auto win = w[Win::CarState]; + wmove(win, y, x); + add_str(win, key); + add_str(win, value.c_str(), color, bold); + add_str(win, unit); + }; + static const std::pair status_text[] = { + {"loading...", Color::Red}, + {"playing", Color::Green}, + {"paused...", Color::Yellow}, + }; + + sm.update(0); + + if (status != Status::Paused) { + status = (sm.updated("carState") || sm.updated("liveParameters")) ? Status::Playing : Status::Waiting; + } + auto [status_str, status_color] = status_text[status]; + write_item(0, 0, "STATUS: ", status_str, " ", false, status_color); + std::string suffix = util::string_format(" / %s [%d/%d] ", format_seconds(replay->totalSeconds()).c_str(), + replay->currentSeconds() / 60, replay->route()->segments().size()); + write_item(0, 25, "TIME: ", format_seconds(replay->currentSeconds()), suffix.c_str(), true); + + auto p = sm["liveParameters"].getLiveParameters(); + write_item(1, 0, "STIFFNESS: ", util::string_format("%.2f %%", p.getStiffnessFactor() * 100), " "); + write_item(1, 25, "SPEED: ", util::string_format("%.2f", sm["carState"].getCarState().getVEgo()), " m/s"); + write_item(2, 0, "STEER RATIO: ", util::string_format("%.2f", p.getSteerRatio()), ""); + auto angle_offsets = util::string_format("%.2f|%.2f", p.getAngleOffsetAverageDeg(), p.getAngleOffsetDeg()); + write_item(2, 25, "ANGLE OFFSET(AVG|INSTANT): ", angle_offsets, " deg"); + + wrefresh(w[Win::CarState]); +} + +void ConsoleUI::displayHelp() { + for (int i = 0; i < std::size(keyboard_shortcuts); ++i) { + wmove(w[Win::Help], i * 2, 0); + for (auto &[key, desc] : keyboard_shortcuts[i]) { + wattron(w[Win::Help], A_REVERSE); + waddstr(w[Win::Help], (' ' + key + ' ').c_str()); + wattroff(w[Win::Help], A_REVERSE); + waddstr(w[Win::Help], (' ' + desc + ' ').c_str()); + } + } + wrefresh(w[Win::Help]); +} + +void ConsoleUI::displayTimelineDesc() { + std::tuple indicators[]{ + {Color::Engaged, " Engaged ", false}, + {Color::Disengaged, " Disengaged ", false}, + {Color::Green, " Info ", true}, + {Color::Yellow, " Warning ", true}, + {Color::Red, " Critical ", true}, + }; + for (auto [color, name, bold] : indicators) { + add_str(w[Win::TimelineDesc], "__", color, bold); + add_str(w[Win::TimelineDesc], name); + } +} + +void ConsoleUI::logMessage(ReplyMsgType type, const QString &msg) { + if (auto win = w[Win::Log]) { + Color color = Color::Default; + if (type == ReplyMsgType::Debug) { + color = Color::Debug; + } else if (type == ReplyMsgType::Warning) { + color = Color::Yellow; + } else if (type == ReplyMsgType::Critical) { + color = Color::Red; + } + add_str(win, qPrintable(msg + "\n"), color); + wrefresh(win); + } +} + +void ConsoleUI::updateProgressBar(uint64_t cur, uint64_t total, bool success) { + werase(w[Win::DownloadBar]); + if (success && cur < total) { + const int width = 35; + const float progress = cur / (double)total; + const int pos = width * progress; + wprintw(w[Win::DownloadBar], "Downloading [%s>%s] %d%% %s", std::string(pos, '=').c_str(), + std::string(width - pos, ' ').c_str(), int(progress * 100.0), formattedDataSize(total).c_str()); + } + wrefresh(w[Win::DownloadBar]); +} + +void ConsoleUI::updateSummary() { + const auto &route = replay->route(); + mvwprintw(w[Win::Stats], 0, 0, "Route: %s, %d segments", qPrintable(route->name()), route->segments().size()); + mvwprintw(w[Win::Stats], 1, 0, "Car Fingerprint: %s", replay->carFingerprint().c_str()); + wrefresh(w[Win::Stats]); +} + +void ConsoleUI::updateTimeline() { + auto win = w[Win::Timeline]; + int width = getmaxx(win); + werase(win); + + wattron(win, COLOR_PAIR(Color::Disengaged)); + mvwhline(win, 1, 0, ' ', width); + mvwhline(win, 2, 0, ' ', width); + wattroff(win, COLOR_PAIR(Color::Disengaged)); + + const int total_sec = replay->totalSeconds(); + for (auto [begin, end, type] : replay->getTimeline()) { + int start_pos = ((double)begin / total_sec) * width; + int end_pos = ((double)end / total_sec) * width; + if (type == TimelineType::Engaged) { + mvwchgat(win, 1, start_pos, end_pos - start_pos + 1, A_COLOR, Color::Engaged, NULL); + mvwchgat(win, 2, start_pos, end_pos - start_pos + 1, A_COLOR, Color::Engaged, NULL); + } else { + auto color_id = Color::Green; + if (type != TimelineType::AlertInfo) { + color_id = type == TimelineType::AlertWarning ? Color::Yellow : Color::Red; + } + mvwchgat(win, 3, start_pos, end_pos - start_pos + 1, ACS_S3, color_id, NULL); + } + } + + int cur_pos = ((double)replay->currentSeconds() / total_sec) * width; + wattron(win, COLOR_PAIR(Color::BrightWhite)); + mvwaddch(win, 0, cur_pos, ACS_VLINE); + mvwaddch(win, 3, cur_pos, ACS_VLINE); + wattroff(win, COLOR_PAIR(Color::BrightWhite)); + wrefresh(win); +} + +void ConsoleUI::readyRead() { + int c; + while ((c = getch()) != ERR) { + handleKey(c); + } +} + +void ConsoleUI::pauseReplay(bool pause) { + replay->pause(pause); + status = pause ? Status::Paused : Status::Waiting; +} + +void ConsoleUI::handleKey(char c) { + if (c == '\n') { + // pause the replay and blocking getchar() + pauseReplay(true); + updateStatus(); + getch_timer.stop(); + curs_set(true); + nodelay(stdscr, false); + + // Wait for user input + rWarning("Waiting for input..."); + int y = getmaxy(stdscr) - 9; + move(y, BORDER_SIZE); + add_str(stdscr, "Enter seek request: ", Color::BrightWhite, true); + refresh(); + + // Seek to choice + echo(); + int choice = 0; + scanw((char *)"%d", &choice); + noecho(); + pauseReplay(false); + replay->seekTo(choice, false); + + // Clean up and turn off the blocking mode + move(y, 0); + clrtoeol(); + nodelay(stdscr, true); + curs_set(false); + refresh(); + getch_timer.start(1000, this); + + } else if (c == 'x') { + if (replay->hasFlag(REPLAY_FLAG_FULL_SPEED)) { + replay->removeFlag(REPLAY_FLAG_FULL_SPEED); + rWarning("replay at normal speed"); + } else { + replay->addFlag(REPLAY_FLAG_FULL_SPEED); + rWarning("replay at full speed"); + } + } else if (c == 'e') { + replay->seekToFlag(FindFlag::nextEngagement); + } else if (c == 'd') { + replay->seekToFlag(FindFlag::nextDisEngagement); + } else if (c == 'm') { + replay->seekTo(+60, true); + } else if (c == 'M') { + replay->seekTo(-60, true); + } else if (c == 's') { + replay->seekTo(+10, true); + } else if (c == 'S') { + replay->seekTo(-10, true); + } else if (c == ' ') { + pauseReplay(!replay->isPaused()); + } else if (c == 'q' || c == 'Q') { + replay->stop(); + qApp->exit(); + } +} diff --git a/selfdrive/ui/replay/consoleui.h b/selfdrive/ui/replay/consoleui.h new file mode 100644 index 000000000..bce1146d4 --- /dev/null +++ b/selfdrive/ui/replay/consoleui.h @@ -0,0 +1,50 @@ +#pragma once + +#include +#include +#include +#include +#include +#include + +#include "selfdrive/ui/replay/replay.h" +#include + +class ConsoleUI : public QObject { + Q_OBJECT + +public: + ConsoleUI(Replay *replay, QObject *parent = 0); + ~ConsoleUI(); + +private: + void initWindows(); + void handleKey(char c); + void displayHelp(); + void displayTimelineDesc(); + void updateTimeline(); + void updateSummary(); + void updateStatus(); + void pauseReplay(bool pause); + + enum Status { Waiting, Playing, Paused }; + enum Win { Title, Stats, Log, LogBorder, DownloadBar, Timeline, TimelineDesc, Help, CarState, Max}; + std::array w{}; + SubMaster sm; + Replay *replay; + QBasicTimer getch_timer; + QTimer sm_timer; + QSocketNotifier notifier{0, QSocketNotifier::Read, this}; + int max_width, max_height; + Status status = Status::Waiting; + +signals: + void updateProgressBarSignal(uint64_t cur, uint64_t total, bool success); + void logMessageSignal(ReplyMsgType type, const QString &msg); + +private slots: + void readyRead(); + void timerEvent(QTimerEvent *ev); + void updateProgressBar(uint64_t cur, uint64_t total, bool success); + void logMessage(ReplyMsgType type, const QString &msg); +}; diff --git a/selfdrive/ui/replay/filereader.cc b/selfdrive/ui/replay/filereader.cc index 84dc76694..b57a62d50 100644 --- a/selfdrive/ui/replay/filereader.cc +++ b/selfdrive/ui/replay/filereader.cc @@ -1,7 +1,6 @@ #include "selfdrive/ui/replay/filereader.h" #include -#include #include "selfdrive/common/util.h" #include "selfdrive/ui/replay/util.h" @@ -35,13 +34,12 @@ std::string FileReader::read(const std::string &file, std::atomic *abort) std::string FileReader::download(const std::string &url, std::atomic *abort) { for (int i = 0; i <= max_retries_ && !(abort && *abort); ++i) { + if (i > 0) rWarning("download failed, retrying %d", i); + std::string result = httpGet(url, chunk_size_, abort); if (!result.empty()) { return result; } - if (i != max_retries_) { - std::cout << "download failed, retrying " << i + 1 << std::endl; - } } return {}; } diff --git a/selfdrive/ui/replay/framereader.cc b/selfdrive/ui/replay/framereader.cc index 32af922f1..ef90c2835 100644 --- a/selfdrive/ui/replay/framereader.cc +++ b/selfdrive/ui/replay/framereader.cc @@ -1,8 +1,11 @@ #include "selfdrive/ui/replay/framereader.h" +#include "selfdrive/ui/replay/util.h" #include #include "libyuv.h" +#include "cereal/visionipc/visionbuf.h" + namespace { struct buffer_data { @@ -13,7 +16,8 @@ struct buffer_data { int readPacket(void *opaque, uint8_t *buf, int buf_size) { struct buffer_data *bd = (struct buffer_data *)opaque; - buf_size = std::min((size_t)buf_size, bd->size - bd->offset); + assert(bd->offset <= bd->size); + buf_size = std::min((size_t)buf_size, (size_t)(bd->size - bd->offset)); if (!buf_size) return AVERROR_EOF; memcpy(buf, bd->data + bd->offset, buf_size); @@ -26,7 +30,7 @@ enum AVPixelFormat get_hw_format(AVCodecContext *ctx, const enum AVPixelFormat * for (const enum AVPixelFormat *p = pix_fmts; *p != -1; p++) { if (*p == *hw_pix_fmt) return *p; } - printf("Please run replay with the --no-cuda flag!\n"); + rWarning("Please run replay with the --no-cuda flag!"); // fallback to YUV420p *hw_pix_fmt = AV_PIX_FMT_NONE; return AV_PIX_FMT_YUV420P; @@ -34,7 +38,9 @@ enum AVPixelFormat get_hw_format(AVCodecContext *ctx, const enum AVPixelFormat * } // namespace -FrameReader::FrameReader() {} +FrameReader::FrameReader() { + av_log_set_level(AV_LOG_QUIET); +} FrameReader::~FrameReader() { for (AVPacket *pkt : packets) { @@ -78,13 +84,13 @@ bool FrameReader::load(const std::byte *data, size_t size, bool no_cuda, std::at if (ret != 0) { char err_str[1024] = {0}; av_strerror(ret, err_str, std::size(err_str)); - printf("Error loading video - %s\n", err_str); + rError("Error loading video - %s", err_str); return false; } ret = avformat_find_stream_info(input_ctx, nullptr); if (ret < 0) { - printf("cannot find a video stream in the input file\n"); + rError("cannot find a video stream in the input file"); return false; } @@ -98,10 +104,11 @@ bool FrameReader::load(const std::byte *data, size_t size, bool no_cuda, std::at width = (decoder_ctx->width + 3) & ~3; height = decoder_ctx->height; + visionbuf_compute_aligned_width_and_height(width, height, &aligned_width, &aligned_height); if (has_cuda_device && !no_cuda) { if (!initHardwareDecoder(AV_HWDEVICE_TYPE_CUDA)) { - printf("No CUDA capable device was found. fallback to CPU decoding.\n"); + rWarning("No CUDA capable device was found. fallback to CPU decoding."); } else { nv12toyuv_buffer.resize(getYUVSize()); } @@ -131,8 +138,8 @@ bool FrameReader::initHardwareDecoder(AVHWDeviceType hw_device_type) { for (int i = 0;; i++) { const AVCodecHWConfig *config = avcodec_get_hw_config(decoder_ctx->codec, i); if (!config) { - printf("decoder %s does not support hw device type %s.\n", - decoder_ctx->codec->name, av_hwdevice_get_type_name(hw_device_type)); + rWarning("decoder %s does not support hw device type %s.", decoder_ctx->codec->name, + av_hwdevice_get_type_name(hw_device_type)); return false; } if (config->methods & AV_CODEC_HW_CONFIG_METHOD_HW_DEVICE_CTX && config->device_type == hw_device_type) { @@ -145,7 +152,7 @@ bool FrameReader::initHardwareDecoder(AVHWDeviceType hw_device_type) { if (ret < 0) { hw_pix_fmt = AV_PIX_FMT_NONE; has_cuda_device = false; - printf("Failed to create specified HW device %d.\n", ret); + rWarning("Failed to create specified HW device %d.", ret); return false; } @@ -188,20 +195,21 @@ bool FrameReader::decode(int idx, uint8_t *rgb, uint8_t *yuv) { AVFrame *FrameReader::decodeFrame(AVPacket *pkt) { int ret = avcodec_send_packet(decoder_ctx, pkt); if (ret < 0) { - printf("Error sending a packet for decoding\n"); + rError("Error sending a packet for decoding: %d", ret); return nullptr; } av_frame_.reset(av_frame_alloc()); ret = avcodec_receive_frame(decoder_ctx, av_frame_.get()); if (ret != 0) { + rError("avcodec_receive_frame error: %d", ret); return nullptr; } if (av_frame_->format == hw_pix_fmt) { hw_frame.reset(av_frame_alloc()); if ((ret = av_hwframe_transfer_data(hw_frame.get(), av_frame_.get(), 0)) < 0) { - printf("error transferring the data from GPU to CPU\n"); + rError("error transferring the data from GPU to CPU"); return nullptr; } return hw_frame.get(); @@ -218,19 +226,21 @@ bool FrameReader::copyBuffers(AVFrame *f, uint8_t *rgb, uint8_t *yuv) { libyuv::NV12ToI420(f->data[0], f->linesize[0], f->data[1], f->linesize[1], y, width, u, width / 2, v, width / 2, width, height); libyuv::I420ToRGB24(y, width, u, width / 2, v, width / 2, - rgb, width * 3, width, height); + rgb, aligned_width * 3, width, height); } else { if (yuv) { uint8_t *u = yuv + width * height; uint8_t *v = u + (width / 2) * (height / 2); - memcpy(yuv, f->data[0], width * height); - memcpy(u, f->data[1], width / 2 * height / 2); - memcpy(v, f->data[2], width / 2 * height / 2); + libyuv::I420Copy(f->data[0], f->linesize[0], + f->data[1], f->linesize[1], + f->data[2], f->linesize[2], + yuv, width, u, width / 2, v, width / 2, + width, height); } libyuv::I420ToRGB24(f->data[0], f->linesize[0], f->data[1], f->linesize[1], f->data[2], f->linesize[2], - rgb, width * 3, width, height); + rgb, aligned_width * 3, width, height); } return true; } diff --git a/selfdrive/ui/replay/framereader.h b/selfdrive/ui/replay/framereader.h index d572b727e..8de5c1f93 100644 --- a/selfdrive/ui/replay/framereader.h +++ b/selfdrive/ui/replay/framereader.h @@ -22,12 +22,13 @@ public: bool load(const std::string &url, bool no_cuda = false, std::atomic *abort = nullptr, bool local_cache = false, int chunk_size = -1, int retries = 0); bool load(const std::byte *data, size_t size, bool no_cuda = false, std::atomic *abort = nullptr); bool get(int idx, uint8_t *rgb, uint8_t *yuv); - int getRGBSize() const { return width * height * 3; } + int getRGBSize() const { return aligned_width * aligned_height * 3; } int getYUVSize() const { return width * height * 3 / 2; } size_t getFrameCount() const { return packets.size(); } bool valid() const { return valid_; } int width = 0, height = 0; + int aligned_width = 0, aligned_height = 0; private: bool initHardwareDecoder(AVHWDeviceType hw_device_type); diff --git a/selfdrive/ui/replay/logreader.cc b/selfdrive/ui/replay/logreader.cc index 8e2836a4f..579fe5064 100644 --- a/selfdrive/ui/replay/logreader.cc +++ b/selfdrive/ui/replay/logreader.cc @@ -1,7 +1,6 @@ #include "selfdrive/ui/replay/logreader.h" #include -#include #include "selfdrive/ui/replay/util.h" Event::Event(const kj::ArrayPtr &amsg, bool frame) : reader(amsg), frame(frame) { @@ -56,15 +55,17 @@ bool LogReader::load(const std::string &url, std::atomic *abort, bool loca } bool LogReader::load(const std::byte *data, size_t size, std::atomic *abort) { - raw_ = decompressBZ2(data, size); + raw_ = decompressBZ2(data, size, abort); if (raw_.empty()) { - std::cout << "failed to decompress log" << std::endl; + if (!(abort && *abort)) { + rWarning("failed to decompress log"); + } return false; } try { kj::ArrayPtr words((const capnp::word *)raw_.data(), raw_.size() / sizeof(capnp::word)); - while (words.size() > 0) { + while (words.size() > 0 && !(abort && *abort)) { #ifdef HAS_MEMORY_RESOURCE Event *evt = new (mbr_) Event(words); @@ -90,12 +91,15 @@ bool LogReader::load(const std::byte *data, size_t size, std::atomic *abor events.push_back(evt); } } catch (const kj::Exception &e) { - std::cout << "failed to parse log : " << e.getDescription().cStr() << std::endl; - if (events.empty()) return false; - - std::cout << "read " << events.size() << " events from corrupt log" << std::endl; + rWarning("failed to parse log : %s", e.getDescription().cStr()); + if (!events.empty()) { + rWarning("read %zu events from corrupt log", events.size()); + } } - std::sort(events.begin(), events.end(), Event::lessThan()); - return true; + if (!events.empty() && !(abort && *abort)) { + std::sort(events.begin(), events.end(), Event::lessThan()); + return true; + } + return false; } diff --git a/selfdrive/ui/replay/logreader.h b/selfdrive/ui/replay/logreader.h index 33d7ea82f..7ada20605 100644 --- a/selfdrive/ui/replay/logreader.h +++ b/selfdrive/ui/replay/logreader.h @@ -34,7 +34,7 @@ public: return mbr->allocate(size); } void operator delete(void *ptr) { - // No-op. memory used by EventMemoryPool increases monotonically until the logReader is destroyed. + // No-op. memory used by EventMemoryPool increases monotonically until the logReader is destroyed. } #endif diff --git a/selfdrive/ui/replay/main.cc b/selfdrive/ui/replay/main.cc index 062837885..a7d2f5404 100644 --- a/selfdrive/ui/replay/main.cc +++ b/selfdrive/ui/replay/main.cc @@ -1,99 +1,13 @@ -#include - #include #include -#include -#include -#include -#include +#include "selfdrive/ui/replay/consoleui.h" #include "selfdrive/ui/replay/replay.h" const QString DEMO_ROUTE = "4cf7a6ad03080c90|2021-09-29--13-46-36"; -struct termios oldt = {}; -Replay *replay = nullptr; - -void sigHandler(int s) { - std::signal(s, SIG_DFL); - if (oldt.c_lflag) { - tcsetattr(STDIN_FILENO, TCSANOW, &oldt); - } - if (replay) { - replay->stop(); - } - qApp->quit(); -} - -int getch() { - int ch; - struct termios newt; - - tcgetattr(STDIN_FILENO, &oldt); - newt = oldt; - newt.c_lflag &= ~(ICANON | ECHO); - - tcsetattr(STDIN_FILENO, TCSANOW, &newt); - ch = getchar(); - tcsetattr(STDIN_FILENO, TCSANOW, &oldt); - - return ch; -} - -void keyboardThread(Replay *replay_) { - char c; - while (true) { - c = getch(); - if (c == '\n') { - printf("Enter seek request: "); - std::string r; - std::cin >> r; - - try { - if (r[0] == '#') { - r.erase(0, 1); - replay_->seekTo(std::stoi(r) * 60, false); - } else { - replay_->seekTo(std::stoi(r), false); - } - } catch (std::invalid_argument) { - qDebug() << "invalid argument"; - } - getch(); // remove \n from entering seek - } else if (c == 'm') { - replay_->seekTo(+60, true); - } else if (c == 'M') { - replay_->seekTo(-60, true); - } else if (c == 's') { - replay_->seekTo(+10, true); - } else if (c == 'S') { - replay_->seekTo(-10, true); - } else if (c == 'G') { - replay_->seekTo(0, true); - } else if (c == ' ') { - replay_->pause(!replay_->isPaused()); - } - } -} - -void replayMessageOutput(QtMsgType type, const QMessageLogContext &context, const QString &msg) { - QByteArray localMsg = msg.toLocal8Bit(); - if (type == QtDebugMsg) { - std::cout << "\033[38;5;248m" << localMsg.constData() << "\033[00m" << std::endl; - } else if (type == QtWarningMsg) { - std::cout << "\033[38;5;227m" << localMsg.constData() << "\033[00m" << std::endl; - } else if (type == QtCriticalMsg) { - std::cout << "\033[38;5;196m" << localMsg.constData() << "\033[00m" << std::endl; - } else { - std::cout << localMsg.constData() << std::endl; - } -} int main(int argc, char *argv[]) { - qInstallMessageHandler(replayMessageOutput); - QApplication app(argc, argv); - std::signal(SIGINT, sigHandler); - std::signal(SIGTERM, sigHandler); const std::tuple flags[] = { {"dcam", REPLAY_FLAG_DCAM, "load driver camera"}, @@ -103,6 +17,7 @@ int main(int argc, char *argv[]) { {"qcam", REPLAY_FLAG_QCAMERA, "load qcamera"}, {"yuv", REPLAY_FLAG_SEND_YUV, "send yuv frame"}, {"no-cuda", REPLAY_FLAG_NO_CUDA, "disable CUDA"}, + {"no-vipc", REPLAY_FLAG_NO_VIPC, "do not output video"}, }; QCommandLineParser parser; @@ -134,16 +49,12 @@ int main(int argc, char *argv[]) { replay_flags |= flag; } } - replay = new Replay(route, allow, block, nullptr, replay_flags, parser.value("data_dir"), &app); + Replay *replay = new Replay(route, allow, block, nullptr, replay_flags, parser.value("data_dir"), &app); if (!replay->load()) { return 0; } - replay->start(parser.value("start").toInt()); - // start keyboard control thread - QThread *t = new QThread(); - QObject::connect(t, &QThread::started, [=]() { keyboardThread(replay); }); - QObject::connect(t, &QThread::finished, t, &QThread::deleteLater); - t->start(); + ConsoleUI console_ui(replay); + replay->start(parser.value("start").toInt()); return app.exec(); } diff --git a/selfdrive/ui/replay/replay.cc b/selfdrive/ui/replay/replay.cc index 8155eb345..fd1a4b199 100644 --- a/selfdrive/ui/replay/replay.cc +++ b/selfdrive/ui/replay/replay.cc @@ -1,7 +1,7 @@ #include "selfdrive/ui/replay/replay.h" -#include #include +#include #include #include "cereal/services.h" @@ -23,6 +23,7 @@ Replay::Replay(QString route, QStringList allow, QStringList block, SubMaster *s } } qDebug() << "services " << s; + qDebug() << "loading route " << route; if (sm == nullptr) { pm = std::make_unique(s); @@ -30,9 +31,6 @@ Replay::Replay(QString route, QStringList allow, QStringList block, SubMaster *s route_ = std::make_unique(route, data_dir); events_ = std::make_unique>(); new_events_ = std::make_unique>(); - - connect(this, &Replay::seekTo, this, &Replay::doSeek); - connect(this, &Replay::segmentChanged, this, &Replay::queueSegment); } Replay::~Replay() { @@ -42,7 +40,7 @@ Replay::~Replay() { void Replay::stop() { if (!stream_thread_ && segments_.empty()) return; - qDebug() << "shutdown: in progress..."; + rInfo("shutdown: in progress..."); if (stream_thread_ != nullptr) { exit_ = updating_events_ = true; stream_cv_.notify_one(); @@ -52,25 +50,29 @@ void Replay::stop() { } segments_.clear(); camera_server_.reset(nullptr); - qDebug() << "shutdown: done"; + timeline_future.waitForFinished(); + rInfo("shutdown: done"); } bool Replay::load() { if (!route_->load()) { - qCritical() << "failed to load route" << route_->name() << "from server"; + qCritical() << "failed to load route" << route_->name() + << "from" << (route_->dir().isEmpty() ? "server" : route_->dir()); return false; } for (auto &[n, f] : route_->segments()) { - if ((!f.rlog.isEmpty() || !f.qlog.isEmpty()) && (!f.road_cam.isEmpty() || !f.qcamera.isEmpty())) { - segments_[n] = nullptr; + bool has_log = !f.rlog.isEmpty() || !f.qlog.isEmpty(); + bool has_video = !f.road_cam.isEmpty() || !f.qcamera.isEmpty(); + if (has_log && (has_video || hasFlag(REPLAY_FLAG_NO_VIPC))) { + segments_.insert({n, nullptr}); } } if (segments_.empty()) { qCritical() << "no valid segments in route" << route_->name(); return false; } - qInfo() << "load route" << route_->name() << "with" << segments_.size() << "valid segments"; + rInfo("load route %s with %zu valid segments", qPrintable(route_->name()), segments_.size()); return true; } @@ -89,21 +91,17 @@ void Replay::updateEvents(const std::function &lambda) { stream_cv_.notify_one(); } -void Replay::doSeek(int seconds, bool relative) { - if (segments_.empty()) return; - +void Replay::seekTo(int seconds, bool relative) { + seconds = relative ? seconds + currentSeconds() : seconds; updateEvents([&]() { - if (relative) { - seconds += currentSeconds(); - } seconds = std::max(0, seconds); int seg = seconds / 60; if (segments_.find(seg) == segments_.end()) { - qWarning() << "can't seek to" << seconds << "s, segment" << seg << "is invalid"; + rWarning("can't seek to %d s segment %d is invalid", seconds, seg); return true; } - qInfo() << "seeking to" << seconds << "s, segment" << seg; + rInfo("seeking to %d s, segment %d", seconds, seg); current_segment_ = seg; cur_mono_time_ = route_start_ts_ + seconds * 1e9; return isSegmentMerged(seg); @@ -111,12 +109,68 @@ void Replay::doSeek(int seconds, bool relative) { queueSegment(); } +void Replay::seekToFlag(FindFlag flag) { + if (auto next = find(flag)) { + seekTo(*next - 2, false); // seek to 2 seconds before next + } +} + +void Replay::buildTimeline() { + uint64_t engaged_begin = 0; + uint64_t alert_begin = 0; + TimelineType alert_type = TimelineType::None; + + for (int i = 0; i < segments_.size() && !exit_; ++i) { + LogReader log; + if (!log.load(route_->at(i).qlog.toStdString(), &exit_, !hasFlag(REPLAY_FLAG_NO_FILE_CACHE), 0, 3)) continue; + + for (const Event *e : log.events) { + if (e->which == cereal::Event::Which::CONTROLS_STATE) { + auto cs = e->event.getControlsState(); + + if (!engaged_begin && cs.getEnabled()) { + engaged_begin = e->mono_time; + } else if (engaged_begin && !cs.getEnabled()) { + std::lock_guard lk(timeline_lock); + timeline.push_back({toSeconds(engaged_begin), toSeconds(e->mono_time), TimelineType::Engaged}); + engaged_begin = 0; + } + + if (!alert_begin && cs.getAlertType().size() > 0) { + alert_begin = e->mono_time; + alert_type = TimelineType::AlertInfo; + if (cs.getAlertStatus() != cereal::ControlsState::AlertStatus::NORMAL) { + alert_type = cs.getAlertStatus() == cereal::ControlsState::AlertStatus::USER_PROMPT + ? TimelineType::AlertWarning + : TimelineType::AlertCritical; + } + } else if (alert_begin && cs.getAlertType().size() == 0) { + std::lock_guard lk(timeline_lock); + timeline.push_back({toSeconds(alert_begin), toSeconds(e->mono_time), alert_type}); + alert_begin = 0; + } + } + } + } +} + +std::optional Replay::find(FindFlag flag) { + int cur_ts = currentSeconds(); + for (auto [start_ts, end_ts, type] : getTimeline()) { + if (type == TimelineType::Engaged) { + if (flag == FindFlag::nextEngagement && start_ts > cur_ts) { + return start_ts; + } else if (flag == FindFlag::nextDisEngagement && end_ts > cur_ts) { + return end_ts; + } + } + } + return std::nullopt; +} + void Replay::pause(bool pause) { updateEvents([=]() { - qInfo() << (pause ? "paused..." : "resuming"); - if (pause) { - qInfo() << "at " << currentSeconds() << "s"; - } + rWarning("%s at %d s", pause ? "paused..." : "resuming", currentSeconds()); paused_ = pause; return true; }); @@ -124,14 +178,14 @@ void Replay::pause(bool pause) { void Replay::setCurrentSegment(int n) { if (current_segment_.exchange(n) != n) { - emit segmentChanged(); + QMetaObject::invokeMethod(this, &Replay::queueSegment, Qt::QueuedConnection); } } void Replay::segmentLoadFinished(bool success) { if (!success) { Segment *seg = qobject_cast(sender()); - qWarning() << "failed to load segment " << seg->seg_num << ", removing it from current replay list"; + rWarning("failed to load segment %d, removing it from current replay list", seg->seg_num); segments_.erase(seg->seg_num); } queueSegment(); @@ -147,19 +201,18 @@ void Replay::queueSegment() { } // load one segment at a time for (auto it = cur; it != end; ++it) { - if (!it->second) { - if (it == cur || std::prev(it)->second->isLoaded()) { - auto &[n, seg] = *it; + auto &[n, seg] = *it; + if ((seg && !seg->isLoaded()) || !seg) { + if (!seg) { + rDebug("loading segment %d...", n); seg = std::make_unique(n, route_->at(n), flags_); QObject::connect(seg.get(), &Segment::loadFinished, this, &Replay::segmentLoadFinished); - qDebug() << "loading segment" << n << "..."; } break; } } - const auto &cur_segment = cur->second; - enableHttpLogging(!cur_segment->isLoaded()); + const auto &cur_segment = cur->second; // merge the previous adjacent segment if it's loaded auto begin = segments_.find(cur_segment->seg_num - 1); if (begin == segments_.end() || !(begin->second && begin->second->isLoaded())) { @@ -174,6 +227,7 @@ void Replay::queueSegment() { // start stream thread if (stream_thread_ == nullptr && cur_segment->isLoaded()) { startStream(cur_segment.get()); + emit streamStarted(); } } @@ -181,13 +235,18 @@ void Replay::mergeSegments(const SegmentMap::iterator &begin, const SegmentMap:: // merge 3 segments in sequence. std::vector segments_need_merge; size_t new_events_size = 0; - for (auto it = begin; it != end && it->second->isLoaded() && segments_need_merge.size() < 3; ++it) { + for (auto it = begin; it != end && it->second && it->second->isLoaded() && segments_need_merge.size() < 3; ++it) { segments_need_merge.push_back(it->first); new_events_size += it->second->log->events.size(); } if (segments_need_merge != segments_merged_) { - qDebug() << "merge segments" << segments_need_merge; + std::string s; + for (int i = 0; i < segments_need_merge.size(); ++i) { + s += std::to_string(segments_need_merge[i]); + if (i != segments_need_merge.size() - 1) s += ", "; + } + rDebug("merge segments %s", s.c_str()); new_events_->clear(); new_events_->reserve(new_events_size); for (int n : segments_need_merge) { @@ -215,26 +274,31 @@ void Replay::startStream(const Segment *cur_segment) { // write CarParams it = std::find_if(events.begin(), events.end(), [](auto e) { return e->which == cereal::Event::Which::CAR_PARAMS; }); if (it != events.end()) { + car_fingerprint_ = (*it)->event.getCarParams().getCarFingerprint(); auto bytes = (*it)->bytes(); Params().put("CarParams", (const char *)bytes.begin(), bytes.size()); } else { - qWarning() << "failed to read CarParams from current segment"; + rWarning("failed to read CarParams from current segment"); } // start camera server - std::pair camera_size[MAX_CAMERAS] = {}; - for (auto type : ALL_CAMERAS) { - if (auto &fr = cur_segment->frames[type]) { - camera_size[type] = {fr->width, fr->height}; + if (!hasFlag(REPLAY_FLAG_NO_VIPC)) { + std::pair camera_size[MAX_CAMERAS] = {}; + for (auto type : ALL_CAMERAS) { + if (auto &fr = cur_segment->frames[type]) { + camera_size[type] = {fr->width, fr->height}; + } } + camera_server_ = std::make_unique(camera_size, hasFlag(REPLAY_FLAG_SEND_YUV)); } - camera_server_ = std::make_unique(camera_size, flags_ & REPLAY_FLAG_SEND_YUV); // start stream thread stream_thread_ = new QThread(); QObject::connect(stream_thread_, &QThread::started, [=]() { stream(); }); QObject::connect(stream_thread_, &QThread::finished, stream_thread_, &QThread::deleteLater); stream_thread_->start(); + + timeline_future = QtConcurrent::run(this, &Replay::buildTimeline); } void Replay::publishMessage(const Event *e) { @@ -242,7 +306,7 @@ void Replay::publishMessage(const Event *e) { auto bytes = e->bytes(); int ret = pm->send(sockets_[e->which], (capnp::byte *)bytes.begin(), bytes.size()); if (ret == -1) { - qDebug() << "stop publishing" << sockets_[e->which] << "due to multiple publishers error"; + rWarning("stop publishing %s due to multiple publishers error", sockets_[e->which]); sockets_[e->which] = nullptr; } } else { @@ -256,8 +320,8 @@ void Replay::publishFrame(const Event *e) { {cereal::Event::DRIVER_ENCODE_IDX, DriverCam}, {cereal::Event::WIDE_ROAD_ENCODE_IDX, WideRoadCam}, }; - if ((e->which == cereal::Event::DRIVER_ENCODE_IDX && !(flags_ & REPLAY_FLAG_DCAM)) || - (e->which == cereal::Event::WIDE_ROAD_ENCODE_IDX && !(flags_ & REPLAY_FLAG_ECAM))) { + if ((e->which == cereal::Event::DRIVER_ENCODE_IDX && !hasFlag(REPLAY_FLAG_DCAM)) || + (e->which == cereal::Event::WIDE_ROAD_ENCODE_IDX && !hasFlag(REPLAY_FLAG_ECAM))) { return; } auto eidx = capnp::AnyStruct::Reader(e->event).getPointerSection()[0].getAs(); @@ -268,9 +332,7 @@ void Replay::publishFrame(const Event *e) { } void Replay::stream() { - float last_print = 0; cereal::Event::Which cur_which = cereal::Event::Which::INIT_DATA; - std::unique_lock lk(stream_lock_); while (true) { @@ -281,7 +343,7 @@ void Replay::stream() { Event cur_event(cur_which, cur_mono_time_); auto eit = std::upper_bound(events_->begin(), events_->end(), &cur_event, Event::lessThan()); if (eit == events_->end()) { - qDebug() << "waiting for events..."; + rInfo("waiting for events..."); continue; } @@ -292,12 +354,7 @@ void Replay::stream() { const Event *evt = (*eit); cur_which = evt->which; cur_mono_time_ = evt->mono_time; - const int current_ts = currentSeconds(); - if (last_print > current_ts || (current_ts - last_print) > 5.0) { - last_print = current_ts; - qInfo() << "at " << current_ts << "s"; - } - setCurrentSegment(current_ts / 60); + setCurrentSegment(toSeconds(cur_mono_time_) / 60); // migration for pandaState -> pandaStates to keep UI working for old segments if (cur_which == cereal::Event::Which::PANDA_STATE_D_E_P_R_E_C_A_T_E_D) { @@ -318,25 +375,30 @@ void Replay::stream() { // reset start times evt_start_ts = cur_mono_time_; loop_start_ts = nanos_since_boot(); - } else if (behind_ns > 0) { + } else if (behind_ns > 0 && !hasFlag(REPLAY_FLAG_FULL_SPEED)) { precise_nano_sleep(behind_ns); } - if (evt->frame) { - publishFrame(evt); - } else { + if (!evt->frame) { publishMessage(evt); + } else if (camera_server_) { + if (hasFlag(REPLAY_FLAG_FULL_SPEED)) { + camera_server_->waitFinish(); + } + publishFrame(evt); } } } // wait for frame to be sent before unlock.(frameReader may be deleted after unlock) - camera_server_->waitFinish(); + if (camera_server_) { + camera_server_->waitFinish(); + } - if (eit == events_->end() && !(flags_ & REPLAY_FLAG_NO_LOOP)) { + if (eit == events_->end() && !hasFlag(REPLAY_FLAG_NO_LOOP)) { int last_segment = segments_.rbegin()->first; if (current_segment_ >= last_segment && isSegmentMerged(last_segment)) { - qInfo() << "reaches the end of route, restart from beginning"; - emit seekTo(0, false); + rInfo("reaches the end of route, restart from beginning"); + QMetaObject::invokeMethod(this, std::bind(&Replay::seekTo, this, 0, false), Qt::QueuedConnection); } } } diff --git a/selfdrive/ui/replay/replay.h b/selfdrive/ui/replay/replay.h index a3e6efaad..d20d5bb92 100644 --- a/selfdrive/ui/replay/replay.h +++ b/selfdrive/ui/replay/replay.h @@ -1,5 +1,7 @@ #pragma once +#include + #include #include "selfdrive/ui/replay/camera.h" @@ -17,8 +19,17 @@ enum REPLAY_FLAGS { REPLAY_FLAG_QCAMERA = 0x0040, REPLAY_FLAG_SEND_YUV = 0x0080, REPLAY_FLAG_NO_CUDA = 0x0100, + REPLAY_FLAG_FULL_SPEED = 0x0200, + REPLAY_FLAG_NO_VIPC = 0x0400, }; +enum class FindFlag { + nextEngagement, + nextDisEngagement +}; + +enum class TimelineType { None, Engaged, AlertInfo, AlertWarning, AlertCritical }; + class Replay : public QObject { Q_OBJECT @@ -30,27 +41,40 @@ public: void start(int seconds = 0); void stop(); void pause(bool pause); - bool isPaused() const { return paused_; } + void seekToFlag(FindFlag flag); + void seekTo(int seconds, bool relative); + inline bool isPaused() const { return paused_; } + inline bool hasFlag(REPLAY_FLAGS flag) const { return flags_ & flag; } + inline void addFlag(REPLAY_FLAGS flag) { flags_ |= flag; } + inline void removeFlag(REPLAY_FLAGS flag) { flags_ &= ~flag; } + inline const Route* route() const { return route_.get(); } + inline int currentSeconds() const { return (cur_mono_time_ - route_start_ts_) / 1e9; } + inline int toSeconds(uint64_t mono_time) const { return (mono_time - route_start_ts_) / 1e9; } + inline int totalSeconds() const { return segments_.size() * 60; } + inline const std::string &carFingerprint() const { return car_fingerprint_; } + inline const std::vector> getTimeline() { + std::lock_guard lk(timeline_lock); + return timeline; + } signals: - void segmentChanged(); - void seekTo(int seconds, bool relative); + void streamStarted(); protected slots: - void queueSegment(); - void doSeek(int seconds, bool relative); void segmentLoadFinished(bool sucess); protected: typedef std::map> SegmentMap; + std::optional find(FindFlag flag); void startStream(const Segment *cur_segment); void stream(); void setCurrentSegment(int n); + void queueSegment(); void mergeSegments(const SegmentMap::iterator &begin, const SegmentMap::iterator &end); void updateEvents(const std::function& lambda); void publishMessage(const Event *e); void publishFrame(const Event *e); - inline int currentSeconds() const { return (cur_mono_time_ - route_start_ts_) / 1e9; } + void buildTimeline(); inline bool isSegmentMerged(int n) { return std::find(segments_merged_.begin(), segments_merged_.end(), n) != segments_merged_.end(); } @@ -64,7 +88,7 @@ protected: std::atomic current_segment_ = 0; SegmentMap segments_; // the following variables must be protected with stream_lock_ - bool exit_ = false; + std::atomic exit_ = false; bool paused_ = false; bool events_updated_ = false; uint64_t route_start_ts_ = 0; @@ -79,5 +103,10 @@ protected: std::vector sockets_; std::unique_ptr route_; std::unique_ptr camera_server_; - uint32_t flags_ = REPLAY_FLAG_NONE; + std::atomic flags_ = REPLAY_FLAG_NONE; + + std::mutex timeline_lock; + QFuture timeline_future; + std::vector> timeline; + std::string car_fingerprint_; }; diff --git a/selfdrive/ui/replay/route.cc b/selfdrive/ui/replay/route.cc index 23c27073c..e6a617714 100644 --- a/selfdrive/ui/replay/route.cc +++ b/selfdrive/ui/replay/route.cc @@ -26,7 +26,7 @@ RouteIdentifier Route::parseRoute(const QString &str) { bool Route::load() { if (route_.str.isEmpty()) { - qInfo() << "invalid route format"; + rInfo("invalid route format"); return false; } return data_dir_.isEmpty() ? loadFromServer() : loadFromLocal(); @@ -91,16 +91,16 @@ void Route::addFileToSegment(int n, const QString &file) { Segment::Segment(int n, const SegmentFile &files, uint32_t flags) : seg_num(n), flags(flags) { // [RoadCam, DriverCam, WideRoadCam, log]. fallback to qcamera/qlog - const QString file_list[] = { + const std::array file_list = { (flags & REPLAY_FLAG_QCAMERA) || files.road_cam.isEmpty() ? files.qcamera : files.road_cam, flags & REPLAY_FLAG_DCAM ? files.driver_cam : "", flags & REPLAY_FLAG_ECAM ? files.wide_road_cam : "", files.rlog.isEmpty() ? files.qlog : files.rlog, }; - for (int i = 0; i < std::size(file_list); i++) { - if (!file_list[i].isEmpty()) { - loading_++; - synchronizer_.addFuture(QtConcurrent::run([=] { loadFile(i, file_list[i].toStdString()); })); + for (int i = 0; i < file_list.size(); ++i) { + if (!file_list[i].isEmpty() && (!(flags & REPLAY_FLAG_NO_VIPC) || i >= MAX_CAMERAS)) { + ++loading_; + synchronizer_.addFuture(QtConcurrent::run(this, &Segment::loadFile, i, file_list[i].toStdString())); } } } diff --git a/selfdrive/ui/replay/route.h b/selfdrive/ui/replay/route.h index c39eef7d9..ac8fba75c 100644 --- a/selfdrive/ui/replay/route.h +++ b/selfdrive/ui/replay/route.h @@ -27,6 +27,7 @@ public: Route(const QString &route, const QString &data_dir = {}); bool load(); inline const QString &name() const { return route_.str; } + inline const QString &dir() const { return data_dir_; } inline const RouteIdentifier &identifier() const { return route_; } inline const std::map &segments() const { return segments_; } inline const SegmentFile &at(int n) { return segments_.at(n); } diff --git a/selfdrive/ui/replay/util.cc b/selfdrive/ui/replay/util.cc index d6791465f..5f06a6c83 100644 --- a/selfdrive/ui/replay/util.cc +++ b/selfdrive/ui/replay/util.cc @@ -15,15 +15,49 @@ #include "selfdrive/common/timing.h" #include "selfdrive/common/util.h" -namespace { +ReplayMessageHandler message_handler = nullptr; +DownloadProgressHandler download_progress_handler = nullptr; -static std::atomic enable_http_logging = false; +void installMessageHandler(ReplayMessageHandler handler) { message_handler = handler; } +void installDownloadProgressHandler(DownloadProgressHandler handler) { download_progress_handler = handler; } + +void logMessage(ReplyMsgType type, const char *fmt, ...) { + static std::mutex lock; + std::lock_guard lk(lock); + + char *msg_buf = nullptr; + va_list args; + va_start(args, fmt); + int ret = vasprintf(&msg_buf, fmt, args); + va_end(args); + if (ret <= 0 || !msg_buf) return; + + if (message_handler) { + message_handler(type, msg_buf); + } else { + if (type == ReplyMsgType::Debug) { + std::cout << "\033[38;5;248m" << msg_buf << "\033[00m" << std::endl; + } else if (type == ReplyMsgType::Warning) { + std::cout << "\033[38;5;227m" << msg_buf << "\033[00m" << std::endl; + } else if (type == ReplyMsgType::Critical) { + std::cout << "\033[38;5;196m" << msg_buf << "\033[00m" << std::endl; + } else { + std::cout << msg_buf << std::endl; + } + } + + free(msg_buf); +} + +namespace { struct CURLGlobalInitializer { CURLGlobalInitializer() { curl_global_init(CURL_GLOBAL_DEFAULT); } ~CURLGlobalInitializer() { curl_global_cleanup(); } }; +static CURLGlobalInitializer curl_initializer; + template struct MultiPartWriter { T *buf; @@ -56,6 +90,38 @@ size_t write_cb(char *data, size_t size, size_t count, void *userp) { size_t dumy_write_cb(char *data, size_t size, size_t count, void *userp) { return size * count; } +struct DownloadStats { + void add(const std::string &url, uint64_t total_bytes) { + std::lock_guard lk(lock); + items[url] = {0, total_bytes}; + } + + void remove(const std::string &url) { + std::lock_guard lk(lock); + items.erase(url); + } + + void update(const std::string &url, uint64_t downloaded, bool success = true) { + std::lock_guard lk(lock); + items[url].first = downloaded; + + auto stat = std::accumulate(items.begin(), items.end(), std::pair{}, [=](auto &a, auto &b){ + return std::pair{a.first + b.second.first, a.second + b.second.second}; + }); + double tm = millis_since_boot(); + if (download_progress_handler && ((tm - prev_tm) > 500 || !success || stat.first >= stat.second)) { + download_progress_handler(stat.first, stat.second, success); + prev_tm = tm; + } + } + + std::mutex lock; + std::map> items; + double prev_tm = 0; +}; + +} // namespace + std::string formattedDataSize(size_t size) { if (size < 1024) { return std::to_string(size) + " B"; @@ -66,9 +132,7 @@ std::string formattedDataSize(size_t size) { } } -} // namespace - -size_t getRemoteFileSize(const std::string &url) { +size_t getRemoteFileSize(const std::string &url, std::atomic *abort) { CURL *curl = curl_easy_init(); if (!curl) return -1; @@ -76,14 +140,20 @@ size_t getRemoteFileSize(const std::string &url) { curl_easy_setopt(curl, CURLOPT_WRITEFUNCTION, dumy_write_cb); curl_easy_setopt(curl, CURLOPT_HEADER, 1); curl_easy_setopt(curl, CURLOPT_NOBODY, 1); - CURLcode res = curl_easy_perform(curl); - double content_length = -1; - if (res == CURLE_OK) { - curl_easy_getinfo(curl, CURLINFO_CONTENT_LENGTH_DOWNLOAD, &content_length); - } else { - std::cout << "Download failed: error code: " << res << std::endl; + + CURLM *cm = curl_multi_init(); + curl_multi_add_handle(cm, curl); + int still_running = 1; + while (still_running > 0 && !(abort && *abort)) { + CURLMcode mc = curl_multi_perform(cm, &still_running); + if (!mc) curl_multi_wait(cm, nullptr, 0, 1000, nullptr); } + + double content_length = -1; + curl_easy_getinfo(curl, CURLINFO_CONTENT_LENGTH_DOWNLOAD, &content_length); + curl_multi_remove_handle(cm, curl); curl_easy_cleanup(curl); + curl_multi_cleanup(cm); return content_length > 0 ? (size_t)content_length : 0; } @@ -92,13 +162,10 @@ std::string getUrlWithoutQuery(const std::string &url) { return (idx == std::string::npos ? url : url.substr(0, idx)); } -void enableHttpLogging(bool enable) { - enable_http_logging = enable; -} - template bool httpDownload(const std::string &url, T &buf, size_t chunk_size, size_t content_length, std::atomic *abort) { - static CURLGlobalInitializer curl_initializer; + static DownloadStats download_stats; + download_stats.add(url, content_length); int parts = 1; if (chunk_size > 0 && content_length > 10 * 1024 * 1024) { @@ -129,23 +196,11 @@ bool httpDownload(const std::string &url, T &buf, size_t chunk_size, size_t cont curl_multi_add_handle(cm, eh); } - size_t prev_written = 0; - double last_print = millis_since_boot(); int still_running = 1; while (still_running > 0 && !(abort && *abort)) { curl_multi_wait(cm, nullptr, 0, 1000, nullptr); curl_multi_perform(cm, &still_running); - - if (enable_http_logging) { - if (double ts = millis_since_boot(); (ts - last_print) > 2 * 1000) { - size_t average = (written - prev_written) / ((ts - last_print) / 1000.); - int progress = std::min(100, 100.0 * (double)written / (double)content_length); - std::cout << "downloading " << getUrlWithoutQuery(url) << " - " << progress - << "% (" << formattedDataSize(average) << "/s)" << std::endl; - last_print = ts; - prev_written = written; - } - } + download_stats.update(url, written); } CURLMsg *msg; @@ -159,25 +214,29 @@ bool httpDownload(const std::string &url, T &buf, size_t chunk_size, size_t cont if (res_status == 206) { complete++; } else { - std::cout << "Download failed: http error code: " << res_status << std::endl; + rWarning("Download failed: http error code: %d", res_status); } } else { - std::cout << "Download failed: connection failure: " << msg->data.result << std::endl; + rWarning("Download failed: connection failure: %d", msg->data.result); } } } + bool success = complete == parts; + download_stats.update(url, written, success); + download_stats.remove(url); + for (const auto &[e, w] : writers) { curl_multi_remove_handle(cm, e); curl_easy_cleanup(e); } curl_multi_cleanup(cm); - return complete == parts; + return success; } std::string httpGet(const std::string &url, size_t chunk_size, std::atomic *abort) { - size_t size = getRemoteFileSize(url); + size_t size = getRemoteFileSize(url, abort); if (size == 0) return {}; std::string result(size, '\0'); @@ -185,7 +244,7 @@ std::string httpGet(const std::string &url, size_t chunk_size, std::atomic } bool httpDownload(const std::string &url, const std::string &file, size_t chunk_size, std::atomic *abort) { - size_t size = getRemoteFileSize(url); + size_t size = getRemoteFileSize(url, abort); if (size == 0) return false; std::ofstream of(file, std::ios::binary | std::ios::out); @@ -193,11 +252,11 @@ bool httpDownload(const std::string &url, const std::string &file, size_t chunk_ return httpDownload(url, of, chunk_size, size, abort); } -std::string decompressBZ2(const std::string &in) { - return decompressBZ2((std::byte *)in.data(), in.size()); +std::string decompressBZ2(const std::string &in, std::atomic *abort) { + return decompressBZ2((std::byte *)in.data(), in.size(), abort); } -std::string decompressBZ2(const std::byte *in, size_t in_size) { +std::string decompressBZ2(const std::byte *in, size_t in_size, std::atomic *abort) { if (in_size == 0) return {}; bz_stream strm = {}; @@ -216,17 +275,17 @@ std::string decompressBZ2(const std::byte *in, size_t in_size) { if (bzerror == BZ_OK && prev_write_pos == strm.next_out) { // content is corrupt bzerror = BZ_STREAM_END; - std::cout << "decompressBZ2 error : content is corrupt" << std::endl; + rWarning("decompressBZ2 error : content is corrupt"); break; } if (bzerror == BZ_OK && strm.avail_in > 0 && strm.avail_out == 0) { out.resize(out.size() * 2); } - } while (bzerror == BZ_OK); + } while (bzerror == BZ_OK && !(abort && *abort)); BZ2_bzDecompressEnd(&strm); - if (bzerror == BZ_STREAM_END) { + if (bzerror == BZ_STREAM_END && !(abort && *abort)) { out.resize(strm.total_out_lo32); return out; } diff --git a/selfdrive/ui/replay/util.h b/selfdrive/ui/replay/util.h index 726e65cb9..6c808095e 100644 --- a/selfdrive/ui/replay/util.h +++ b/selfdrive/ui/replay/util.h @@ -1,14 +1,34 @@ #pragma once #include +#include #include +enum class ReplyMsgType { + Info, + Debug, + Warning, + Critical +}; + +typedef std::function ReplayMessageHandler; +void installMessageHandler(ReplayMessageHandler); +void logMessage(ReplyMsgType type, const char* fmt, ...); + +#define rInfo(fmt, ...) ::logMessage(ReplyMsgType::Info, fmt, ## __VA_ARGS__) +#define rDebug(fmt, ...) ::logMessage(ReplyMsgType::Debug, fmt, ## __VA_ARGS__) +#define rWarning(fmt, ...) ::logMessage(ReplyMsgType::Warning, fmt, ## __VA_ARGS__) +#define rError(fmt, ...) ::logMessage(ReplyMsgType::Critical , fmt, ## __VA_ARGS__) + std::string sha256(const std::string &str); void precise_nano_sleep(long sleep_ns); -std::string decompressBZ2(const std::string &in); -std::string decompressBZ2(const std::byte *in, size_t in_size); -void enableHttpLogging(bool enable); +std::string decompressBZ2(const std::string &in, std::atomic *abort = nullptr); +std::string decompressBZ2(const std::byte *in, size_t in_size, std::atomic *abort = nullptr); std::string getUrlWithoutQuery(const std::string &url); -size_t getRemoteFileSize(const std::string &url); +size_t getRemoteFileSize(const std::string &url, std::atomic *abort = nullptr); std::string httpGet(const std::string &url, size_t chunk_size = 0, std::atomic *abort = nullptr); + +typedef std::function DownloadProgressHandler; +void installDownloadProgressHandler(DownloadProgressHandler); bool httpDownload(const std::string &url, const std::string &file, size_t chunk_size = 0, std::atomic *abort = nullptr); +std::string formattedDataSize(size_t size); diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc index 38c08eb48..bbdd6d4f3 100644 --- a/selfdrive/ui/ui.cc +++ b/selfdrive/ui/ui.cc @@ -3,6 +3,8 @@ #include #include +#include + #include "common/transformations/orientation.hpp" #include "selfdrive/common/params.h" #include "selfdrive/common/swaglog.h" @@ -36,17 +38,17 @@ static bool calib_frame_to_full_frame(const UIState *s, float in_x, float in_y, static int get_path_length_idx(const cereal::ModelDataV2::XYZTData::Reader &line, const float path_height) { const auto line_x = line.getX(); int max_idx = 0; - for (int i = 0; i < TRAJECTORY_SIZE && line_x[i] < path_height; ++i) { + for (int i = 1; i < TRAJECTORY_SIZE && line_x[i] <= path_height; ++i) { max_idx = i; } return max_idx; } -static void update_leads(UIState *s, const cereal::RadarState::Reader &radar_state, std::optional line) { +static void update_leads(UIState *s, const cereal::RadarState::Reader &radar_state, const cereal::ModelDataV2::XYZTData::Reader &line) { for (int i = 0; i < 2; ++i) { auto lead_data = (i == 0) ? radar_state.getLeadOne() : radar_state.getLeadTwo(); if (lead_data.getStatus()) { - float z = line ? (*line).getZ()[get_path_length_idx(*line, lead_data.getDRel())] : 0.0; + float z = line.getZ()[get_path_length_idx(line, lead_data.getDRel())]; calib_frame_to_full_frame(s, lead_data.getDRel(), -lead_data.getYRel(), z + 1.22, &s->scene.lead_vertices[i]); } } @@ -107,18 +109,7 @@ static void update_state(UIState *s) { SubMaster &sm = *(s->sm); UIScene &scene = s->scene; - if (sm.updated("modelV2")) { - update_model(s, sm["modelV2"].getModelV2()); - } - if (sm.updated("radarState")) { - std::optional line; - if (sm.rcv_frame("modelV2") > 0) { - line = sm["modelV2"].getModelV2().getPosition(); - } - update_leads(s, sm["radarState"].getRadarState(), line); - } if (sm.updated("liveCalibration")) { - scene.world_objects_visible = true; auto rpy_list = sm["liveCalibration"].getLiveCalibration().getRpyCalib(); Eigen::Vector3d rpy; rpy << rpy_list[0], rpy_list[1], rpy_list[2]; @@ -134,6 +125,14 @@ static void update_state(UIState *s) { } } } + if (s->worldObjectsVisible()) { + if (sm.updated("modelV2")) { + update_model(s, sm["modelV2"].getModelV2()); + } + if (sm.updated("radarState") && sm.rcv_frame("modelV2") > s->scene.started_frame) { + update_leads(s, sm["radarState"].getRadarState(), sm["modelV2"].getModelV2().getPosition()); + } + } if (sm.updated("pandaStates")) { auto pandaStates = sm["pandaStates"].getPandaStates(); if (pandaStates.size() > 0) { @@ -167,16 +166,22 @@ static void update_state(UIState *s) { } } } - if (sm.updated("roadCameraState")) { + if (!Hardware::TICI() && sm.updated("roadCameraState")) { auto camera_state = sm["roadCameraState"].getRoadCameraState(); float max_lines = Hardware::EON() ? 5408 : 1904; float max_gain = Hardware::EON() ? 1.0: 10.0; float max_ev = max_lines * max_gain; - if (Hardware::TICI()) { - max_ev /= 6; - } + float ev = camera_state.getGain() * float(camera_state.getIntegLines()); + + scene.light_sensor = std::clamp(1.0 - (ev / max_ev), 0.0, 1.0); + } else if (Hardware::TICI() && sm.updated("wideRoadCameraState")) { + auto camera_state = sm["wideRoadCameraState"].getWideRoadCameraState(); + + float max_lines = 1904; + float max_gain = 10.0; + float max_ev = max_lines * max_gain / 6; float ev = camera_state.getGain() * float(camera_state.getIntegLines()); @@ -189,68 +194,65 @@ void ui_update_params(UIState *s) { s->scene.is_metric = Params().getBool("IsMetric"); } -static void update_status(UIState *s) { - if (s->scene.started && s->sm->updated("controlsState")) { - auto controls_state = (*s->sm)["controlsState"].getControlsState(); +void UIState::updateStatus() { + if (scene.started && sm->updated("controlsState")) { + auto controls_state = (*sm)["controlsState"].getControlsState(); auto alert_status = controls_state.getAlertStatus(); if (alert_status == cereal::ControlsState::AlertStatus::USER_PROMPT) { - s->status = STATUS_WARNING; + status = STATUS_WARNING; } else if (alert_status == cereal::ControlsState::AlertStatus::CRITICAL) { - s->status = STATUS_ALERT; + status = STATUS_ALERT; } else { - s->status = controls_state.getEnabled() ? STATUS_ENGAGED : STATUS_DISENGAGED; + status = controls_state.getEnabled() ? STATUS_ENGAGED : STATUS_DISENGAGED; } } // Handle onroad/offroad transition - static bool started_prev = false; - if (s->scene.started != started_prev) { - if (s->scene.started) { - s->status = STATUS_DISENGAGED; - s->scene.started_frame = s->sm->frame; - s->scene.end_to_end = Params().getBool("EndToEndToggle"); - s->wide_camera = Hardware::TICI() ? Params().getBool("EnableWideCamera") : false; + if (scene.started != started_prev || sm->frame == 1) { + if (scene.started) { + status = STATUS_DISENGAGED; + scene.started_frame = sm->frame; + scene.end_to_end = Params().getBool("EndToEndToggle"); + wide_camera = Hardware::TICI() ? Params().getBool("EnableWideCamera") : false; } - // Invisible until we receive a calibration message. - s->scene.world_objects_visible = false; + started_prev = scene.started; + emit offroadTransition(!scene.started); } - started_prev = s->scene.started; } - -QUIState::QUIState(QObject *parent) : QObject(parent) { - ui_state.sm = std::make_unique>({ +UIState::UIState(QObject *parent) : QObject(parent) { + sm = std::make_unique>({ "modelV2", "controlsState", "liveCalibration", "radarState", "deviceState", "roadCameraState", "pandaStates", "carParams", "driverMonitoringState", "sensorEvents", "carState", "liveLocationKalman", + "wideRoadCameraState", }); Params params; - ui_state.wide_camera = Hardware::TICI() ? params.getBool("EnableWideCamera") : false; - ui_state.has_prime = params.getBool("HasPrime"); + wide_camera = Hardware::TICI() ? params.getBool("EnableWideCamera") : false; + prime_type = std::atoi(params.get("PrimeType").c_str()); // update timer timer = new QTimer(this); - QObject::connect(timer, &QTimer::timeout, this, &QUIState::update); + QObject::connect(timer, &QTimer::timeout, this, &UIState::update); timer->start(1000 / UI_FREQ); } -void QUIState::update() { - update_sockets(&ui_state); - update_state(&ui_state); - update_status(&ui_state); +void UIState::update() { + update_sockets(this); + update_state(this); + updateStatus(); - if (ui_state.scene.started != started_prev || ui_state.sm->frame == 1) { - started_prev = ui_state.scene.started; - emit offroadTransition(!ui_state.scene.started); - } - - if (ui_state.sm->frame % UI_FREQ == 0) { + if (sm->frame % UI_FREQ == 0) { watchdog_kick(); } - emit uiUpdate(ui_state); + emit uiUpdate(*this); } Device::Device(QObject *parent) : brightness_filter(BACKLIGHT_OFFROAD, BACKLIGHT_TS, BACKLIGHT_DT), QObject(parent) { + setAwake(true); + resetInteractiveTimout(); + + QObject::connect(uiState(), &UIState::uiUpdate, this, &Device::update); } void Device::update(const UIState &s) { @@ -258,20 +260,20 @@ void Device::update(const UIState &s) { updateWakefulness(s); // TODO: remove from UIState and use signals - QUIState::ui_state.awake = awake; + uiState()->awake = awake; } -void Device::setAwake(bool on, bool reset) { +void Device::setAwake(bool on) { if (on != awake) { awake = on; Hardware::set_display_power(awake); LOGD("setting display power %d", awake); emit displayPowerChanged(awake); } +} - if (reset) { - awake_timeout = 30 * UI_FREQ; - } +void Device::resetInteractiveTimout() { + interactive_timeout = (ignition_on ? 10 : 30) * UI_FREQ; } void Device::updateBrightness(const UIState &s) { @@ -297,23 +299,40 @@ void Device::updateBrightness(const UIState &s) { } if (brightness != last_brightness) { - std::thread{Hardware::set_brightness, brightness}.detach(); + if (!brightness_future.isRunning()) { + brightness_future = QtConcurrent::run(Hardware::set_brightness, brightness); + last_brightness = brightness; + } } - last_brightness = brightness; +} + +bool Device::motionTriggered(const UIState &s) { + static float accel_prev = 0; + static float gyro_prev = 0; + + bool accel_trigger = abs(s.scene.accel_sensor - accel_prev) > 0.2; + bool gyro_trigger = abs(s.scene.gyro_sensor - gyro_prev) > 0.15; + + gyro_prev = s.scene.gyro_sensor; + accel_prev = (accel_prev * (accel_samples - 1) + s.scene.accel_sensor) / accel_samples; + + return (!awake && accel_trigger && gyro_trigger); } void Device::updateWakefulness(const UIState &s) { - awake_timeout = std::max(awake_timeout - 1, 0); + bool ignition_just_turned_off = !s.scene.ignition && ignition_on; + ignition_on = s.scene.ignition; - bool should_wake = s.scene.started || s.scene.ignition; - if (!should_wake) { - // tap detection while display is off - bool accel_trigger = abs(s.scene.accel_sensor - accel_prev) > 0.2; - bool gyro_trigger = abs(s.scene.gyro_sensor - gyro_prev) > 0.15; - should_wake = accel_trigger && gyro_trigger; - gyro_prev = s.scene.gyro_sensor; - accel_prev = (accel_prev * (accel_samples - 1) + s.scene.accel_sensor) / accel_samples; + if (ignition_just_turned_off || motionTriggered(s)) { + resetInteractiveTimout(); + } else if (interactive_timeout > 0 && --interactive_timeout == 0) { + emit interactiveTimout(); } - setAwake(awake_timeout, should_wake); + setAwake(s.scene.ignition || interactive_timeout > 0); +} + +UIState *uiState() { + static UIState ui_state; + return &ui_state; } diff --git a/selfdrive/ui/ui.h b/selfdrive/ui/ui.h index 4b4ef0bb2..382a7df5e 100644 --- a/selfdrive/ui/ui.h +++ b/selfdrive/ui/ui.h @@ -7,6 +7,7 @@ #include #include #include +#include #include #include "cereal/messaging/messaging.h" @@ -32,29 +33,38 @@ struct Alert { QString type; cereal::ControlsState::AlertSize size; AudibleAlert sound; + bool equal(const Alert &a2) { return text1 == a2.text1 && text2 == a2.text2 && type == a2.type && sound == a2.sound; } static Alert get(const SubMaster &sm, uint64_t started_frame) { + const cereal::ControlsState::Reader &cs = sm["controlsState"].getControlsState(); if (sm.updated("controlsState")) { - const cereal::ControlsState::Reader &cs = sm["controlsState"].getControlsState(); return {cs.getAlertText1().cStr(), cs.getAlertText2().cStr(), cs.getAlertType().cStr(), cs.getAlertSize(), cs.getAlertSound()}; } else if ((sm.frame - started_frame) > 5 * UI_FREQ) { const int CONTROLS_TIMEOUT = 5; + const int controls_missing = (nanos_since_boot() - sm.rcv_time("controlsState")) / 1e9; + // Handle controls timeout if (sm.rcv_frame("controlsState") < started_frame) { // car is started, but controlsState hasn't been seen at all return {"openpilot Unavailable", "Waiting for controls to start", "controlsWaiting", cereal::ControlsState::AlertSize::MID, AudibleAlert::NONE}; - } else if ((nanos_since_boot() - sm.rcv_time("controlsState")) / 1e9 > CONTROLS_TIMEOUT) { + } else if (controls_missing > CONTROLS_TIMEOUT) { // car is started, but controls is lagging or died - return {"TAKE CONTROL IMMEDIATELY", "Controls Unresponsive", - "controlsUnresponsive", cereal::ControlsState::AlertSize::FULL, - AudibleAlert::WARNING_IMMEDIATE}; + if (cs.getEnabled() && (controls_missing - CONTROLS_TIMEOUT) < 10) { + return {"TAKE CONTROL IMMEDIATELY", "Controls Unresponsive", + "controlsUnresponsive", cereal::ControlsState::AlertSize::FULL, + AudibleAlert::WARNING_IMMEDIATE}; + } else { + return {"Controls Unresponsive", "Reboot Device", + "controlsUnresponsivePermanent", cereal::ControlsState::AlertSize::MID, + AudibleAlert::NONE}; + } } } return {}; @@ -82,8 +92,6 @@ typedef struct { typedef struct UIScene { mat3 view_from_calib; - bool world_objects_visible; - cereal::PandaState::PandaType pandaType; // modelV2 @@ -101,7 +109,19 @@ typedef struct UIScene { uint64_t started_frame; } UIScene; -typedef struct UIState { +class UIState : public QObject { + Q_OBJECT + +public: + UIState(QObject* parent = 0); + void updateStatus(); + inline bool worldObjectsVisible() const { + return sm->rcv_frame("liveCalibration") > scene.started_frame; + }; + inline bool engaged() const { + return scene.started && (*sm)["controlsState"].getControlsState().getEnabled(); + }; + int fb_w = 0, fb_h = 0; std::unique_ptr sm; @@ -110,21 +130,10 @@ typedef struct UIState { UIScene scene = {}; bool awake; - bool has_prime = false; + int prime_type = 0; QTransform car_space_transform; bool wide_camera; -} UIState; - - -class QUIState : public QObject { - Q_OBJECT - -public: - QUIState(QObject* parent = 0); - - // TODO: get rid of this, only use signal - inline static UIState ui_state = {0}; signals: void uiUpdate(const UIState &s); @@ -135,9 +144,10 @@ private slots: private: QTimer *timer; - bool started_prev = true; + bool started_prev = false; }; +UIState *uiState(); // device management class @@ -152,22 +162,23 @@ private: const float accel_samples = 5*UI_FREQ; bool awake = false; - int awake_timeout = 0; - float accel_prev = 0; - float gyro_prev = 0; + int interactive_timeout = 0; + bool ignition_on = false; int last_brightness = 0; FirstOrderFilter brightness_filter; - - QTimer *timer; + QFuture brightness_future; void updateBrightness(const UIState &s); void updateWakefulness(const UIState &s); + bool motionTriggered(const UIState &s); + void setAwake(bool on); signals: void displayPowerChanged(bool on); + void interactiveTimout(); public slots: - void setAwake(bool on, bool reset); + void resetInteractiveTimout(); void update(const UIState &s); }; diff --git a/selfdrive/updated.py b/selfdrive/updated.py index 2acebf2a4..1a8779861 100755 --- a/selfdrive/updated.py +++ b/selfdrive/updated.py @@ -40,7 +40,7 @@ from common.params import Params from selfdrive.hardware import EON, TICI, HARDWARE from selfdrive.swaglog import cloudlog from selfdrive.controls.lib.alertmanager import set_offroad_alert -from selfdrive.version import get_tested_branch +from selfdrive.version import is_tested_branch LOCK_FILE = os.getenv("UPDATER_LOCK_FILE", "/tmp/safe_staging_overlay.lock") STAGING_ROOT = os.getenv("UPDATER_STAGING_ROOT", "/data/safe_staging") @@ -142,7 +142,7 @@ def set_params(new_version: bool, failed_count: int, exception: Optional[str]) - now = datetime.datetime.utcnow() dt = now - last_update if failed_count > 15 and exception is not None: - if get_tested_branch(): + if is_tested_branch(): extra_text = "Ensure the software is correctly installed" else: extra_text = exception @@ -342,7 +342,7 @@ def fetch_update(wait_helper: WaitTimeHelper) -> bool: new_version = cur_hash != upstream_hash git_fetch_result = check_git_fetch_result(git_fetch_output) - cloudlog.info("comparing %s to %s" % (cur_hash, upstream_hash)) + cloudlog.info(f"comparing {cur_hash} to {upstream_hash}") if new_version or git_fetch_result: cloudlog.info("Running update") @@ -370,7 +370,7 @@ def fetch_update(wait_helper: WaitTimeHelper) -> bool: return new_version -def main(): +def main() -> None: params = Params() if params.get_bool("DisableUpdates"): @@ -380,7 +380,7 @@ def main(): ov_lock_fd = open(LOCK_FILE, 'w') try: fcntl.flock(ov_lock_fd, fcntl.LOCK_EX | fcntl.LOCK_NB) - except IOError as e: + except OSError as e: raise RuntimeError("couldn't get overlay lock; is another instance running?") from e # Set low io priority @@ -400,7 +400,7 @@ def main(): overlay_init.unlink(missing_ok=True) first_run = True - last_fetch_time = 0 + last_fetch_time = 0.0 update_failed_count = 0 # Set initial params for offroad alerts diff --git a/selfdrive/version.py b/selfdrive/version.py index 2ddfc93c6..f2570cd30 100644 --- a/selfdrive/version.py +++ b/selfdrive/version.py @@ -7,7 +7,6 @@ from functools import lru_cache from common.basedir import BASEDIR from selfdrive.swaglog import cloudlog - TESTED_BRANCHES = ['devel', 'release2-staging', 'release3-staging', 'dashcam-staging', 'release2', 'release3', 'dashcam'] training_version: bytes = b"0.2.0" @@ -54,20 +53,34 @@ def get_origin(default: Optional[str] = None) -> Optional[str]: return run_cmd_default(["git", "config", "--get", "remote.origin.url"], default=default) +@cache +def get_normalized_origin(default: Optional[str] = None) -> Optional[str]: + return get_origin()\ + .replace("git@", "", 1)\ + .replace(".git", "", 1)\ + .replace("https://", "", 1)\ + .replace(":", "/", 1) + + @cache def get_version() -> str: with open(os.path.join(os.path.dirname(os.path.abspath(__file__)), "common", "version.h")) as _versionf: version = _versionf.read().split('"')[1] return version +@cache +def get_short_version() -> str: + return get_version().split('-')[0] @cache -def get_prebuilt() -> bool: +def is_prebuilt() -> bool: return os.path.exists(os.path.join(BASEDIR, 'prebuilt')) @cache -def get_comma_remote() -> bool: +def is_comma_remote() -> bool: + # note to fork maintainers, this is used for release metrics. please do not + # touch this to get rid of the orange startup alert. there's better ways to do that origin = get_origin() if origin is None: return False @@ -76,12 +89,12 @@ def get_comma_remote() -> bool: @cache -def get_tested_branch() -> bool: +def is_tested_branch() -> bool: return get_short_branch() in TESTED_BRANCHES @cache -def get_dirty() -> bool: +def is_dirty() -> bool: origin = get_origin() branch = get_branch() if (origin is None) or (branch is None): @@ -90,7 +103,7 @@ def get_dirty() -> bool: dirty = False try: # Actually check dirty files - if not get_prebuilt(): + if not is_prebuilt(): # This is needed otherwise touched files might show up as modified try: subprocess.check_call(["git", "update-index", "--refresh"]) @@ -98,19 +111,6 @@ def get_dirty() -> bool: pass dirty = (subprocess.call(["git", "diff-index", "--quiet", branch, "--"]) != 0) - - # Log dirty files - if dirty and get_comma_remote(): - try: - dirty_files = run_cmd(["git", "diff-index", branch, "--"]) - cloudlog.event("dirty comma branch", version=get_version(), dirty=dirty, origin=origin, branch=branch, - dirty_files=dirty_files, commit=get_commit(), origin_commit=get_commit(branch)) - except subprocess.CalledProcessError: - pass - - dirty = dirty or (not get_comma_remote()) - dirty = dirty or ('master' in branch) - except subprocess.CalledProcessError: cloudlog.exception("git subprocess failed while checking dirty") dirty = True @@ -125,9 +125,11 @@ if __name__ == "__main__": params.put("TermsVersion", terms_version) params.put("TrainingVersion", training_version) - print("Dirty: %s" % get_dirty()) - print("Version: %s" % get_version()) - print("Origin: %s" % get_origin()) - print("Branch: %s" % get_branch()) - print("Short branch: %s" % get_short_branch()) - print("Prebuilt: %s" % get_prebuilt()) + print(f"Dirty: {is_dirty()}") + print(f"Version: {get_version()}") + print(f"Short version: {get_short_version()}") + print(f"Origin: {get_origin()}") + print(f"Normalized origin: {get_normalized_origin()}") + print(f"Branch: {get_branch()}") + print(f"Short branch: {get_short_branch()}") + print(f"Prebuilt: {is_prebuilt()}") diff --git a/tools/lib/auth.py b/tools/lib/auth.py index d5d2a60bb..0e9e7705b 100755 --- a/tools/lib/auth.py +++ b/tools/lib/auth.py @@ -109,7 +109,7 @@ def login(method): if 'code' in web_server.query_params: break elif 'error' in web_server.query_params: - print('Authentication Error: "%s". Description: "%s" ' % ( + print('Authentication Error: "{}". Description: "{}" '.format( web_server.query_params['error'], web_server.query_params.get('error_description')), file=sys.stderr) break diff --git a/tools/lib/bootlog.py b/tools/lib/bootlog.py new file mode 100644 index 000000000..dc1cf35c5 --- /dev/null +++ b/tools/lib/bootlog.py @@ -0,0 +1,48 @@ +import datetime +import functools +import re + +from tools.lib.auth_config import get_token +from tools.lib.api import CommaApi +from tools.lib.helpers import RE, timestamp_to_datetime + + +@functools.total_ordering +class Bootlog: + def __init__(self, url: str): + self._url = url + + r = re.search(RE.BOOTLOG_NAME, url) + if not r: + raise Exception(f"Unable to parse: {url}") + + self._dongle_id = r.group('dongle_id') + self._timestamp = r.group('timestamp') + + @property + def url(self) -> str: + return self._url + + @property + def dongle_id(self) -> str: + return self._dongle_id + + @property + def timestamp(self) -> str: + return self._timestamp + + @property + def datetime(self) -> datetime.datetime: + return timestamp_to_datetime(self._timestamp) + + def __eq__(self, b) -> bool: + return self.datetime == b.datetime + + def __lt__(self, b) -> bool: + return self.datetime < b.datetime + + +def get_bootlogs(dongle_id: str): + api = CommaApi(get_token()) + r = api.get(f'v1/devices/{dongle_id}/bootlogs') + return [Bootlog(b) for b in r] diff --git a/tools/lib/filereader.py b/tools/lib/filereader.py index 3d4c46b22..4ea9ad429 100644 --- a/tools/lib/filereader.py +++ b/tools/lib/filereader.py @@ -1,6 +1,11 @@ +import os from tools.lib.url_file import URLFile +DATA_ENDPOINT = os.getenv("DATA_ENDPOINT", "http://data-raw.internal/") + def FileReader(fn, debug=False): + if fn.startswith("cd:/"): + fn = fn.replace("cd:/", DATA_ENDPOINT) if fn.startswith("http://") or fn.startswith("https://"): return URLFile(fn, debug=debug) return open(fn, "rb") diff --git a/tools/lib/framereader.py b/tools/lib/framereader.py index db07c2017..bdf48bb43 100644 --- a/tools/lib/framereader.py +++ b/tools/lib/framereader.py @@ -17,10 +17,7 @@ from tools.lib.cache import cache_path_for_file_path from tools.lib.exceptions import DataUnreadableError from common.file_helpers import atomic_write_in_dir -try: - from xx.chffr.lib.filereader import FileReader -except ImportError: - from tools.lib.filereader import FileReader +from tools.lib.filereader import FileReader HEVC_SLICE_B = 0 HEVC_SLICE_P = 1 @@ -50,7 +47,7 @@ def fingerprint_video(fn): with FileReader(fn) as f: header = f.read(4) if len(header) == 0: - raise DataUnreadableError("%s is empty" % fn) + raise DataUnreadableError(f"{fn} is empty") elif header == b"\x00\xc0\x12\x00": return FrameType.raw elif header == b"\x00\x00\x00\x01": @@ -90,7 +87,7 @@ def vidindex(fn, typ): try: subprocess.check_call([vidindex, typ, fn, prefix_f.name, index_f.name]) except subprocess.CalledProcessError: - raise DataUnreadableError("vidindex failed on file %s" % fn) + raise DataUnreadableError(f"vidindex failed on file {fn}") with open(index_f.name, "rb") as f: index = f.read() with open(prefix_f.name, "rb") as f: @@ -308,7 +305,7 @@ class RawFrameReader(BaseFrameReader): assert num+count <= self.frame_count if pix_fmt not in ("yuv420p", "rgb24"): - raise ValueError("Unsupported pixel format %r" % pix_fmt) + raise ValueError(f"Unsupported pixel format {pix_fmt!r}") app = [] for i in range(num, num+count): @@ -548,10 +545,10 @@ class GOPFrameReader(BaseFrameReader): assert self.frame_count is not None if num + count > self.frame_count: - raise ValueError("{} > {}".format(num + count, self.frame_count)) + raise ValueError(f"{num + count} > {self.frame_count}") if pix_fmt not in ("yuv420p", "rgb24", "yuv444p"): - raise ValueError("Unsupported pixel format %r" % pix_fmt) + raise ValueError(f"Unsupported pixel format {pix_fmt!r}") ret = [self._get_one(num + i, pix_fmt) for i in range(count)] @@ -572,15 +569,13 @@ class StreamFrameReader(StreamGOPReader, GOPFrameReader): def GOPFrameIterator(gop_reader, pix_fmt): dec = VideoStreamDecompressor(gop_reader.fn, gop_reader.vid_fmt, gop_reader.w, gop_reader.h, pix_fmt) - for frame in dec.read(): - yield frame + yield from dec.read() def FrameIterator(fn, pix_fmt, **kwargs): fr = FrameReader(fn, **kwargs) if isinstance(fr, GOPReader): - for v in GOPFrameIterator(fr, pix_fmt): - yield v + yield from GOPFrameIterator(fr, pix_fmt) else: for i in range(fr.frame_count): yield fr.get(i, pix_fmt=pix_fmt)[0] diff --git a/tools/lib/helpers.py b/tools/lib/helpers.py new file mode 100644 index 000000000..efe704b9e --- /dev/null +++ b/tools/lib/helpers.py @@ -0,0 +1,20 @@ +import datetime + +TIME_FMT = "%Y-%m-%d--%H-%M-%S" + +# regex patterns +class RE: + DONGLE_ID = r'(?P[a-z0-9]{16})' + TIMESTAMP = r'(?P[0-9]{4}-[0-9]{2}-[0-9]{2}--[0-9]{2}-[0-9]{2}-[0-9]{2})' + ROUTE_NAME = r'{}[|_/]{}'.format(DONGLE_ID, TIMESTAMP) + SEGMENT_NAME = r'{}(?:--|/)(?P[0-9]+)'.format(ROUTE_NAME) + BOOTLOG_NAME = ROUTE_NAME + + EXPLORER_FILE = r'^(?P{})--(?P[a-z]+\.[a-z0-9]+)$'.format(SEGMENT_NAME) + OP_SEGMENT_DIR = r'^(?P{})$'.format(SEGMENT_NAME) + +def timestamp_to_datetime(t: str) -> datetime.datetime: + """ + Convert an openpilot route timestamp to a python datetime + """ + return datetime.datetime.strptime(t, TIME_FMT) diff --git a/tools/lib/logreader.py b/tools/lib/logreader.py index 1c9cc81e3..c8d506b4b 100755 --- a/tools/lib/logreader.py +++ b/tools/lib/logreader.py @@ -5,17 +5,14 @@ import bz2 import urllib.parse import capnp -try: - from xx.chffr.lib.filereader import FileReader -except ImportError: - from tools.lib.filereader import FileReader +from tools.lib.filereader import FileReader from cereal import log as capnp_log # this is an iterator itself, and uses private variables from LogReader -class MultiLogIterator(object): - def __init__(self, log_paths, wraparound=False): +class MultiLogIterator: + def __init__(self, log_paths, sort_by_time=False): self._log_paths = log_paths - self._wraparound = wraparound + self.sort_by_time = sort_by_time self._first_log_idx = next(i for i in range(len(log_paths)) if log_paths[i] is not None) self._current_log = self._first_log_idx @@ -26,7 +23,7 @@ class MultiLogIterator(object): def _log_reader(self, i): if self._log_readers[i] is None and self._log_paths[i] is not None: log_path = self._log_paths[i] - self._log_readers[i] = LogReader(log_path) + self._log_readers[i] = LogReader(log_path, sort_by_time=self.sort_by_time) return self._log_readers[i] @@ -41,12 +38,8 @@ class MultiLogIterator(object): self._idx = 0 self._current_log = next(i for i in range(self._current_log + 1, len(self._log_readers) + 1) if i == len(self._log_readers) or self._log_paths[i] is not None) - # wraparound if self._current_log == len(self._log_readers): - if self._wraparound: - self._current_log = self._first_log_idx - else: - raise StopIteration + raise StopIteration def __next__(self): while 1: @@ -74,8 +67,8 @@ class MultiLogIterator(object): return True -class LogReader(object): - def __init__(self, fn, canonicalize=True, only_union_types=False): +class LogReader: + def __init__(self, fn, canonicalize=True, only_union_types=False, sort_by_time=False): data_version = None _, ext = os.path.splitext(urllib.parse.urlparse(fn).path) with FileReader(fn) as f: @@ -90,7 +83,7 @@ class LogReader(object): else: raise Exception(f"unknown extension {ext}") - self._ents = list(ents) + self._ents = list(sorted(ents, key=lambda x: x.logMonoTime) if sort_by_time else ents) self._ts = [x.logMonoTime for x in self._ents] self.data_version = data_version self._only_union_types = only_union_types @@ -112,6 +105,6 @@ if __name__ == "__main__": # below line catches those errors and replaces the bytes with \x__ codecs.register_error("strict", codecs.backslashreplace_errors) log_path = sys.argv[1] - lr = LogReader(log_path) + lr = LogReader(log_path, sort_by_time=True) for msg in lr: print(msg) diff --git a/tools/lib/robust_logreader.py b/tools/lib/robust_logreader.py index e534a7c8f..c7feb6c3e 100755 --- a/tools/lib/robust_logreader.py +++ b/tools/lib/robust_logreader.py @@ -13,7 +13,7 @@ from cereal import log as capnp_log class RobustLogReader(LogReader): - def __init__(self, fn, canonicalize=True, only_union_types=False): # pylint: disable=super-init-not-called + def __init__(self, fn, canonicalize=True, only_union_types=False, sort_by_time=False): # pylint: disable=super-init-not-called data_version = None _, ext = os.path.splitext(urllib.parse.urlparse(fn).path) with FileReader(fn) as f: @@ -45,7 +45,7 @@ class RobustLogReader(LogReader): while True: try: ents = capnp_log.Event.read_multiple_bytes(dat) - self._ents = list(ents) + self._ents = list(sorted(ents, key=lambda x: x.logMonoTime) if sort_by_time else ents) break except capnp.lib.capnp.KjException: if progress is None: diff --git a/tools/lib/route.py b/tools/lib/route.py index 8c03cd9cc..8092096a0 100644 --- a/tools/lib/route.py +++ b/tools/lib/route.py @@ -6,10 +6,7 @@ from itertools import chain from tools.lib.auth_config import get_token from tools.lib.api import CommaApi - -SEGMENT_NAME_RE = r'[a-z0-9]{16}[|_][0-9]{4}-[0-9]{2}-[0-9]{2}--[0-9]{2}-[0-9]{2}-[0-9]{2}--[0-9]+' -EXPLORER_FILE_RE = r'^({})--([a-z]+\.[a-z0-9]+)$'.format(SEGMENT_NAME_RE) -OP_SEGMENT_DIR_RE = r'^({})$'.format(SEGMENT_NAME_RE) +from tools.lib.helpers import RE QLOG_FILENAMES = ['qlog.bz2'] QCAMERA_FILENAMES = ['qcamera.ts'] @@ -18,48 +15,52 @@ CAMERA_FILENAMES = ['fcamera.hevc', 'video.hevc'] DCAMERA_FILENAMES = ['dcamera.hevc'] ECAMERA_FILENAMES = ['ecamera.hevc'] -class Route(object): - def __init__(self, route_name, data_dir=None): +class Route: + def __init__(self, name, data_dir=None): + self._name = RouteName(name) self.files = None - self.route_name = route_name.replace('_', '|') if data_dir is not None: self._segments = self._get_segments_local(data_dir) else: self._segments = self._get_segments_remote() - self.max_seg_number = self._segments[-1].canonical_name.segment_num + self.max_seg_number = self._segments[-1].name.segment_num + + @property + def name(self): + return self._name @property def segments(self): return self._segments def log_paths(self): - log_path_by_seg_num = {s.canonical_name.segment_num: s.log_path for s in self._segments} + log_path_by_seg_num = {s.name.segment_num: s.log_path for s in self._segments} return [log_path_by_seg_num.get(i, None) for i in range(self.max_seg_number+1)] def qlog_paths(self): - qlog_path_by_seg_num = {s.canonical_name.segment_num: s.qlog_path for s in self._segments} + qlog_path_by_seg_num = {s.name.segment_num: s.qlog_path for s in self._segments} return [qlog_path_by_seg_num.get(i, None) for i in range(self.max_seg_number+1)] def camera_paths(self): - camera_path_by_seg_num = {s.canonical_name.segment_num: s.camera_path for s in self._segments} + camera_path_by_seg_num = {s.name.segment_num: s.camera_path for s in self._segments} return [camera_path_by_seg_num.get(i, None) for i in range(self.max_seg_number+1)] def dcamera_paths(self): - dcamera_path_by_seg_num = {s.canonical_name.segment_num: s.dcamera_path for s in self._segments} + dcamera_path_by_seg_num = {s.name.segment_num: s.dcamera_path for s in self._segments} return [dcamera_path_by_seg_num.get(i, None) for i in range(self.max_seg_number+1)] def ecamera_paths(self): - ecamera_path_by_seg_num = {s.canonical_name.segment_num: s.ecamera_path for s in self._segments} + ecamera_path_by_seg_num = {s.name.segment_num: s.ecamera_path for s in self._segments} return [ecamera_path_by_seg_num.get(i, None) for i in range(self.max_seg_number+1)] def qcamera_paths(self): - qcamera_path_by_seg_num = {s.canonical_name.segment_num: s.qcamera_path for s in self._segments} + qcamera_path_by_seg_num = {s.name.segment_num: s.qcamera_path for s in self._segments} return [qcamera_path_by_seg_num.get(i, None) for i in range(self.max_seg_number+1)] # TODO: refactor this, it's super repetitive def _get_segments_remote(self): api = CommaApi(get_token()) - route_files = api.get('v1/route/' + self.route_name + '/files') + route_files = api.get('v1/route/' + self.name.canonical_name + '/files') self.files = list(chain.from_iterable(route_files.values())) segments = {} @@ -67,7 +68,7 @@ class Route(object): _, dongle_id, time_str, segment_num, fn = urlparse(url).path.rsplit('/', maxsplit=4) segment_name = f'{dongle_id}|{time_str}--{segment_num}' if segments.get(segment_name): - segments[segment_name] = RouteSegment( + segments[segment_name] = Segment( segment_name, url if fn in LOG_FILENAMES else segments[segment_name].log_path, url if fn in QLOG_FILENAMES else segments[segment_name].qlog_path, @@ -77,7 +78,7 @@ class Route(object): url if fn in QCAMERA_FILENAMES else segments[segment_name].qcamera_path, ) else: - segments[segment_name] = RouteSegment( + segments[segment_name] = Segment( segment_name, url if fn in LOG_FILENAMES else None, url if fn in QLOG_FILENAMES else None, @@ -87,7 +88,7 @@ class Route(object): url if fn in QCAMERA_FILENAMES else None, ) - return sorted(segments.values(), key=lambda seg: seg.canonical_name.segment_num) + return sorted(segments.values(), key=lambda seg: seg.name.segment_num) def _get_segments_local(self, data_dir): files = os.listdir(data_dir) @@ -95,24 +96,25 @@ class Route(object): for f in files: fullpath = os.path.join(data_dir, f) - explorer_match = re.match(EXPLORER_FILE_RE, f) - op_match = re.match(OP_SEGMENT_DIR_RE, f) + explorer_match = re.match(RE.EXPLORER_FILE, f) + op_match = re.match(RE.OP_SEGMENT_DIR, f) if explorer_match: - segment_name, fn = explorer_match.groups() - if segment_name.replace('_', '|').startswith(self.route_name): + segment_name = explorer_match.group('segment_name') + fn = explorer_match.group('file_name') + if segment_name.replace('_', '|').startswith(self.name.canonical_name): segment_files[segment_name].append((fullpath, fn)) elif op_match and os.path.isdir(fullpath): - segment_name, = op_match.groups() - if segment_name.startswith(self.route_name): + segment_name = op_match.group('segment_name') + if segment_name.startswith(self.name.canonical_name): for seg_f in os.listdir(fullpath): segment_files[segment_name].append((os.path.join(fullpath, seg_f), seg_f)) - elif f == self.route_name: + elif f == self.name.canonical_name: for seg_num in os.listdir(fullpath): if not seg_num.isdigit(): continue - segment_name = '{}--{}'.format(self.route_name, seg_num) + segment_name = f'{self.name.canonical_name}--{seg_num}' for seg_f in os.listdir(os.path.join(fullpath, seg_num)): segment_files[segment_name].append((os.path.join(fullpath, seg_num, seg_f), seg_f)) @@ -149,15 +151,15 @@ class Route(object): except StopIteration: qcamera_path = None - segments.append(RouteSegment(segment, log_path, qlog_path, camera_path, dcamera_path, ecamera_path, qcamera_path)) + segments.append(Segment(segment, log_path, qlog_path, camera_path, dcamera_path, ecamera_path, qcamera_path)) if len(segments) == 0: - raise ValueError('Could not find segments for route {} in data directory {}'.format(self.route_name, data_dir)) - return sorted(segments, key=lambda seg: seg.canonical_name.segment_num) + raise ValueError(f'Could not find segments for route {self.name.canonical_name} in data directory {data_dir}') + return sorted(segments, key=lambda seg: seg.name.segment_num) -class RouteSegment(object): +class Segment: def __init__(self, name, log_path, qlog_path, camera_path, dcamera_path, ecamera_path, qcamera_path): - self._name = RouteSegmentName(name) + self._name = SegmentName(name) self.log_path = log_path self.qlog_path = qlog_path self.camera_path = camera_path @@ -167,21 +169,55 @@ class RouteSegment(object): @property def name(self): - return str(self._name) - - @property - def canonical_name(self): return self._name -class RouteSegmentName(object): - def __init__(self, name_str): - self._segment_name_str = name_str - self._route_name_str, num_str = self._segment_name_str.rsplit("--", 1) - self._num = int(num_str) +class RouteName: + def __init__(self, name_str: str): + self._name_str = name_str + delim = next(c for c in self._name_str if c in ("|", "/")) + self._dongle_id, self._time_str = self._name_str.split(delim) + + assert len(self._dongle_id) == 16, self._name_str + assert len(self._time_str) == 20, self._name_str + self._canonical_name = f"{self._dongle_id}|{self._time_str}" @property - def segment_num(self): - return self._num + def canonical_name(self) -> str: return self._canonical_name - def __str__(self): - return self._segment_name_str + @property + def dongle_id(self) -> str: return self._dongle_id + + @property + def time_str(self) -> str: return self._time_str + + def __str__(self) -> str: return self._canonical_name + +class SegmentName: + # TODO: add constructor that takes dongle_id, time_str, segment_num and then create instances + # of this class instead of manually constructing a segment name (use canonical_name prop instead) + def __init__(self, name_str: str, allow_route_name=False): + self._name_str = name_str + seg_num_delim = "--" if self._name_str.count("--") == 2 else "/" + name_parts = self._name_str.rsplit(seg_num_delim, 1) + if allow_route_name and len(name_parts) == 1: + name_parts.append("-1") # no segment number + self._route_name = RouteName(name_parts[0]) + self._num = int(name_parts[1]) + self._canonical_name = f"{self._route_name._dongle_id}|{self._route_name._time_str}--{self._num}" + + @property + def canonical_name(self) -> str: return self._canonical_name + + @property + def dongle_id(self) -> str: return self._route_name.dongle_id + + @property + def time_str(self) -> str: return self._route_name.time_str + + @property + def segment_num(self) -> int: return self._num + + @property + def route_name(self) -> RouteName: return self._route_name + + def __str__(self) -> str: return self._canonical_name diff --git a/tools/lib/url_file.py b/tools/lib/url_file.py index 2161770d0..8ad2f96b3 100644 --- a/tools/lib/url_file.py +++ b/tools/lib/url_file.py @@ -22,7 +22,7 @@ def hash_256(link): return hsh -class URLFile(object): +class URLFile: _tlocal = threading.local() def __init__(self, url, debug=False, cache=None): @@ -70,7 +70,7 @@ class URLFile(object): return self._length file_length_path = os.path.join(CACHE_DIR, hash_256(self._url) + "_length") if os.path.exists(file_length_path) and not self._force_download: - with open(file_length_path, "r") as file_length: + with open(file_length_path) as file_length: content = file_length.read() self._length = int(content) return self._length @@ -156,7 +156,7 @@ class URLFile(object): if self._debug: t2 = time.time() if t2 - t1 > 0.1: - print("get %s %r %.f slow" % (self._url, headers, t2 - t1)) + print(f"get {self._url} {headers!r} {t2 - t1:.f} slow") response_code = c.getinfo(pycurl.RESPONSE_CODE) if response_code == 416: # Requested Range Not Satisfiable