diff --git a/Jenkinsfile b/Jenkinsfile
index 97633da80..778d8f3e5 100644
--- a/Jenkinsfile
+++ b/Jenkinsfile
@@ -36,7 +36,7 @@ EOF"""
def phone_steps(String device_type, steps) {
lock(resource: "", label: device_type, inversePrecedence: true, variable: 'device_ip', quantity: 1) {
- timeout(time: 90, unit: 'MINUTES') {
+ timeout(time: 150, unit: 'MINUTES') {
phone(device_ip, "git checkout", readFile("selfdrive/test/setup_device_ci.sh"),)
steps.each { item ->
phone(device_ip, item[0], item[1])
@@ -52,7 +52,7 @@ pipeline {
TEST_DIR = "/data/openpilot"
}
options {
- timeout(time: 1, unit: 'HOURS')
+ timeout(time: 3, unit: 'HOURS')
}
stages {
@@ -78,7 +78,7 @@ pipeline {
when {
not {
anyOf {
- branch 'master-ci'; branch 'devel'; branch 'devel-staging'; branch 'release2'; branch 'release2-staging'; branch 'dashcam'; branch 'dashcam-staging'; branch 'testing-closet*'
+ branch 'master-ci'; branch 'devel'; branch 'devel-staging'; branch 'release2'; branch 'release2-staging'; branch 'dashcam'; branch 'dashcam-staging'; branch 'testing-closet*'; branch 'hotfix-*'
}
}
}
@@ -127,7 +127,7 @@ pipeline {
stage('Devel Tests') {
steps {
phone_steps("eon-build", [
- ["build devel", "cd release && SCONS_CACHE=1 DEVEL_TEST=1 ./build_devel.sh"],
+ ["build devel", "cd release && DEVEL_TEST=1 ./build_devel.sh"],
["test manager", "python selfdrive/manager/test/test_manager.py"],
["onroad tests", "cd selfdrive/test/ && ./test_onroad.py"],
["test car interfaces", "cd selfdrive/car/tests/ && ./test_car_interfaces.py"],
@@ -138,8 +138,8 @@ pipeline {
stage('Replay Tests') {
steps {
phone_steps("eon2", [
- ["build QCOM_REPLAY", "SCONS_CACHE=1 QCOM_REPLAY=1 scons -j4"],
- ["camerad/modeld replay", "cd selfdrive/test/process_replay && ./camera_replay.py"],
+ ["build", "cd selfdrive/manager && ./build.py"],
+ ["model replay", "cd selfdrive/test/process_replay && ./model_replay.py"],
])
}
}
@@ -147,7 +147,7 @@ pipeline {
stage('HW + Unit Tests') {
steps {
phone_steps("eon", [
- ["build", "SCONS_CACHE=1 scons -j4"],
+ ["build", "cd selfdrive/manager && ./build.py"],
["test athena", "nosetests -s selfdrive/athena/tests/test_athenad_old.py"],
["test sounds", "nosetests -s selfdrive/test/test_sounds.py"],
["test boardd loopback", "nosetests -s selfdrive/boardd/tests/test_boardd_loopback.py"],
@@ -166,7 +166,7 @@ pipeline {
timeout(time: 90, unit: 'MINUTES') {
sh script: "/home/batman/tools/zookeeper/enable_and_wait.py $device_ip 120", label: "turn on device"
phone(device_ip, "git checkout", readFile("selfdrive/test/setup_device_ci.sh"),)
- phone(device_ip, "build", "SCONS_CACHE=1 scons -j4 && sync")
+ phone(device_ip, "build", "scons -j4 && sync")
sh script: "/home/batman/tools/zookeeper/disable.py $device_ip", label: "turn off device"
sh script: "/home/batman/tools/zookeeper/enable_and_wait.py $device_ip 120", label: "turn on device"
sh script: "/home/batman/tools/zookeeper/check_consumption.py 60 3", label: "idle power consumption after boot"
@@ -186,7 +186,7 @@ pipeline {
}
steps {
phone_steps("tici", [
- ["build", "SCONS_CACHE=1 scons -j16"],
+ ["build", "cd selfdrive/manager && ./build.py"],
["test loggerd", "python selfdrive/loggerd/tests/test_loggerd.py"],
["test encoder", "LD_LIBRARY_PATH=/usr/local/lib python selfdrive/loggerd/tests/test_encoder.py"],
["onroad tests", "cd selfdrive/test/ && ./test_onroad.py"],
@@ -198,7 +198,7 @@ pipeline {
stage('camerad') {
steps {
phone_steps("eon-party", [
- ["build", "SCONS_CACHE=1 scons -j16"],
+ ["build", "cd selfdrive/manager && ./build.py"],
["test camerad", "python selfdrive/camerad/test/test_camerad.py"],
["test exposure", "python selfdrive/camerad/test/test_exposure.py"],
])
@@ -208,7 +208,7 @@ pipeline {
stage('Tici camerad') {
steps {
phone_steps("tici-party", [
- ["build", "SCONS_CACHE=1 scons -j16"],
+ ["build", "cd selfdrive/manager && ./build.py"],
["test camerad", "python selfdrive/camerad/test/test_camerad.py"],
["test exposure", "python selfdrive/camerad/test/test_exposure.py"],
])
diff --git a/README.md b/README.md
index 95a0897c1..e620273dc 100644
--- a/README.md
+++ b/README.md
@@ -97,7 +97,9 @@ Supported Cars
| Lexus | RX 2020-21 | All | openpilot | 0mph | 0mph |
| Lexus | RX Hybrid 2016-19 | All | Stock3| 0mph | 0mph |
| Lexus | RX Hybrid 2020 | All | openpilot | 0mph | 0mph |
+| Lexus | UX Hybrid 2019 | All | openpilot | 0mph | 0mph |
| Toyota | Avalon 2016-21 | TSS-P | Stock3| 20mph1 | 0mph |
+| Toyota | Avalon Hybrid 2019 | TSS-P | Stock3| 20mph1 | 0mph |
| Toyota | Camry 2018-20 | All | Stock | 0mph4 | 0mph |
| Toyota | Camry 2021 | All | openpilot | 0mph | 0mph |
| Toyota | Camry Hybrid 2018-20 | All | Stock | 0mph4 | 0mph |
@@ -133,8 +135,9 @@ Community Maintained Cars and Features
| Make | Model (US Market Reference) | Supported Package | ACC | No ACC accel below | No ALC below |
| ----------| ------------------------------| ------------------| -----------------| -------------------| -------------|
-| Audi | A3 2014-17 | Prestige | Stock | 0mph | 0mph |
+| Audi | A3 2014-18 | Prestige | Stock | 0mph | 0mph |
| Audi | A3 Sportback e-tron 2017-18 | Prestige | Stock | 0mph | 0mph |
+| Audi | Q2 2018 | Driver Assistance | Stock | 0mph | 0mph |
| Buick | Regal 20181 | Adaptive Cruise | openpilot | 0mph | 7mph |
| Cadillac | ATS 20181 | Adaptive Cruise | openpilot | 0mph | 7mph |
| Chevrolet | Malibu 20171 | Adaptive Cruise | openpilot | 0mph | 7mph |
@@ -148,7 +151,7 @@ Community Maintained Cars and Features
| 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 2017-19, 2021 | SCC + LKAS | Stock | 19mph | 34mph |
| 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 |
@@ -167,12 +170,14 @@ Community Maintained Cars and Features
| Kia | Sorento 2018-19 | SCC + LKAS | Stock | 0mph | 0mph |
| Kia | Stinger 2018 | SCC + LKAS | Stock | 0mph | 0mph |
| Kia | Ceed 2019 | SCC + LKAS | Stock | 0mph | 0mph |
-| Nissan | Altima 2020 | ProPILOT | Stock | 0mph | 0mph |
+| Nissan | Altima 2019-20 | ProPILOT | Stock | 0mph | 0mph |
| Nissan | Leaf 2018-20 | 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 | Kodiaq 2018 | Driver Assistance | Stock | 0mph | 0mph |
+| Škoda | Octavia 2015, 2019 | 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 |
diff --git a/RELEASES.md b/RELEASES.md
index bf764dd59..065c4ac5b 100644
--- a/RELEASES.md
+++ b/RELEASES.md
@@ -1,3 +1,18 @@
+Version 0.8.5 (2021-06-11)
+========================
+ * NEOS update: improved reliability and stability with better voltage regulator configuration
+ * Smart model-based Forward Collision Warning
+ * CAN-based fingerprinting moved behind community features toggle
+ * Improved longitudinal control on Toyotas with a comma pedal
+ * Improved auto-brightness using road-facing camera
+ * Added "Software" settings page with updater controls
+ * Audi Q2 2018 support thanks to jyoung8607!
+ * Hyundai Elantra 2021 support thanks to CruiseBrantley!
+ * Lexus UX Hybrid 2019-2020 support thanks to brianhaugen2!
+ * Toyota Avalon Hybrid 2019 support thanks to jbates9011!
+ * SEAT Leon 2017 & 2020 support thanks to jyoung8607!
+ * Škoda Octavia 2015 & 2019 support thanks to jyoung8607!
+
Version 0.8.4 (2021-05-17)
========================
* Delay controls start until system is ready
diff --git a/SConstruct b/SConstruct
index 138c6ab3f..6b7905bfc 100644
--- a/SConstruct
+++ b/SConstruct
@@ -37,6 +37,10 @@ AddOption('--mpc-generate',
action='store_true',
help='regenerates the mpc sources')
+AddOption('--snpe',
+ action='store_true',
+ help='use SNPE on PC')
+
AddOption('--external-sconscript',
action='store',
metavar='FILE',
@@ -51,7 +55,6 @@ if arch == "aarch64" and TICI:
arch = "larch64"
USE_WEBCAM = os.getenv("USE_WEBCAM") is not None
-QCOM_REPLAY = arch == "aarch64" and os.getenv("QCOM_REPLAY") is not None
lenv = {
"PATH": os.environ['PATH'],
@@ -98,10 +101,6 @@ if arch == "aarch64" or arch == "larch64":
cflags = ["-DQCOM", "-mcpu=cortex-a57"]
cxxflags = ["-DQCOM", "-mcpu=cortex-a57"]
rpath = []
-
- if QCOM_REPLAY:
- cflags += ["-DQCOM_REPLAY"]
- cxxflags += ["-DQCOM_REPLAY"]
else:
cflags = []
cxxflags = []
@@ -128,6 +127,7 @@ else:
libpath = [
"#phonelibs/snpe/x86_64-linux-clang",
"#phonelibs/libyuv/x64/lib",
+ "#phonelibs/mapbox-gl-native-qt/x86_64",
"#cereal",
"#selfdrive/common",
"/usr/lib",
@@ -190,6 +190,7 @@ env = Environment(
"#phonelibs/android_system_core/include",
"#phonelibs/linux/include",
"#phonelibs/snpe/include",
+ "#phonelibs/mapbox-gl-native-qt/include",
"#phonelibs/nanovg",
"#phonelibs/qrcode",
"#phonelibs",
@@ -222,15 +223,10 @@ env = Environment(
if GetOption('compile_db'):
env.CompilationDatabase('compile_commands.json')
-if os.environ.get('SCONS_CACHE'):
- cache_dir = '/tmp/scons_cache'
- if TICI:
- cache_dir = '/data/scons_cache'
-
- if QCOM_REPLAY:
- cache_dir = '/tmp/scons_cache_qcom_replay'
-
- CacheDir(cache_dir)
+# Setup cache dir
+cache_dir = '/data/scons_cache' if TICI else '/tmp/scons_cache'
+CacheDir(cache_dir)
+Clean(["."], cache_dir)
node_interval = 5
node_count = 0
@@ -272,7 +268,7 @@ Export('envCython')
# Qt build environment
qt_env = env.Clone()
-qt_modules = ["Widgets", "Gui", "Core", "Network", "Concurrent", "Multimedia", "Quick", "Qml", "QuickWidgets"]
+qt_modules = ["Widgets", "Gui", "Core", "Network", "Concurrent", "Multimedia", "Quick", "Qml", "QuickWidgets", "Location", "Positioning"]
if arch != "aarch64":
qt_modules += ["DBus"]
@@ -338,7 +334,7 @@ if GetOption("clazy"):
qt_env['ENV']['CLAZY_IGNORE_DIRS'] = qt_dirs[0]
qt_env['ENV']['CLAZY_CHECKS'] = ','.join(checks)
-Export('env', 'qt_env', 'arch', 'real_arch', 'SHARED', 'USE_WEBCAM', 'QCOM_REPLAY')
+Export('env', 'qt_env', 'arch', 'real_arch', 'SHARED', 'USE_WEBCAM')
# cereal and messaging are shared with the system
SConscript(['cereal/SConscript'])
diff --git a/cereal/SConscript b/cereal/SConscript
index a671aeecc..b3c8da9ae 100644
--- a/cereal/SConscript
+++ b/cereal/SConscript
@@ -1,4 +1,4 @@
-Import('env', 'envCython', 'arch', 'QCOM_REPLAY')
+Import('env', 'envCython', 'arch')
import shutil
@@ -54,7 +54,7 @@ vipc_sources = [
'visionipc/visionbuf.cc',
]
-if arch in ["aarch64", "larch64"] and (not QCOM_REPLAY):
+if arch in ["aarch64", "larch64"]:
vipc_sources += ['visionipc/visionbuf_ion.cc']
else:
vipc_sources += ['visionipc/visionbuf_cl.cc']
@@ -64,6 +64,8 @@ vipc = env.Library('visionipc', vipc_objects)
libs = envCython["LIBS"]+["OpenCL", "zmq", vipc, messaging_lib]
+if arch == "aarch64":
+ libs += ["adreno_utils"]
if arch == "Darwin":
del libs[libs.index('OpenCL')]
envCython['FRAMEWORKS'] += ['OpenCL']
diff --git a/cereal/car.capnp b/cereal/car.capnp
index c98928190..999c064f0 100644
--- a/cereal/car.capnp
+++ b/cereal/car.capnp
@@ -52,7 +52,7 @@ struct CarEvent @0x9b1657f34caf3ad3 {
manualRestart @30;
lowSpeedLockout @31;
plannerError @32;
- debugAlert @34;
+ joystickDebug @34;
steerTempUnavailableUserOverride @35;
resumeRequired @36;
preDriverDistracted @37;
@@ -90,6 +90,7 @@ struct CarEvent @0x9b1657f34caf3ad3 {
startupNoControl @77;
startupMaster @78;
startupFuzzyFingerprint @97;
+ startupNoFw @104;
fcw @79;
steerSaturated @80;
belowEngageSpeed @84;
@@ -103,6 +104,11 @@ struct CarEvent @0x9b1657f34caf3ad3 {
processNotRunning @95;
dashcamMode @96;
controlsInitializing @98;
+ usbError @99;
+ roadCameraError @100;
+ driverCameraError @101;
+ wideRoadCameraError @102;
+ localizerMalfunction @103;
radarCanErrorDEPRECATED @15;
radarCommIssueDEPRECATED @67;
@@ -147,7 +153,6 @@ struct CarState {
# brake pedal, 0.0-1.0
brake @5 :Float32; # this is user pedal only
brakePressed @6 :Bool; # this is user pedal only
- brakeLights @19 :Bool;
# steering wheel
steeringAngleDeg @7 :Float32;
@@ -241,6 +246,7 @@ struct CarState {
}
errorsDEPRECATED @0 :List(CarEvent.EventName);
+ brakeLightsDEPRECATED @19 :Bool;
}
# ******* radar state @ 20hz *******
@@ -361,6 +367,7 @@ struct CarParams {
enableDsu @5 :Bool; # driving support unit
enableApgs @6 :Bool; # advanced parking guidance system
enableBsm @56 :Bool; # blind spot monitoring
+ hasStockCamera @57 :Bool; # factory LKAS/LDW camera is present
minEnableSpeed @7 :Float32;
minSteerSpeed @8 :Float32;
@@ -512,6 +519,7 @@ struct CarParams {
automatic @1; # Traditional auto, including DSG
manual @2; # True "stick shift" only
direct @3; # Electric vehicle or other direct drive
+ cvt @4;
}
struct CarFw {
diff --git a/cereal/log.capnp b/cereal/log.capnp
index 41de42009..bd028f511 100644
--- a/cereal/log.capnp
+++ b/cereal/log.capnp
@@ -23,6 +23,7 @@ struct Map(Key, Value) {
struct InitData {
kernelArgs @0 :List(Text);
kernelVersion @15 :Text;
+ osVersion @18 :Text;
gctx @1 :Text;
dongleId @2 :Text;
@@ -280,6 +281,7 @@ struct DeviceState @0xa4d8b5af2aa492eb {
cpuUsagePercent @20 :Int8;
usbOnline @12 :Bool;
networkType @22 :NetworkType;
+ networkInfo @31 :NetworkInfo;
offroadPowerUsageUwh @23 :UInt32;
networkStrength @24 :NetworkStrength;
carBatteryCapacityUwh @25 :UInt32;
@@ -288,6 +290,8 @@ struct DeviceState @0xa4d8b5af2aa492eb {
started @11 :Bool;
startedMonoTime @13 :UInt64;
+ lastAthenaPingTime @32 :UInt64;
+
# power
batteryPercent @8 :Int16;
batteryStatus @9 :Text;
@@ -328,6 +332,15 @@ struct DeviceState @0xa4d8b5af2aa492eb {
great @4;
}
+ struct NetworkInfo {
+ technology @0 :Text;
+ operator @1 :Text;
+ band @2 :Text;
+ channel @3 :UInt16;
+ extra @4 :Text;
+ state @5 :Text;
+ }
+
# deprecated
cpu0DEPRECATED @0 :UInt16;
cpu1DEPRECATED @1 :UInt16;
@@ -361,6 +374,8 @@ struct PandaState @0xa7649e2575e4591e {
powerSaveEnabled @16 :Bool;
uptime @17 :UInt32;
faults @18 :List(FaultType);
+ harnessStatus @21 :HarnessStatus;
+ heartbeatLost @22 :Bool;
enum FaultStatus {
none @0;
@@ -411,6 +426,12 @@ struct PandaState @0xa7649e2575e4591e {
dcp @3;
}
+ enum HarnessStatus {
+ notConnected @0;
+ normal @1;
+ flipped @2;
+ }
+
startedSignalDetectedDEPRECATED @5 :Bool;
}
@@ -676,10 +697,24 @@ struct ModelDataV2 {
struct MetaData {
engagedProb @0 :Float32;
desirePrediction @1 :List(Float32);
- brakeDisengageProb @2 :Float32;
- gasDisengageProb @3 :Float32;
- steerOverrideProb @4 :Float32;
desireState @5 :List(Float32);
+ disengagePredictions @6 :DisengagePredictions;
+ hardBrakePredicted @7 :Bool;
+
+ # deprecated
+ brakeDisengageProbDEPRECATED @2 :Float32;
+ gasDisengageProbDEPRECATED @3 :Float32;
+ steerOverrideProbDEPRECATED @4 :Float32;
+ }
+
+ struct DisengagePredictions {
+ t @0 :List(Float32);
+ brakeDisengageProbs @1 :List(Float32);
+ gasDisengageProbs @2 :List(Float32);
+ steerOverrideProbs @3 :List(Float32);
+ brake3MetersPerSecondSquaredProbs @4 :List(Float32);
+ brake4MetersPerSecondSquaredProbs @5 :List(Float32);
+ brake5MetersPerSecondSquaredProbs @6 :List(Float32);
}
}
@@ -867,6 +902,8 @@ struct LiveLocationKalman {
gpsOK @19 :Bool = true;
sensorsOK @21 :Bool = true;
deviceStable @22 :Bool = true;
+ timeSinceReset @23 :Float64;
+ excessiveResets @24 :Bool;
enum Status {
uninitialized @0;
@@ -1250,6 +1287,7 @@ struct Sentinel {
startOfRoute @3;
}
type @0 :SentinelType;
+ signal @1 :Int32;
}
struct ManagerState {
diff --git a/cereal/messaging/messaging.h b/cereal/messaging/messaging.h
index 4acdbb484..8c0825bb2 100644
--- a/cereal/messaging/messaging.h
+++ b/cereal/messaging/messaging.h
@@ -66,13 +66,13 @@ public:
class SubMaster {
public:
- SubMaster(const std::initializer_list &service_list,
- const char *address = nullptr, const std::initializer_list &ignore_alive = {});
+ SubMaster(const std::vector &service_list,
+ const char *address = nullptr, const std::vector &ignore_alive = {});
void update(int timeout = 1000);
void update_msgs(uint64_t current_time, std::vector> messages);
- inline bool allAlive(const std::initializer_list &service_list = {}) { return all_(service_list, false, true); }
- inline bool allValid(const std::initializer_list &service_list = {}) { return all_(service_list, true, false); }
- inline bool allAliveAndValid(const std::initializer_list &service_list = {}) { return all_(service_list, true, true); }
+ inline bool allAlive(const std::vector &service_list = {}) { return all_(service_list, false, true); }
+ inline bool allValid(const std::vector &service_list = {}) { return all_(service_list, true, false); }
+ inline bool allAliveAndValid(const std::vector &service_list = {}) { return all_(service_list, true, true); }
void drain();
~SubMaster();
@@ -82,10 +82,10 @@ public:
bool valid(const char *name) const;
uint64_t rcv_frame(const char *name) const;
uint64_t rcv_time(const char *name) const;
- cereal::Event::Reader &operator[](const char *name);
+ cereal::Event::Reader &operator[](const char *name) const;
private:
- bool all_(const std::initializer_list &service_list, bool valid, bool alive);
+ bool all_(const std::vector &service_list, bool valid, bool alive);
Poller *poller_ = nullptr;
struct SubMessage;
std::map messages_;
@@ -117,7 +117,7 @@ private:
class PubMaster {
public:
- PubMaster(const std::initializer_list &service_list);
+ PubMaster(const std::vector &service_list);
inline int send(const char *name, capnp::byte *data, size_t size) { return sockets_.at(name)->send((char *)data, size); }
int send(const char *name, MessageBuilder &msg);
~PubMaster();
diff --git a/cereal/messaging/msgq.h b/cereal/messaging/msgq.h
index 301d5d1a3..90a20acdd 100644
--- a/cereal/messaging/msgq.h
+++ b/cereal/messaging/msgq.h
@@ -5,7 +5,7 @@
#include
#define DEFAULT_SEGMENT_SIZE (10 * 1024 * 1024)
-#define NUM_READERS 8
+#define NUM_READERS 10
#define ALIGN(n) ((n + (8 - 1)) & -8)
#define UNPACK64(higher, lower, input) do {uint64_t tmp = input; higher = tmp >> 32; lower = tmp & 0xFFFFFFFF;} while (0)
diff --git a/cereal/messaging/socketmaster.cc b/cereal/messaging/socketmaster.cc
index b10133e43..c88a033bf 100644
--- a/cereal/messaging/socketmaster.cc
+++ b/cereal/messaging/socketmaster.cc
@@ -2,6 +2,7 @@
#include
#include
#include
+#include
#include "services.h"
#include "messaging.h"
@@ -21,7 +22,7 @@ static const service *get_service(const char *name) {
return nullptr;
}
-static inline bool inList(const std::initializer_list &list, const char *value) {
+static inline bool inList(const std::vector &list, const char *value) {
for (auto &v : list) {
if (strcmp(value, v) == 0) return true;
}
@@ -30,11 +31,18 @@ static inline bool inList(const std::initializer_list &list, const
class MessageContext {
public:
- MessageContext() { ctx_ = Context::create(); }
+ MessageContext() : ctx_(nullptr) {};
~MessageContext() { delete ctx_; }
+ inline Context *context() {
+ std::call_once(init_flag, [=]() { ctx_ = Context::create(); });
+ return ctx_;
+ }
+private:
Context *ctx_;
+ std::once_flag init_flag;
};
-MessageContext ctx;
+
+MessageContext message_context;
struct SubMaster::SubMessage {
std::string name;
@@ -48,13 +56,13 @@ struct SubMaster::SubMessage {
cereal::Event::Reader event;
};
-SubMaster::SubMaster(const std::initializer_list &service_list, const char *address,
- const std::initializer_list &ignore_alive) {
+SubMaster::SubMaster(const std::vector &service_list, const char *address,
+ const std::vector &ignore_alive) {
poller_ = Poller::create();
for (auto name : service_list) {
const service *serv = get_service(name);
assert(serv != nullptr);
- SubSocket *socket = SubSocket::create(ctx.ctx_, name, address ? address : "127.0.0.1", true);
+ SubSocket *socket = SubSocket::create(message_context.context(), name, address ? address : "127.0.0.1", true);
assert(socket != 0);
poller_->registerSocket(socket);
SubMessage *m = new SubMessage{
@@ -63,6 +71,7 @@ SubMaster::SubMaster(const std::initializer_list &service_list, co
.freq = serv->frequency,
.ignore_alive = inList(ignore_alive, name),
.allocated_msg_reader = malloc(sizeof(capnp::FlatArrayMessageReader))};
+ m->msg_reader = new (m->allocated_msg_reader) capnp::FlatArrayMessageReader({});
messages_[socket] = m;
services_[name] = m;
}
@@ -82,9 +91,7 @@ void SubMaster::update(int timeout) {
SubMessage *m = messages_.at(s);
- if (m->msg_reader) {
- m->msg_reader->~FlatArrayMessageReader();
- }
+ m->msg_reader->~FlatArrayMessageReader();
m->msg_reader = new (m->allocated_msg_reader) capnp::FlatArrayMessageReader(m->aligned_buf.align(msg));
delete msg;
messages.push_back({m->name, m->msg_reader->getRoot()});
@@ -118,7 +125,7 @@ void SubMaster::update_msgs(uint64_t current_time, std::vector &service_list, bool valid, bool alive) {
+bool SubMaster::all_(const std::vector &service_list, bool valid, bool alive) {
int found = 0;
for (auto &kv : messages_) {
SubMessage *m = kv.second;
@@ -162,7 +169,7 @@ uint64_t SubMaster::rcv_time(const char *name) const {
return services_.at(name)->rcv_time;
}
-cereal::Event::Reader &SubMaster::operator[](const char *name) {
+cereal::Event::Reader &SubMaster::operator[](const char *name) const {
return services_.at(name)->event;
};
@@ -170,19 +177,17 @@ SubMaster::~SubMaster() {
delete poller_;
for (auto &kv : messages_) {
SubMessage *m = kv.second;
- if (m->msg_reader) {
- m->msg_reader->~FlatArrayMessageReader();
- }
+ m->msg_reader->~FlatArrayMessageReader();
free(m->allocated_msg_reader);
delete m->socket;
delete m;
}
}
-PubMaster::PubMaster(const std::initializer_list &service_list) {
+PubMaster::PubMaster(const std::vector &service_list) {
for (auto name : service_list) {
assert(get_service(name) != nullptr);
- PubSocket *socket = PubSocket::create(ctx.ctx_, name);
+ PubSocket *socket = PubSocket::create(message_context.context(), name);
assert(socket);
sockets_[name] = socket;
}
diff --git a/cereal/services.py b/cereal/services.py
old mode 100644
new mode 100755
index a30436bcd..bd89cfa31
--- a/cereal/services.py
+++ b/cereal/services.py
@@ -2,7 +2,7 @@
import os
from typing import Optional
-EON = os.path.isfile('/EON')
+TICI = os.path.isfile('/TICI')
RESERVED_PORT = 8022 # sshd
STARTING_PORT = 8001
@@ -55,10 +55,10 @@ services = {
"thumbnail": (True, 0.2, 1),
"carEvents": (True, 1., 1),
"carParams": (True, 0.02, 1),
- "driverCameraState": (True, 10. if EON else 20., 1),
- "driverEncodeIdx": (True, 10. if EON else 20., 1),
- "driverState": (True, 10. if EON else 20., 1),
- "driverMonitoringState": (True, 10. if EON else 20., 1),
+ "driverCameraState": (True, 10. if not TICI else 20., 1),
+ "driverEncodeIdx": (True, 10. if not TICI else 20., 1),
+ "driverState": (True, 10. if not TICI else 20., 1),
+ "driverMonitoringState": (True, 10. if not TICI else 20., 1),
"offroadLayout": (False, 0.),
"wideRoadEncodeIdx": (True, 20., 1),
"wideRoadCameraState": (True, 20., 1),
@@ -83,7 +83,7 @@ def build_header():
for k, v in service_list.items():
should_log = "true" if v.should_log else "false"
decimation = -1 if v.decimation is None else v.decimation
- h += ' { .name = "%s", .port = %d, .should_log = %s, .frequency = %d, .decimation = %d },\n' % \
+ h += ' { "%s", %d, %s, %d, %d },\n' % \
(k, v.port, should_log, v.frequency, decimation)
h += "};\n"
h += "#endif\n"
diff --git a/cereal/visionipc/visionbuf.cc b/cereal/visionipc/visionbuf.cc
index 64693b572..39c521913 100644
--- a/cereal/visionipc/visionbuf.cc
+++ b/cereal/visionipc/visionbuf.cc
@@ -15,7 +15,7 @@ extern "C" void compute_aligned_width_and_height(int width,
#endif
void visionbuf_compute_aligned_width_and_height(int width, int height, int *aligned_w, int *aligned_h) {
-#if defined(QCOM) && !defined(QCOM_REPLAY)
+#ifdef QCOM
compute_aligned_width_and_height(ALIGN(width, 32), ALIGN(height, 32), 3, 0, 0, 512, aligned_w, aligned_h);
#else
*aligned_w = width; *aligned_h = height;
diff --git a/common/params_pxd.pxd b/common/params_pxd.pxd
index b31a5ab70..80113c339 100644
--- a/common/params_pxd.pxd
+++ b/common/params_pxd.pxd
@@ -12,7 +12,8 @@ cdef extern from "selfdrive/common/params.h":
PERSISTENT
CLEAR_ON_MANAGER_START
CLEAR_ON_PANDA_DISCONNECT
- CLEAR_ON_IGNITION
+ CLEAR_ON_IGNITION_ON
+ CLEAR_ON_IGNITION_OFF
ALL
cdef cppclass Params:
diff --git a/common/params_pyx.pyx b/common/params_pyx.pyx
index dab8d20fa..e1ebf95eb 100755
--- a/common/params_pyx.pyx
+++ b/common/params_pyx.pyx
@@ -13,7 +13,8 @@ cdef class ParamKeyType:
PERSISTENT = c_ParamKeyType.PERSISTENT
CLEAR_ON_MANAGER_START = c_ParamKeyType.CLEAR_ON_MANAGER_START
CLEAR_ON_PANDA_DISCONNECT = c_ParamKeyType.CLEAR_ON_PANDA_DISCONNECT
- CLEAR_ON_IGNITION = c_ParamKeyType.CLEAR_ON_IGNITION
+ CLEAR_ON_IGNITION_ON = c_ParamKeyType.CLEAR_ON_IGNITION_ON
+ CLEAR_ON_IGNITION_OFF = c_ParamKeyType.CLEAR_ON_IGNITION_OFF
ALL = c_ParamKeyType.ALL
def ensure_bytes(v):
diff --git a/common/realtime.py b/common/realtime.py
index f702cd6d3..762410f09 100644
--- a/common/realtime.py
+++ b/common/realtime.py
@@ -3,6 +3,7 @@ import gc
import os
import time
import multiprocessing
+from typing import Optional
from common.clock import sec_since_boot # pylint: disable=no-name-in-module, import-error
from selfdrive.hardware import PC, TICI
@@ -31,49 +32,49 @@ class Priority:
CTRL_HIGH = 53
-def set_realtime_priority(level):
+def set_realtime_priority(level: int) -> None:
if not PC:
- os.sched_setscheduler(0, os.SCHED_FIFO, os.sched_param(level))
+ os.sched_setscheduler(0, os.SCHED_FIFO, os.sched_param(level)) # type: ignore[attr-defined]
-def set_core_affinity(core):
+def set_core_affinity(core: int) -> None:
if not PC:
os.sched_setaffinity(0, [core,])
-def config_realtime_process(core, priority):
+def config_realtime_process(core: int, priority: int) -> None:
gc.disable()
set_realtime_priority(priority)
set_core_affinity(core)
-class Ratekeeper():
- def __init__(self, rate, print_delay_threshold=0.):
+class Ratekeeper:
+ def __init__(self, rate: int, print_delay_threshold: Optional[float] = 0.0) -> None:
"""Rate in Hz for ratekeeping. print_delay_threshold must be nonnegative."""
self._interval = 1. / rate
self._next_frame_time = sec_since_boot() + self._interval
self._print_delay_threshold = print_delay_threshold
self._frame = 0
- self._remaining = 0
+ self._remaining = 0.0
self._process_name = multiprocessing.current_process().name
@property
- def frame(self):
+ def frame(self) -> int:
return self._frame
@property
- def remaining(self):
+ def remaining(self) -> float:
return self._remaining
# Maintain loop rate by calling this at the end of each loop
- def keep_time(self):
+ def keep_time(self) -> bool:
lagged = self.monitor_time()
if self._remaining > 0:
time.sleep(self._remaining)
return lagged
# this only monitor the cumulative lag, but does not enforce a rate
- def monitor_time(self):
+ def monitor_time(self) -> bool:
lagged = False
remaining = self._next_frame_time - sec_since_boot()
self._next_frame_time += self._interval
diff --git a/common/transformations/camera.py b/common/transformations/camera.py
index 9c365dc7e..29ce3277d 100644
--- a/common/transformations/camera.py
+++ b/common/transformations/camera.py
@@ -5,14 +5,12 @@ from selfdrive.hardware import TICI
## -- hardcoded hardware params --
eon_f_focal_length = 910.0
-eon_d_focal_length = 860.0
-leon_d_focal_length = 650.0
+eon_d_focal_length = 650.0
tici_f_focal_length = 2648.0
tici_e_focal_length = tici_d_focal_length = 567.0 # probably wrong? magnification is not consistent across frame
eon_f_frame_size = (1164, 874)
-eon_d_frame_size = (1152, 864)
-leon_d_frame_size = (816, 612)
+eon_d_frame_size = (816, 612)
tici_f_frame_size = tici_e_frame_size = tici_d_frame_size = (1928, 1208)
# aka 'K' aka camera_frame_from_view_frame
@@ -22,11 +20,6 @@ eon_fcam_intrinsics = np.array([
[0.0, 0.0, 1.0]])
eon_intrinsics = eon_fcam_intrinsics # xx
-leon_dcam_intrinsics = np.array([
- [leon_d_focal_length, 0.0, float(leon_d_frame_size[0])/2],
- [0.0, leon_d_focal_length, float(leon_d_frame_size[1])/2],
- [0.0, 0.0, 1.0]])
-
eon_dcam_intrinsics = np.array([
[eon_d_focal_length, 0.0, float(eon_d_frame_size[0])/2],
[0.0, eon_d_focal_length, float(eon_d_frame_size[1])/2],
diff --git a/installer/updater/update.json b/installer/updater/update.json
index faff0c52d..465320544 100644
--- a/installer/updater/update.json
+++ b/installer/updater/update.json
@@ -1,7 +1,7 @@
{
- "ota_url": "https://commadist.azureedge.net/neosupdate/ota-signed-969e22c42e5c6314e54bc3ccaa5c6a684f3130a53a7a70e0cea9f1453ceb0b06.zip",
- "ota_hash": "969e22c42e5c6314e54bc3ccaa5c6a684f3130a53a7a70e0cea9f1453ceb0b06",
- "recovery_url": "https://commadist.azureedge.net/neosupdate/recovery-9c784a24826c25df315d0ace864224478e9c0e86b904f5d1f8e18ea1037e842b.img",
+ "ota_url": "https://commadist.azureedge.net/neosupdate/ota-signed-c4f56c62c5603c86e2ae9d83008a8d42a91319979661d0c42fb97b85d9112266.zip",
+ "ota_hash": "c4f56c62c5603c86e2ae9d83008a8d42a91319979661d0c42fb97b85d9112266",
+ "recovery_url": "https://commadist.azureedge.net/neosupdate/recovery-c5db3790c3b09756e8e896187ddb3f1258315eb0a86030468baa187b84a3bbf5.img",
"recovery_len": 15209772,
- "recovery_hash": "9c784a24826c25df315d0ace864224478e9c0e86b904f5d1f8e18ea1037e842b"
+ "recovery_hash": "c5db3790c3b09756e8e896187ddb3f1258315eb0a86030468baa187b84a3bbf5"
}
diff --git a/launch_chffrplus.sh b/launch_chffrplus.sh
index 3f9ce9977..1b71e0730 100755
--- a/launch_chffrplus.sh
+++ b/launch_chffrplus.sh
@@ -96,6 +96,7 @@ function two_init {
function tici_init {
sudo su -c 'echo "performance" > /sys/class/devfreq/soc:qcom,memlat-cpu0/governor'
sudo su -c 'echo "performance" > /sys/class/devfreq/soc:qcom,memlat-cpu4/governor'
+ nmcli connection modify --temporary lte gsm.auto-config yes
# set success flag for current boot slot
sudo abctl --set_success
diff --git a/launch_env.sh b/launch_env.sh
index a8ab9ad65..e1ebfbb96 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="16.2"
+ export REQUIRED_NEOS_VERSION="17"
fi
if [ -z "$AGNOS_VERSION" ]; then
- export AGNOS_VERSION="0.14"
+ export AGNOS_VERSION="0.18"
fi
if [ -z "$PASSIVE" ]; then
diff --git a/models/dmonitoring_model_q.dlc b/models/dmonitoring_model_q.dlc
index b067c3e6d..78fb53258 100644
Binary files a/models/dmonitoring_model_q.dlc and b/models/dmonitoring_model_q.dlc differ
diff --git a/models/supercombo.dlc b/models/supercombo.dlc
index dc905d59c..cbd090665 100644
Binary files a/models/supercombo.dlc and b/models/supercombo.dlc differ
diff --git a/opendbc/honda_accord_lx15t_2018_can_generated.dbc b/opendbc/honda_accord_2018_can_generated.dbc
similarity index 98%
rename from opendbc/honda_accord_lx15t_2018_can_generated.dbc
rename to opendbc/honda_accord_2018_can_generated.dbc
index 938b47427..fa7f29695 100644
--- a/opendbc/honda_accord_lx15t_2018_can_generated.dbc
+++ b/opendbc/honda_accord_2018_can_generated.dbc
@@ -380,7 +380,7 @@ 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_accord_lx15t_2018_can.dbc starts here";
+CM_ "honda_accord_2018_can.dbc starts here";
BO_ 304 GAS_PEDAL_2: 8 PCM
@@ -389,8 +389,14 @@ BO_ 304 GAS_PEDAL_2: 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_ 401 GEARBOX: 8 PCM
+
+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
SG_ GEAR2 : 31|8@0+ (1,0) [0|1] "" XXX
@@ -430,6 +436,7 @@ 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" ;
diff --git a/opendbc/honda_accord_s2t_2018_can_generated.dbc b/opendbc/honda_accord_s2t_2018_can_generated.dbc
deleted file mode 100644
index 970f62bd8..000000000
--- a/opendbc/honda_accord_s2t_2018_can_generated.dbc
+++ /dev/null
@@ -1,438 +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
-
-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
-
-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_accord_s2t_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
- 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_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON
- SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON
- SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON
- SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" EON
-
-BO_ 446 BRAKE_MODULE: 3 VSA
- SG_ BRAKE_PRESSED : 4|1@0+ (1,0) [0|1] "" XXX
- SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" XXX
- SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" XXX
-
-BO_ 927 RADAR_HUD: 8 RADAR
- SG_ ZEROS_BOH : 7|10@0+ (1,0) [0|127] "" BDY
- SG_ CMBS_OFF : 12|1@0+ (1,0) [0|1] "" BDY
- SG_ RESUME_INSTRUCTION : 21|1@0+ (1,0) [0|1] "" XXX
- SG_ SET_TO_1 : 13|1@0+ (1,0) [0|1] "" BDY
- SG_ ZEROS_BOH2 : 11|4@0+ (1,0) [0|1] "" XXX
- SG_ APPLY_BRAKES_FOR_CANC : 23|1@0+ (1,0) [0|1] "" XXX
- SG_ ACC_ALERTS : 20|5@0+ (1,0) [0|1] "" BDY
- SG_ SET_TO_0 : 22|1@0+ (1,0) [0|1] "" XXX
- SG_ LEAD_DISTANCE : 39|8@0+ (1,0) [0|255] "" XXX
- SG_ BOH : 40|1@0+ (1,0) [0|1] "" XXX
- SG_ BOH_2 : 30|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
-
-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" ;
-
-CM_ "CHFFR_METRIC 330 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0";
diff --git a/opendbc/lexus_ct200h_2018_pt_generated.dbc b/opendbc/lexus_ct200h_2018_pt_generated.dbc
index 20dbdd7d7..513a9e0a9 100644
--- a/opendbc/lexus_ct200h_2018_pt_generated.dbc
+++ b/opendbc/lexus_ct200h_2018_pt_generated.dbc
@@ -261,6 +261,7 @@ BO_ 1556 STEERING_LEVERS: 8 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_ 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
diff --git a/opendbc/lexus_is_2018_pt_generated.dbc b/opendbc/lexus_is_2018_pt_generated.dbc
index 8956c429b..a1fede6cc 100644
--- a/opendbc/lexus_is_2018_pt_generated.dbc
+++ b/opendbc/lexus_is_2018_pt_generated.dbc
@@ -261,6 +261,7 @@ BO_ 1556 STEERING_LEVERS: 8 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_ 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
diff --git a/opendbc/lexus_nx300_2018_pt_generated.dbc b/opendbc/lexus_nx300_2018_pt_generated.dbc
index 43f059e6b..55ad91963 100644
--- a/opendbc/lexus_nx300_2018_pt_generated.dbc
+++ b/opendbc/lexus_nx300_2018_pt_generated.dbc
@@ -261,6 +261,7 @@ BO_ 1556 STEERING_LEVERS: 8 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_ 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
diff --git a/opendbc/lexus_nx300h_2018_pt_generated.dbc b/opendbc/lexus_nx300h_2018_pt_generated.dbc
index 6121973e2..88d3662d8 100644
--- a/opendbc/lexus_nx300h_2018_pt_generated.dbc
+++ b/opendbc/lexus_nx300h_2018_pt_generated.dbc
@@ -261,6 +261,7 @@ BO_ 1556 STEERING_LEVERS: 8 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_ 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
diff --git a/opendbc/lexus_rx_350_2016_pt_generated.dbc b/opendbc/lexus_rx_350_2016_pt_generated.dbc
index e55caa5c5..fd0c31d4d 100644
--- a/opendbc/lexus_rx_350_2016_pt_generated.dbc
+++ b/opendbc/lexus_rx_350_2016_pt_generated.dbc
@@ -261,6 +261,7 @@ BO_ 1556 STEERING_LEVERS: 8 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_ 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
diff --git a/opendbc/lexus_rx_hybrid_2017_pt_generated.dbc b/opendbc/lexus_rx_hybrid_2017_pt_generated.dbc
index 516fd5bef..79100c55e 100644
--- a/opendbc/lexus_rx_hybrid_2017_pt_generated.dbc
+++ b/opendbc/lexus_rx_hybrid_2017_pt_generated.dbc
@@ -261,6 +261,7 @@ BO_ 1556 STEERING_LEVERS: 8 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_ 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
diff --git a/opendbc/mazda_2017.dbc b/opendbc/mazda_2017.dbc
index e763f153c..9ee492928 100644
--- a/opendbc/mazda_2017.dbc
+++ b/opendbc/mazda_2017.dbc
@@ -168,17 +168,16 @@ BO_ 581 CAM_IDK3: 8 XXX
SG_ S9 : 56|8@1+ (1,0) [0|255] "" XXX
BO_ 863 CAM_TRAFFIC_SIGNS: 8 XXX
- SG_ STOP_SIGN : 31|4@0+ (1,0) [0|1] "" XXX
SG_ NEW_SIGNAL_3 : 55|1@0+ (1,0) [0|127] "" XXX
SG_ FORWARD_COLLISION : 40|8@1+ (1,0) [0|7] "" XXX
SG_ SPEED_SIGN : 4|7@0+ (1,0) [0|15] "" XXX
SG_ NEW_SIGNAL_2 : 52|5@0+ (1,0) [0|31] "" XXX
- SG_ NEW_SIGNAL_4 : 33|1@0+ (1,0) [0|1] "" XXX
- SG_ NEW_SIGNAL_1 : 13|2@0+ (1,0) [0|3] "" XXX
SG_ SPEED_SIGN_CAM : 32|1@0+ (1,0) [0|32767] "" XXX
+ SG_ SPEED_SIGN_ON : 12|1@0+ (1,0) [0|3] "" XXX
+ SG_ STOP_SIGN : 31|4@0+ (1,0) [0|1] "" XXX
+ SG_ NEW_SIGNAL_4 : 33|1@0+ (1,0) [0|1] "" XXX
BO_ 1157 CAM_SETTINGS: 8 XXX
- SG_ NEW_SIGNAL_2 : 14|1@0+ (1,0) [0|1] "" XXX
SG_ SBS_WARNING_DISTANCE : 25|2@0+ (1,0) [0|127] "" XXX
SG_ SBS_SCBC : 28|2@0+ (1,0) [0|7] "" XXX
SG_ LKAS_ASSIT_TIMING : 13|1@0+ (1,0) [0|1] "" XXX
@@ -186,8 +185,10 @@ BO_ 1157 CAM_SETTINGS: 8 XXX
SG_ ILKAS_NTERVENTION_ON2 : 17|1@0+ (1,0) [0|255] "" XXX
SG_ LANEE_DEPARTURE_ALERT : 16|2@0+ (1,0) [0|1] "" XXX
SG_ LKAS_INERVENTION_ON1 : 15|1@0+ (1,0) [0|1] "" XXX
- SG_ NEW_SIGNAL_1 : 12|1@0+ (1,0) [0|7] "" XXX
SG_ WARNING : 11|1@0+ (1,0) [0|1] "" XXX
+ SG_ BIT1 : 12|1@0+ (1,0) [0|7] "" XXX
+ SG_ BIT2 : 14|1@0+ (1,0) [0|1] "" XXX
+ SG_ BIT3 : 18|1@0+ (1,0) [0|1] "" XXX
BO_ 1160 CAM_Empty3: 8 XXX
SG_ NEW_SIGNAL_1 : 47|24@0+ (1,0) [0|16777215] "" XXX
@@ -759,6 +760,7 @@ CM_ SG_ 605 BRAKE_WARNING "Flashing brake warning and audible alert for potentia
CM_ SG_ 579 STEERING_ANGLE "steering angle aligns with 0.022 factor and -45.06 offset";
CM_ SG_ 863 SPEED_SIGN "speed limit in MPH";
CM_ SG_ 863 SPEED_SIGN_CAM "1: The speed limit is recognized by the camera. 0: speed limit is map based or is not available";
+CM_ SG_ 863 STOP_SIGN "value 9 when stop sign is active";
CM_ SG_ 1157 SBS_WARNING_DISTANCE "1 far, 2 mid, 3 near";
CM_ SG_ 1157 SBS_SCBC "1 off, 2 on";
CM_ SG_ 1157 LKAS_ASSIT_TIMING "1 at, 0 before";
@@ -773,4 +775,4 @@ CM_ SG_ 552 GEAR "0 Shifting, 1 P, 2 R, 3 N, 4 D";
CM_ SG_ 552 GEAR_BOX "0 P, 14 R, 1 though 6 D for speeds, 15 Shift";
CM_ SG_ 540 HANDS_ON_STEER_WARN "0 no warning, b warning";
CM_ SG_ 1143 REAR_CT_ALERT "Rear Cross Traffic Alert";
-VAL_ 552 GEAR 1 "P" 2 "R" 3 "N" 4 "D";
+VAL_ 552 GEAR 1 "P" 2 "R" 3 "N" 4 "D" ;
diff --git a/opendbc/subaru_forester_2017_generated.dbc b/opendbc/subaru_forester_2017_generated.dbc
index c1ef35fbc..f68afcf59 100644
--- a/opendbc/subaru_forester_2017_generated.dbc
+++ b/opendbc/subaru_forester_2017_generated.dbc
@@ -76,13 +76,17 @@ BO_ 212 Wheel_Speeds: 8 XXX
BO_ 320 Throttle: 8 XXX
SG_ Throttle_Pedal : 0|8@1+ (0.392157,0) [0|255] "" XXX
SG_ Counter : 8|4@1+ (1,0) [0|15] "" XXX
+ SG_ Signal1 : 12|2@1+ (1,0) [0|7] "" XXX
SG_ Not_Full_Throttle : 14|1@1+ (1,0) [0|1] "" XXX
+ SG_ Signal2 : 15|1@1+ (1,0) [0|1] "" XXX
SG_ Engine_RPM : 16|14@1+ (1,0) [0|32767] "" XXX
SG_ Off_Throttle : 30|1@1+ (1,0) [0|1] "" XXX
+ SG_ Signal3 : 31|1@1+ (1,0) [0|1] "" XXX
SG_ Throttle_Cruise : 32|8@1+ (1,0) [0|255] "" XXX
SG_ Throttle_Combo : 40|8@1+ (1,0) [0|255] "" XXX
SG_ Throttle_Body : 48|8@1+ (1,0) [0|255] "" XXX
SG_ Off_Throttle_2 : 56|1@1+ (1,0) [0|1] "" XXX
+ SG_ Signal4 : 57|7@1+ (1,0) [0|127] "" XXX
BO_ 321 Engine: 8 XXX
SG_ Engine_Torque : 0|15@1+ (1,0) [0|255] "" XXX
@@ -124,7 +128,7 @@ BO_ 338 Stalk: 8 XXX
BO_ 352 ES_Brake: 8 XXX
SG_ Brake_Pressure : 0|16@1+ (1,0) [0|255] "" XXX
SG_ Brake_Light : 20|1@1+ (1,0) [0|1] "" XXX
- SG_ ES_Error : 21|1@1+ (1,0) [0|1] "" XXX
+ SG_ Cruise_Fault : 21|1@1+ (1,0) [0|1] "" XXX
SG_ Brake_On : 22|1@1+ (1,0) [0|1] "" XXX
SG_ Cruise_Activated : 23|1@1+ (1,0) [0|1] "" XXX
SG_ Counter : 48|3@1+ (1,0) [0|7] "" XXX
@@ -136,17 +140,17 @@ BO_ 353 ES_CruiseThrottle: 8 XXX
SG_ Cruise_Activated : 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_ DistanceSwap : 21|1@1+ (1,0) [0|1] "" XXX
+ SG_ Distance_Swap : 21|1@1+ (1,0) [0|1] "" XXX
SG_ Standstill : 22|1@1+ (1,0) [0|1] "" XXX
SG_ Signal3 : 23|1@1+ (1,0) [0|1] "" XXX
- SG_ CloseDistance : 24|8@1+ (0.0196,0) [0|255] "m" XXX
+ SG_ Close_Distance : 24|8@1+ (0.0196,0) [0|255] "m" XXX
SG_ Signal4 : 32|9@1+ (1,0) [0|255] "" XXX
SG_ Standstill_2 : 41|1@1+ (1,0) [0|1] "" XXX
- SG_ ES_Error : 42|1@1+ (1,0) [0|1] "" XXX
+ SG_ Cruise_Fault : 42|1@1+ (1,0) [0|1] "" XXX
SG_ Signal5 : 43|1@1+ (1,0) [0|1] "" XXX
SG_ Counter : 44|3@1+ (1,0) [0|7] "" XXX
SG_ Signal6 : 47|1@1+ (1,0) [0|1] "" XXX
- SG_ Button : 48|3@1+ (1,0) [0|7] "" XXX
+ SG_ Cruise_Button : 48|3@1+ (1,0) [0|7] "" XXX
SG_ Signal7 : 51|5@1+ (1,0) [0|31] "" XXX
SG_ Checksum : 56|8@1+ (1,0) [0|255] "" XXX
@@ -213,6 +217,9 @@ BO_ 864 Engine_Temp: 8 XXX
BO_ 866 Fuel: 8 XXX
+BO_ 977 Dash_State2: 8 XXX
+ SG_ Units : 15|1@1+ (1,0) [0|1] "" XXX
+
BO_ 1745 Dash_State: 8 XXX
SG_ Units : 15|1@1+ (1,0) [0|1] "" XXX
@@ -220,7 +227,7 @@ CM_ SG_ 320 Off_Throttle_2 "Less sensitive";
CM_ SG_ 320 Throttle_Body "Throttle related";
CM_ SG_ 328 Gear "15 = P, 14 = R, 0 = N, 1-6=gear";
CM_ SG_ 328 Gear_2 "15 = P, 14 = R, 0 = N, 1-6=gear";
-CM_ SG_ 353 Button "1 = main, 2 = set shallow, 3 = set deep, 4 = resume shallow, 5 resume deep";
+CM_ SG_ 353 Cruise_Button "1 = main, 2 = set shallow, 3 = set deep, 4 = resume shallow, 5 resume deep";
CM_ SG_ 354 RPM "20hz version of Transmission_Engine under Transmission";
CM_ SG_ 359 Sig1Right_Depart "right depart, hill steep and seatbelt disengage";
CM_ SG_ 359 LKAS_Inactive_2017 "1 when not steering, 0 when lkas steering";
@@ -253,6 +260,6 @@ BO_ 355 ES_DashStatus: 8 XXX
BO_ 881 Steering_Torque: 8 XXX
SG_ Steering_Motor_Flat : 0|10@1+ (32,0) [0|1000] "" XXX
SG_ Steer_Torque_Output : 16|11@1- (-32,0) [-1000|1000] "" XXX
- SG_ LKA_Lockout : 27|1@1+ (1,0) [0|1] "" XXX
+ SG_ Steer_Error_1 : 27|1@1+ (1,0) [0|1] "" XXX
SG_ Steer_Torque_Sensor : 29|11@1- (-1,0) [-1000|1000] "" XXX
SG_ Steering_Angle : 40|16@1- (-0.033,0) [-600|600] "" XXX
diff --git a/opendbc/subaru_global_2017_generated.dbc b/opendbc/subaru_global_2017_generated.dbc
index f17667e56..d43791b23 100644
--- a/opendbc/subaru_global_2017_generated.dbc
+++ b/opendbc/subaru_global_2017_generated.dbc
@@ -48,11 +48,13 @@ BO_ 2 Steering: 8 XXX
BO_ 64 Throttle: 8 XXX
SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX
SG_ Counter : 8|4@1+ (1,0) [0|15] "" XXX
+ SG_ Signal1 : 12|4@1+ (1,0) [0|15] "" XXX
SG_ Engine_RPM : 16|12@1+ (1,0) [0|4095] "" XXX
+ SG_ Signal2 : 28|4@1+ (1,0) [0|15] "" XXX
SG_ Throttle_Pedal : 32|8@1+ (1,0) [0|255] "" XXX
SG_ Throttle_Cruise : 40|8@1+ (1,0) [0|255] "" XXX
SG_ Throttle_Combo : 48|8@1+ (1,0) [0|255] "" XXX
- SG_ Signal1 : 56|4@1+ (1,0) [0|15] "" XXX
+ SG_ Signal3 : 56|4@1+ (1,0) [0|15] "" XXX
SG_ Off_Accel : 60|4@1+ (1,0) [0|15] "" XXX
BO_ 316 Brake_Status: 8 XXX
diff --git a/opendbc/subaru_outback_2015_generated.dbc b/opendbc/subaru_outback_2015_generated.dbc
index c0a601589..dca4e60dc 100644
--- a/opendbc/subaru_outback_2015_generated.dbc
+++ b/opendbc/subaru_outback_2015_generated.dbc
@@ -76,13 +76,17 @@ BO_ 212 Wheel_Speeds: 8 XXX
BO_ 320 Throttle: 8 XXX
SG_ Throttle_Pedal : 0|8@1+ (0.392157,0) [0|255] "" XXX
SG_ Counter : 8|4@1+ (1,0) [0|15] "" XXX
+ SG_ Signal1 : 12|2@1+ (1,0) [0|7] "" XXX
SG_ Not_Full_Throttle : 14|1@1+ (1,0) [0|1] "" XXX
+ SG_ Signal2 : 15|1@1+ (1,0) [0|1] "" XXX
SG_ Engine_RPM : 16|14@1+ (1,0) [0|32767] "" XXX
SG_ Off_Throttle : 30|1@1+ (1,0) [0|1] "" XXX
+ SG_ Signal3 : 31|1@1+ (1,0) [0|1] "" XXX
SG_ Throttle_Cruise : 32|8@1+ (1,0) [0|255] "" XXX
SG_ Throttle_Combo : 40|8@1+ (1,0) [0|255] "" XXX
SG_ Throttle_Body : 48|8@1+ (1,0) [0|255] "" XXX
SG_ Off_Throttle_2 : 56|1@1+ (1,0) [0|1] "" XXX
+ SG_ Signal4 : 57|7@1+ (1,0) [0|127] "" XXX
BO_ 321 Engine: 8 XXX
SG_ Engine_Torque : 0|15@1+ (1,0) [0|255] "" XXX
@@ -124,7 +128,7 @@ BO_ 338 Stalk: 8 XXX
BO_ 352 ES_Brake: 8 XXX
SG_ Brake_Pressure : 0|16@1+ (1,0) [0|255] "" XXX
SG_ Brake_Light : 20|1@1+ (1,0) [0|1] "" XXX
- SG_ ES_Error : 21|1@1+ (1,0) [0|1] "" XXX
+ SG_ Cruise_Fault : 21|1@1+ (1,0) [0|1] "" XXX
SG_ Brake_On : 22|1@1+ (1,0) [0|1] "" XXX
SG_ Cruise_Activated : 23|1@1+ (1,0) [0|1] "" XXX
SG_ Counter : 48|3@1+ (1,0) [0|7] "" XXX
@@ -136,17 +140,17 @@ BO_ 353 ES_CruiseThrottle: 8 XXX
SG_ Cruise_Activated : 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_ DistanceSwap : 21|1@1+ (1,0) [0|1] "" XXX
+ SG_ Distance_Swap : 21|1@1+ (1,0) [0|1] "" XXX
SG_ Standstill : 22|1@1+ (1,0) [0|1] "" XXX
SG_ Signal3 : 23|1@1+ (1,0) [0|1] "" XXX
- SG_ CloseDistance : 24|8@1+ (0.0196,0) [0|255] "m" XXX
+ SG_ Close_Distance : 24|8@1+ (0.0196,0) [0|255] "m" XXX
SG_ Signal4 : 32|9@1+ (1,0) [0|255] "" XXX
SG_ Standstill_2 : 41|1@1+ (1,0) [0|1] "" XXX
- SG_ ES_Error : 42|1@1+ (1,0) [0|1] "" XXX
+ SG_ Cruise_Fault : 42|1@1+ (1,0) [0|1] "" XXX
SG_ Signal5 : 43|1@1+ (1,0) [0|1] "" XXX
SG_ Counter : 44|3@1+ (1,0) [0|7] "" XXX
SG_ Signal6 : 47|1@1+ (1,0) [0|1] "" XXX
- SG_ Button : 48|3@1+ (1,0) [0|7] "" XXX
+ SG_ Cruise_Button : 48|3@1+ (1,0) [0|7] "" XXX
SG_ Signal7 : 51|5@1+ (1,0) [0|31] "" XXX
SG_ Checksum : 56|8@1+ (1,0) [0|255] "" XXX
@@ -213,6 +217,9 @@ BO_ 864 Engine_Temp: 8 XXX
BO_ 866 Fuel: 8 XXX
+BO_ 977 Dash_State2: 8 XXX
+ SG_ Units : 15|1@1+ (1,0) [0|1] "" XXX
+
BO_ 1745 Dash_State: 8 XXX
SG_ Units : 15|1@1+ (1,0) [0|1] "" XXX
@@ -220,7 +227,7 @@ CM_ SG_ 320 Off_Throttle_2 "Less sensitive";
CM_ SG_ 320 Throttle_Body "Throttle related";
CM_ SG_ 328 Gear "15 = P, 14 = R, 0 = N, 1-6=gear";
CM_ SG_ 328 Gear_2 "15 = P, 14 = R, 0 = N, 1-6=gear";
-CM_ SG_ 353 Button "1 = main, 2 = set shallow, 3 = set deep, 4 = resume shallow, 5 resume deep";
+CM_ SG_ 353 Cruise_Button "1 = main, 2 = set shallow, 3 = set deep, 4 = resume shallow, 5 resume deep";
CM_ SG_ 354 RPM "20hz version of Transmission_Engine under Transmission";
CM_ SG_ 359 Sig1Right_Depart "right depart, hill steep and seatbelt disengage";
CM_ SG_ 359 LKAS_Inactive_2017 "1 when not steering, 0 when lkas steering";
@@ -252,22 +259,22 @@ BO_ 358 ES_DashStatus: 8 XXX
SG_ Signal1 : 18|1@1+ (1,0) [0|1] "" XXX
SG_ WHEELS_MOVING_2015 : 19|1@1+ (1,0) [0|1] "" XXX
SG_ Driver_Input : 20|1@1+ (1,0) [0|1] "" XXX
- SG_ Distance_Bars : 21|3@1+ (1,0) [0|7] "" XXX
+ SG_ Cruise_Distance : 21|3@1+ (1,0) [0|7] "" XXX
SG_ Cruise_Set_Speed : 24|8@1+ (1,0) [0|255] "" XXX
- SG_ ES_Error : 32|1@1+ (1,0) [0|1] "" XXX
+ SG_ Cruise_Fault : 32|1@1+ (1,0) [0|1] "" XXX
SG_ Cruise_On_2 : 34|1@1+ (1,0) [0|1] "" XXX
SG_ Counter : 37|3@1+ (1,0) [0|7] "" XXX
SG_ Steep_Hill_Disengage : 44|1@1+ (1,0) [0|3] "" XXX
- SG_ Lead_Car : 46|1@1+ (1,0) [0|1] "" XXX
- SG_ Obstacle_Distance : 48|4@1+ (5,0) [0|15] "m" XXX
+ SG_ Car_Follow : 46|1@1+ (1,0) [0|1] "" XXX
+ SG_ Far_Distance : 48|4@1+ (5,0) [0|15] "m" XXX
BO_ 881 Steering_Torque: 8 XXX
SG_ Steering_Motor_Flat : 0|10@1+ (32,0) [0|1000] "" XXX
SG_ Steer_Torque_Output : 16|11@1- (-32,0) [-1000|1000] "" XXX
- SG_ LKA_Lockout : 27|1@1+ (1,0) [0|1] "" XXX
+ SG_ Steer_Error_1 : 27|1@1+ (1,0) [0|1] "" XXX
SG_ Steer_Torque_Sensor : 29|11@1- (1,0) [-1000|1000] "" XXX
SG_ Steering_Angle : 40|16@1- (-0.033,0) [-600|600] "" XXX
CM_ SG_ 358 Disengage_Alert "seatbelt and steep hill disengage";
-CM_ SG_ 358 ES_Error "No engagement until restart";
-CM_ SG_ 358 Lead_Car "front car detected";
+CM_ SG_ 358 Cruise_Fault "No engagement until restart";
+CM_ SG_ 358 Car_Follow "lead car detected";
diff --git a/opendbc/subaru_outback_2019_generated.dbc b/opendbc/subaru_outback_2019_generated.dbc
index 00b042487..9241c527f 100644
--- a/opendbc/subaru_outback_2019_generated.dbc
+++ b/opendbc/subaru_outback_2019_generated.dbc
@@ -76,13 +76,17 @@ BO_ 212 Wheel_Speeds: 8 XXX
BO_ 320 Throttle: 8 XXX
SG_ Throttle_Pedal : 0|8@1+ (0.392157,0) [0|255] "" XXX
SG_ Counter : 8|4@1+ (1,0) [0|15] "" XXX
+ SG_ Signal1 : 12|2@1+ (1,0) [0|7] "" XXX
SG_ Not_Full_Throttle : 14|1@1+ (1,0) [0|1] "" XXX
+ SG_ Signal2 : 15|1@1+ (1,0) [0|1] "" XXX
SG_ Engine_RPM : 16|14@1+ (1,0) [0|32767] "" XXX
SG_ Off_Throttle : 30|1@1+ (1,0) [0|1] "" XXX
+ SG_ Signal3 : 31|1@1+ (1,0) [0|1] "" XXX
SG_ Throttle_Cruise : 32|8@1+ (1,0) [0|255] "" XXX
SG_ Throttle_Combo : 40|8@1+ (1,0) [0|255] "" XXX
SG_ Throttle_Body : 48|8@1+ (1,0) [0|255] "" XXX
SG_ Off_Throttle_2 : 56|1@1+ (1,0) [0|1] "" XXX
+ SG_ Signal4 : 57|7@1+ (1,0) [0|127] "" XXX
BO_ 321 Engine: 8 XXX
SG_ Engine_Torque : 0|15@1+ (1,0) [0|255] "" XXX
@@ -124,7 +128,7 @@ BO_ 338 Stalk: 8 XXX
BO_ 352 ES_Brake: 8 XXX
SG_ Brake_Pressure : 0|16@1+ (1,0) [0|255] "" XXX
SG_ Brake_Light : 20|1@1+ (1,0) [0|1] "" XXX
- SG_ ES_Error : 21|1@1+ (1,0) [0|1] "" XXX
+ SG_ Cruise_Fault : 21|1@1+ (1,0) [0|1] "" XXX
SG_ Brake_On : 22|1@1+ (1,0) [0|1] "" XXX
SG_ Cruise_Activated : 23|1@1+ (1,0) [0|1] "" XXX
SG_ Counter : 48|3@1+ (1,0) [0|7] "" XXX
@@ -136,17 +140,17 @@ BO_ 353 ES_CruiseThrottle: 8 XXX
SG_ Cruise_Activated : 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_ DistanceSwap : 21|1@1+ (1,0) [0|1] "" XXX
+ SG_ Distance_Swap : 21|1@1+ (1,0) [0|1] "" XXX
SG_ Standstill : 22|1@1+ (1,0) [0|1] "" XXX
SG_ Signal3 : 23|1@1+ (1,0) [0|1] "" XXX
- SG_ CloseDistance : 24|8@1+ (0.0196,0) [0|255] "m" XXX
+ SG_ Close_Distance : 24|8@1+ (0.0196,0) [0|255] "m" XXX
SG_ Signal4 : 32|9@1+ (1,0) [0|255] "" XXX
SG_ Standstill_2 : 41|1@1+ (1,0) [0|1] "" XXX
- SG_ ES_Error : 42|1@1+ (1,0) [0|1] "" XXX
+ SG_ Cruise_Fault : 42|1@1+ (1,0) [0|1] "" XXX
SG_ Signal5 : 43|1@1+ (1,0) [0|1] "" XXX
SG_ Counter : 44|3@1+ (1,0) [0|7] "" XXX
SG_ Signal6 : 47|1@1+ (1,0) [0|1] "" XXX
- SG_ Button : 48|3@1+ (1,0) [0|7] "" XXX
+ SG_ Cruise_Button : 48|3@1+ (1,0) [0|7] "" XXX
SG_ Signal7 : 51|5@1+ (1,0) [0|31] "" XXX
SG_ Checksum : 56|8@1+ (1,0) [0|255] "" XXX
@@ -213,6 +217,9 @@ BO_ 864 Engine_Temp: 8 XXX
BO_ 866 Fuel: 8 XXX
+BO_ 977 Dash_State2: 8 XXX
+ SG_ Units : 15|1@1+ (1,0) [0|1] "" XXX
+
BO_ 1745 Dash_State: 8 XXX
SG_ Units : 15|1@1+ (1,0) [0|1] "" XXX
@@ -220,7 +227,7 @@ CM_ SG_ 320 Off_Throttle_2 "Less sensitive";
CM_ SG_ 320 Throttle_Body "Throttle related";
CM_ SG_ 328 Gear "15 = P, 14 = R, 0 = N, 1-6=gear";
CM_ SG_ 328 Gear_2 "15 = P, 14 = R, 0 = N, 1-6=gear";
-CM_ SG_ 353 Button "1 = main, 2 = set shallow, 3 = set deep, 4 = resume shallow, 5 resume deep";
+CM_ SG_ 353 Cruise_Button "1 = main, 2 = set shallow, 3 = set deep, 4 = resume shallow, 5 resume deep";
CM_ SG_ 354 RPM "20hz version of Transmission_Engine under Transmission";
CM_ SG_ 359 Sig1Right_Depart "right depart, hill steep and seatbelt disengage";
CM_ SG_ 359 LKAS_Inactive_2017 "1 when not steering, 0 when lkas steering";
@@ -252,22 +259,22 @@ BO_ 358 ES_DashStatus: 8 XXX
SG_ Signal1 : 18|1@1+ (1,0) [0|1] "" XXX
SG_ WHEELS_MOVING_2015 : 19|1@1+ (1,0) [0|1] "" XXX
SG_ Driver_Input : 20|1@1+ (1,0) [0|1] "" XXX
- SG_ Distance_Bars : 21|3@1+ (1,0) [0|7] "" XXX
+ SG_ Cruise_Distance : 21|3@1+ (1,0) [0|7] "" XXX
SG_ Cruise_Set_Speed : 24|8@1+ (1,0) [0|255] "" XXX
- SG_ ES_Error : 32|1@1+ (1,0) [0|1] "" XXX
+ SG_ Cruise_Fault : 32|1@1+ (1,0) [0|1] "" XXX
SG_ Cruise_On_2 : 34|1@1+ (1,0) [0|1] "" XXX
SG_ Counter : 37|3@1+ (1,0) [0|7] "" XXX
SG_ Steep_Hill_Disengage : 44|1@1+ (1,0) [0|3] "" XXX
- SG_ Lead_Car : 46|1@1+ (1,0) [0|1] "" XXX
- SG_ Obstacle_Distance : 48|4@1+ (5,0) [0|15] "m" XXX
+ SG_ Car_Follow : 46|1@1+ (1,0) [0|1] "" XXX
+ SG_ Far_Distance : 48|4@1+ (5,0) [0|15] "m" XXX
BO_ 881 Steering_Torque: 8 XXX
SG_ Steering_Motor_Flat : 0|10@1+ (32,0) [0|1000] "" XXX
SG_ Steer_Torque_Output : 16|11@1- (-32,0) [-1000|1000] "" XXX
- SG_ LKA_Lockout : 27|1@1+ (1,0) [0|1] "" XXX
+ SG_ Steer_Error_1 : 27|1@1+ (1,0) [0|1] "" XXX
SG_ Steer_Torque_Sensor : 29|11@1- (-1,0) [-1000|1000] "" XXX
SG_ Steering_Angle : 40|16@1- (-0.033,0) [-600|600] "" XXX
CM_ SG_ 358 Disengage_Alert "seatbelt and steep hill disengage";
-CM_ SG_ 358 ES_Error "No engagement until restart";
-CM_ SG_ 358 Lead_Car "front car detected";
+CM_ SG_ 358 Cruise_Fault "No engagement until restart";
+CM_ SG_ 358 Car_Follow "lead car detected";
diff --git a/opendbc/toyota_avalon_2017_pt_generated.dbc b/opendbc/toyota_avalon_2017_pt_generated.dbc
index f1f520eb2..369c0e84c 100644
--- a/opendbc/toyota_avalon_2017_pt_generated.dbc
+++ b/opendbc/toyota_avalon_2017_pt_generated.dbc
@@ -261,6 +261,7 @@ BO_ 1556 STEERING_LEVERS: 8 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_ 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
diff --git a/opendbc/toyota_camry_hybrid_2018_pt_generated.dbc b/opendbc/toyota_camry_hybrid_2018_pt_generated.dbc
index 52b999cfb..35a165a17 100644
--- a/opendbc/toyota_camry_hybrid_2018_pt_generated.dbc
+++ b/opendbc/toyota_camry_hybrid_2018_pt_generated.dbc
@@ -261,6 +261,7 @@ BO_ 1556 STEERING_LEVERS: 8 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_ 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
diff --git a/opendbc/toyota_corolla_2017_pt_generated.dbc b/opendbc/toyota_corolla_2017_pt_generated.dbc
index 229393698..aec13d864 100644
--- a/opendbc/toyota_corolla_2017_pt_generated.dbc
+++ b/opendbc/toyota_corolla_2017_pt_generated.dbc
@@ -261,6 +261,7 @@ BO_ 1556 STEERING_LEVERS: 8 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_ 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
diff --git a/opendbc/toyota_highlander_2017_pt_generated.dbc b/opendbc/toyota_highlander_2017_pt_generated.dbc
index 81a1caf90..b96c4b28d 100644
--- a/opendbc/toyota_highlander_2017_pt_generated.dbc
+++ b/opendbc/toyota_highlander_2017_pt_generated.dbc
@@ -261,6 +261,7 @@ BO_ 1556 STEERING_LEVERS: 8 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_ 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
diff --git a/opendbc/toyota_highlander_hybrid_2018_pt_generated.dbc b/opendbc/toyota_highlander_hybrid_2018_pt_generated.dbc
index fbf531dd4..1e4964a91 100644
--- a/opendbc/toyota_highlander_hybrid_2018_pt_generated.dbc
+++ b/opendbc/toyota_highlander_hybrid_2018_pt_generated.dbc
@@ -261,6 +261,7 @@ BO_ 1556 STEERING_LEVERS: 8 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_ 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
diff --git a/opendbc/toyota_nodsu_hybrid_pt_generated.dbc b/opendbc/toyota_nodsu_hybrid_pt_generated.dbc
index 9afca5350..aac755dbd 100644
--- a/opendbc/toyota_nodsu_hybrid_pt_generated.dbc
+++ b/opendbc/toyota_nodsu_hybrid_pt_generated.dbc
@@ -291,6 +291,7 @@ BO_ 1556 STEERING_LEVERS: 8 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_ 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
diff --git a/opendbc/toyota_nodsu_pt_generated.dbc b/opendbc/toyota_nodsu_pt_generated.dbc
index 2bfabcc23..810c323a3 100644
--- a/opendbc/toyota_nodsu_pt_generated.dbc
+++ b/opendbc/toyota_nodsu_pt_generated.dbc
@@ -291,6 +291,7 @@ BO_ 1556 STEERING_LEVERS: 8 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_ 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
diff --git a/opendbc/toyota_prius_2017_pt_generated.dbc b/opendbc/toyota_prius_2017_pt_generated.dbc
index 40fa754f4..502ef852f 100644
--- a/opendbc/toyota_prius_2017_pt_generated.dbc
+++ b/opendbc/toyota_prius_2017_pt_generated.dbc
@@ -261,6 +261,7 @@ BO_ 1556 STEERING_LEVERS: 8 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_ 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
diff --git a/opendbc/toyota_rav4_2017_pt_generated.dbc b/opendbc/toyota_rav4_2017_pt_generated.dbc
index 724aae6bb..4be2a2ed2 100644
--- a/opendbc/toyota_rav4_2017_pt_generated.dbc
+++ b/opendbc/toyota_rav4_2017_pt_generated.dbc
@@ -261,6 +261,7 @@ BO_ 1556 STEERING_LEVERS: 8 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_ 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
diff --git a/opendbc/toyota_rav4_hybrid_2017_pt_generated.dbc b/opendbc/toyota_rav4_hybrid_2017_pt_generated.dbc
index 0b36f13dc..b64182e0f 100644
--- a/opendbc/toyota_rav4_hybrid_2017_pt_generated.dbc
+++ b/opendbc/toyota_rav4_hybrid_2017_pt_generated.dbc
@@ -261,6 +261,7 @@ BO_ 1556 STEERING_LEVERS: 8 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_ 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
diff --git a/opendbc/toyota_sienna_xle_2018_pt_generated.dbc b/opendbc/toyota_sienna_xle_2018_pt_generated.dbc
index 3a7ad53c0..12c2afe45 100644
--- a/opendbc/toyota_sienna_xle_2018_pt_generated.dbc
+++ b/opendbc/toyota_sienna_xle_2018_pt_generated.dbc
@@ -261,6 +261,7 @@ BO_ 1556 STEERING_LEVERS: 8 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_ 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
diff --git a/opendbc/vw_mqb_2010.dbc b/opendbc/vw_mqb_2010.dbc
index f68564fa4..49f2541e6 100644
--- a/opendbc/vw_mqb_2010.dbc
+++ b/opendbc/vw_mqb_2010.dbc
@@ -1351,18 +1351,19 @@ BO_ 391 EV_Gearshift: 8 XXX
SG_ GearPosition : 16|4@1+ (1,0) [0|255] "" XXX
SG_ RegenBrakingMode : 12|2@1+ (1,0) [0|3] "" XXX
-CM_ SG_ 173 COUNTERXX "Message not renamed to COUNTER because J533 rate-limiting makes it look like messages are being lost";
CM_ SG_ 134 LWI_Lenkradwinkel "Steering angle WITH variable ratio effect included";
+CM_ SG_ 159 EPS_HCA_Status "Status of Heading Control Assist feature"
+CM_ SG_ 159 EPS_Lenkmoment "Steering input by driver, torque";
+CM_ SG_ 159 EPS_VZ_Lenkmoment "Steering input by driver, direction";
+CM_ SG_ 159 EPS_Berechneter_LW "Raw steering angle, degrees";
+CM_ SG_ 159 EPS_VZ_BLW "Raw steering angle, direction"
+CM_ SG_ 173 COUNTERXX "Message not renamed to COUNTER because J533 rate-limiting makes it look like messages are being lost";
CM_ SG_ 294 3 "May be zero when sent by older cameras";
CM_ SG_ 294 7 "May be zero when sent by older cameras";
CM_ SG_ 294 254 "May be zero when sent by older cameras";
CM_ SG_ 294 Assist_Torque "Heading control input, torque";
CM_ SG_ 294 Assist_VZ "Heading control input, direction (sign)";
CM_ SG_ 294 HCA_Available "Must be 1 for steering rack to accept HCA commands";
-CM_ SG_ 159 HCA_Ready "1 if HCA is okay, 0 if the rack doesn't have HCA configured or a timer/constraint has been violated, rack will not respond to HCA commands";
-CM_ SG_ 159 Driver_Strain "Steering input by driver, torque";
-CM_ SG_ 159 Driver_Strain_VZ "Steering input by driver, sign (direction)";
-CM_ SG_ 159 Steering_Wheel_Angle "Steering angle WITHOUT variable ratio effect included";
CM_ SG_ 919 LDW_DLC "Probable DLC (distance to line crossing)";
CM_ SG_ 919 LDW_TLC "Probable TLC (time to line crossing)";
CM_ SG_ 919 LDW_Unknown "Might be a steering pressed / driver active flag";
@@ -1378,6 +1379,7 @@ CM_ SG_ 780 Abstand "Following distance";
CM_ SG_ 780 SetSpeed "ACC set speed";
CM_ SG_ 391 GearPosition "Traditional PRND plus B-mode aggressive regen, B-mode mapped to Drive";
CM_ SG_ 960 ZAS_Kl_15 "Indicates ignition on";
+VAL_ 159 EPS_HCA_Status 0 "disabled" 1 "initializing" 2 "fault" 3 "ready" 4 "rejected" 5 "active";
VAL_ 173 GE_Fahrstufe 5 "P" 6 "R" 7 "N" 8 "D" 9 "S" 10 "E" 14 "T";
VAL_ 391 GearPosition 2 "P" 3 "R" 4 "N" 5 "D" 6 "D";
VAL_ 391 RegenBrakingMode 0 "default" 1 "B1" 2 "B2" 3 "B3";
diff --git a/panda/board/boards/dos.h b/panda/board/boards/dos.h
index fd952cd21..592155fb6 100644
--- a/panda/board/boards/dos.h
+++ b/panda/board/boards/dos.h
@@ -26,9 +26,9 @@ void dos_enable_can_transceivers(bool enabled) {
for(uint8_t i=1U; i<=4U; i++){
// Leave main CAN always on for CAN-based ignition detection
if((car_harness_status == HARNESS_STATUS_FLIPPED) ? (i == 3U) : (i == 1U)){
- uno_enable_can_transceiver(i, true);
+ dos_enable_can_transceiver(i, true);
} else {
- uno_enable_can_transceiver(i, enabled);
+ dos_enable_can_transceiver(i, enabled);
}
}
}
diff --git a/panda/board/main.c b/panda/board/main.c
index 9b80830ec..8337bd169 100644
--- a/panda/board/main.c
+++ b/panda/board/main.c
@@ -42,6 +42,7 @@
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!
struct __attribute__((packed)) health_t {
uint32_t uptime_pkt;
uint32_t voltage_pkt;
@@ -61,6 +62,7 @@ struct __attribute__((packed)) health_t {
int16_t safety_param_pkt;
uint8_t fault_status_pkt;
uint8_t power_save_enabled_pkt;
+ uint8_t heartbeat_lost_pkt;
};
@@ -140,6 +142,7 @@ void set_safety_mode(uint16_t mode, int16_t param) {
case SAFETY_ELM327:
set_intercept_relay(false);
heartbeat_counter = 0U;
+ heartbeat_lost = false;
if (board_has_obd()) {
current_board->set_can_mode(CAN_MODE_OBD_CAN2);
}
@@ -148,6 +151,7 @@ void set_safety_mode(uint16_t mode, int16_t param) {
default:
set_intercept_relay(true);
heartbeat_counter = 0U;
+ heartbeat_lost = false;
if (board_has_obd()) {
current_board->set_can_mode(CAN_MODE_NORMAL);
}
@@ -182,6 +186,7 @@ int get_health_pkt(void *dat) {
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;
@@ -595,6 +600,7 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, bool hardwired)
case 0xf3:
{
heartbeat_counter = 0U;
+ heartbeat_lost = false;
break;
}
// **** 0xf4: k-line/l-line 5 baud initialization
@@ -732,6 +738,9 @@ void TIM1_BRK_TIM9_IRQ_Handler(void) {
set_power_save_state(POWER_SAVE_STATUS_ENABLED);
}
+ // set flag to indicate the heartbeat was lost
+ heartbeat_lost = true;
+
// Also disable IR when the heartbeat goes missing
current_board->set_ir_power(0U);
diff --git a/panda/board/main_declarations.h b/panda/board/main_declarations.h
index ade4acac3..8181d6e32 100644
--- a/panda/board/main_declarations.h
+++ b/panda/board/main_declarations.h
@@ -13,5 +13,6 @@ const board *current_board;
bool is_enumerated = 0;
uint32_t heartbeat_counter = 0;
uint32_t uptime_cnt = 0;
+bool heartbeat_lost = false;
bool siren_enabled = false;
bool green_led_enabled = false;
diff --git a/panda/board/safety/safety_honda.h b/panda/board/safety/safety_honda.h
index 392344624..1d851dc67 100644
--- a/panda/board/safety/safety_honda.h
+++ b/panda/board/safety/safety_honda.h
@@ -37,7 +37,8 @@ const int HONDA_RX_CHECKS_LEN = sizeof(honda_rx_checks) / sizeof(honda_rx_checks
AddrCheckStruct honda_bh_rx_checks[] = {
{.msg = {{0x296, 1, 4, .check_checksum = true, .max_counter = 3U, .expected_timestep = 40000U}}},
{.msg = {{0x158, 1, 8, .check_checksum = true, .max_counter = 3U, .expected_timestep = 10000U}}},
- {.msg = {{0x17C, 1, 8, .check_checksum = true, .max_counter = 3U, .expected_timestep = 10000U}}},
+ {.msg = {{0x17C, 1, 8, .check_checksum = true, .max_counter = 3U, .expected_timestep = 10000U},
+ {0x1BE, 1, 3, .check_checksum = true, .max_counter = 3U, .expected_timestep = 20000U}}},
};
const int HONDA_BH_RX_CHECKS_LEN = sizeof(honda_bh_rx_checks) / sizeof(honda_bh_rx_checks[0]);
diff --git a/panda/python/__init__.py b/panda/python/__init__.py
index 13d543f8c..1ef4d2a4a 100644
--- a/panda/python/__init__.py
+++ b/panda/python/__init__.py
@@ -332,8 +332,8 @@ class Panda(object):
# ******************* health *******************
def health(self):
- dat = self._handle.controlRead(Panda.REQUEST_IN, 0xd2, 0, 0, 41)
- a = struct.unpack("IIIIIIIIBBBBBBBBB", dat)
+ dat = self._handle.controlRead(Panda.REQUEST_IN, 0xd2, 0, 0, 44)
+ a = struct.unpack("
+
diff --git a/selfdrive/athena/athenad.py b/selfdrive/athena/athenad.py
index e71b5b80e..1659b692c 100755
--- a/selfdrive/athena/athenad.py
+++ b/selfdrive/athena/athenad.py
@@ -25,12 +25,11 @@ from common.api import Api
from common.basedir import PERSIST
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
-import selfdrive.crash as crash
-from selfdrive.version import dirty, origin, branch, commit
+from selfdrive.version import get_version, get_git_remote, get_git_branch, get_git_commit
ATHENA_HOST = os.getenv('ATHENA_HOST', 'wss://athena.comma.ai')
HANDLER_THREADS = int(os.getenv('HANDLER_THREADS', "4"))
@@ -38,6 +37,7 @@ LOCAL_PORT_WHITELIST = set([8022])
LOG_ATTR_NAME = 'user.upload'
LOG_ATTR_VALUE_MAX_UNIX_TIME = int.to_bytes(2147483647, 4, sys.byteorder)
+RECONNECT_TIMEOUT_S = 70
dispatcher["echo"] = lambda s: s
recv_queue: Any = queue.Queue()
@@ -53,12 +53,12 @@ def handle_long_poll(ws):
end_event = threading.Event()
threads = [
- threading.Thread(target=ws_recv, args=(ws, end_event)),
- threading.Thread(target=ws_send, args=(ws, end_event)),
- threading.Thread(target=upload_handler, args=(end_event,)),
- threading.Thread(target=log_handler, args=(end_event,)),
+ threading.Thread(target=ws_recv, args=(ws, end_event), name='ws_recv'),
+ threading.Thread(target=ws_send, args=(ws, end_event), name='wc_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=jsonrpc_handler, args=(end_event,))
+ threading.Thread(target=jsonrpc_handler, args=(end_event,), name=f'worker_{x}')
for x in range(HANDLER_THREADS)
]
@@ -72,17 +72,20 @@ def handle_long_poll(ws):
raise
finally:
for thread in threads:
+ cloudlog.debug(f"athena.joining {thread.name}")
thread.join()
+
def jsonrpc_handler(end_event):
dispatcher["startLocalProxy"] = partial(startLocalProxy, end_event)
while not end_event.is_set():
try:
data = recv_queue.get(timeout=1)
if "method" in data:
+ cloudlog.debug(f"athena.jsonrpc_handler.call_method {data}")
response = JSONRPCResponseManager.handle(data, dispatcher)
send_queue.put_nowait(response.json)
- elif "result" in data and "id" in data:
+ elif "id" in data and ("result" in data or "error" in data):
log_recv_queue.put_nowait(data)
else:
raise Exception("not a valid request or response")
@@ -131,6 +134,27 @@ def getMessage(service=None, timeout=1000):
return ret.to_dict()
+@dispatcher.add_method
+def getVersion():
+ return {
+ "version": get_version(),
+ "remote": get_git_remote(),
+ "branch": get_git_branch(),
+ "commit": get_git_commit(),
+ }
+
+
+@dispatcher.add_method
+def setNavDestination(latitude=0, longitude=0):
+ destination = {
+ "latitude": latitude,
+ "longitude": longitude,
+ }
+ Params().put("NavDestination", json.dumps(destination))
+
+ return {"success": 1}
+
+
@dispatcher.add_method
def listDataDirectory():
files = [os.path.relpath(os.path.join(dp, f), ROOT) for dp, dn, fn in os.walk(ROOT) for f in fn]
@@ -190,6 +214,8 @@ def startLocalProxy(global_end_event, remote_ws_uri, local_port):
if local_port not in LOCAL_PORT_WHITELIST:
raise Exception("Requested local port not whitelisted")
+ cloudlog.debug("athena.startLocalProxy.starting")
+
params = Params()
dongle_id = params.get("DongleId").decode('utf8')
identity_token = Api(dongle_id).get_token()
@@ -210,6 +236,7 @@ def startLocalProxy(global_end_event, remote_ws_uri, local_port):
for thread in threads:
thread.start()
+ cloudlog.debug("athena.startLocalProxy.started")
return {"success": 1}
except Exception as e:
cloudlog.exception("athenad.startLocalProxy.exception")
@@ -282,56 +309,60 @@ def log_handler(end_event):
log_files = []
last_scan = 0
- log_retries = 0
while not end_event.is_set():
try:
- try:
- result = json.loads(log_recv_queue.get(timeout=1))
- log_success = result.get("success")
- log_entry = result.get("id")
- log_path = os.path.join(SWAGLOG_DIR, log_entry)
- if log_entry and log_success:
- try:
- setxattr(log_path, LOG_ATTR_NAME, LOG_ATTR_VALUE_MAX_UNIX_TIME)
- except OSError:
- pass # file could be deleted by log rotation
- except queue.Empty:
- pass
-
curr_scan = sec_since_boot()
if curr_scan - last_scan > 10:
log_files = get_logs_to_send_sorted()
last_scan = curr_scan
- # never send last log file because it is the active log
- # and only send one log file at a time (most recent first)
- if not len(log_files) or not log_send_queue.empty():
- continue
+ # send one log
+ curr_log = None
+ if len(log_files) > 0:
+ log_entry = log_files.pop()
+ cloudlog.debug(f"athena.log_handler.forward_request {log_entry}")
+ try:
+ 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:
+ jsonrpc = {
+ "method": "forwardLogs",
+ "params": {
+ "logs": f.read()
+ },
+ "jsonrpc": "2.0",
+ "id": log_entry
+ }
+ log_send_queue.put_nowait(json.dumps(jsonrpc))
+ curr_log = log_entry
+ except OSError:
+ pass # file could be deleted by log rotation
+
+ # wait for response up to ~100 seconds
+ # always read queue at least once to process any old responses that arrive
+ for _ in range(100):
+ if end_event.is_set():
+ break
+ try:
+ log_resp = json.loads(log_recv_queue.get(timeout=1))
+ log_entry = log_resp.get("id")
+ log_success = "result" in log_resp and log_resp["result"].get("success")
+ cloudlog.debug(f"athena.log_handler.forward_response {log_entry} {log_success}")
+ if log_entry and log_success:
+ log_path = os.path.join(SWAGLOG_DIR, log_entry)
+ try:
+ setxattr(log_path, LOG_ATTR_NAME, LOG_ATTR_VALUE_MAX_UNIX_TIME)
+ except OSError:
+ pass # file could be deleted by log rotation
+ if curr_log == log_entry:
+ break
+ except queue.Empty:
+ if curr_log is None:
+ break
- log_entry = log_files.pop()
- try:
- 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:
- jsonrpc = {
- "method": "forwardLogs",
- "params": {
- "logs": f.read()
- },
- "jsonrpc": "2.0",
- "id": log_entry
- }
- log_send_queue.put_nowait(json.dumps(jsonrpc))
- except OSError:
- pass # file could be deleted by log rotation
- log_retries = 0
except Exception:
cloudlog.exception("athena.log_handler.exception")
- log_retries += 1
-
- if log_retries != 0:
- time.sleep(backoff(log_retries))
def ws_proxy_recv(ws, local_sock, ssock, end_event, global_end_event):
@@ -345,8 +376,11 @@ def ws_proxy_recv(ws, local_sock, ssock, end_event, global_end_event):
cloudlog.exception("athenad.ws_proxy_recv.exception")
break
+ cloudlog.debug("athena.ws_proxy_recv closing sockets")
ssock.close()
local_sock.close()
+ cloudlog.debug("athena.ws_proxy_recv done closing sockets")
+
end_event.set()
@@ -370,10 +404,13 @@ def ws_proxy_send(ws, local_sock, signal_sock, end_event):
cloudlog.exception("athenad.ws_proxy_send.exception")
end_event.set()
+ cloudlog.debug("athena.ws_proxy_send closing sockets")
signal_sock.close()
+ cloudlog.debug("athena.ws_proxy_send done closing sockets")
def ws_recv(ws, end_event):
+ last_ping = int(sec_since_boot() * 1e9)
while not end_event.is_set():
try:
opcode, data = ws.recv_data(control_frame=True)
@@ -382,9 +419,13 @@ def ws_recv(ws, end_event):
data = data.decode("utf-8")
recv_queue.put_nowait(data)
elif opcode == ABNF.OPCODE_PING:
- Params().put("LastAthenaPingTime", str(int(sec_since_boot() * 1e9)))
+ last_ping = int(sec_since_boot() * 1e9)
+ Params().put("LastAthenaPingTime", str(last_ping))
except WebSocketTimeoutException:
- pass
+ ns_since_last_ping = int(sec_since_boot() * 1e9) - last_ping
+ if ns_since_last_ping > RECONNECT_TIMEOUT_S * 1e9:
+ cloudlog.exception("athenad.wc_recv.timeout")
+ end_event.set()
except Exception:
cloudlog.exception("athenad.ws_recv.exception")
end_event.set()
@@ -409,26 +450,41 @@ def backoff(retries):
return random.randrange(0, min(128, int(2 ** retries)))
+def manage_tokens(api):
+ if not TICI:
+ return
+
+ try:
+ params = Params()
+ mapbox = api.get(f"/v1/tokens/mapbox/{api.dongle_id}/", timeout=5.0, access_token=api.get_token())
+ if mapbox.status_code == 200:
+ params.put("MapboxToken", mapbox.json()["token"])
+ else:
+ params.delete("MapboxToken")
+ except Exception:
+ cloudlog.exception("Failed to update tokens")
+
+
def main():
params = Params()
dongle_id = params.get("DongleId", encoding='utf-8')
- crash.init()
- crash.bind_user(id=dongle_id)
- crash.bind_extra(dirty=dirty, origin=origin, branch=branch, commit=commit,
- device=HARDWARE.get_device_type())
ws_uri = ATHENA_HOST + "/ws/v2/" + dongle_id
-
api = Api(dongle_id)
conn_retries = 0
while 1:
try:
+ cloudlog.event("athenad.main.connecting_ws", ws_uri=ws_uri)
ws = create_connection(ws_uri,
cookie="jwt=" + api.get_token(),
- enable_multithread=True)
- cloudlog.event("athenad.main.connected_ws", ws_uri=ws_uri)
+ enable_multithread=True,
+ timeout=1.0)
ws.settimeout(1)
+ cloudlog.event("athenad.main.connected_ws", ws_uri=ws_uri)
+
+ manage_tokens(api)
+
conn_retries = 0
handle_long_poll(ws)
except (KeyboardInterrupt, SystemExit):
@@ -437,7 +493,6 @@ def main():
conn_retries += 1
params.delete("LastAthenaPingTime")
except Exception:
- crash.capture_exception()
cloudlog.exception("athenad.main.exception")
conn_retries += 1
diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc
index f1f885b0c..e52c8d2e6 100644
--- a/selfdrive/boardd/boardd.cc
+++ b/selfdrive/boardd/boardd.cc
@@ -12,8 +12,6 @@
#include
#include
#include
-#include
-#include
#include
#include
@@ -42,21 +40,7 @@ std::atomic safety_setter_thread_running(false);
std::atomic ignition(false);
ExitHandler do_exit;
-struct tm get_time(){
- time_t rawtime;
- time(&rawtime);
- struct tm sys_time;
- gmtime_r(&rawtime, &sys_time);
-
- return sys_time;
-}
-
-bool time_valid(struct tm sys_time){
- int year = 1900 + sys_time.tm_year;
- int month = 1 + sys_time.tm_mon;
- return (year > 2020) || (year == 2020 && month >= 10);
-}
void safety_setter_thread() {
LOGD("Starting safety setter thread");
@@ -164,10 +148,10 @@ bool usb_connect() {
if (tmp_panda->has_rtc){
setenv("TZ","UTC",1);
- struct tm sys_time = get_time();
+ struct tm sys_time = util::get_time();
struct tm rtc_time = tmp_panda->get_rtc();
- if (!time_valid(sys_time) && time_valid(rtc_time)) {
+ if (!util::time_valid(sys_time) && util::time_valid(rtc_time)) {
LOGE("System time wrong, setting from RTC. "
"System: %d-%02d-%02d %02d:%02d:%02d RTC: %d-%02d-%02d %02d:%02d:%02d",
sys_time.tm_year + 1900, sys_time.tm_mon + 1, sys_time.tm_mday,
@@ -320,7 +304,7 @@ void panda_state_thread(bool spoofing_started) {
// clear VIN, CarParams, and set new safety on car start
if (ignition && !ignition_last) {
- params.clearAll(CLEAR_ON_IGNITION);
+ params.clearAll(CLEAR_ON_IGNITION_ON);
if (!safety_setter_thread_running) {
safety_setter_thread_running = true;
@@ -328,15 +312,17 @@ void panda_state_thread(bool spoofing_started) {
} else {
LOGW("Safety setter thread already running");
}
+ } else if (!ignition && ignition_last) {
+ params.clearAll(CLEAR_ON_IGNITION_OFF);
}
// Write to rtc once per minute when no ignition present
if ((panda->has_rtc) && !ignition && (no_ignition_cnt % 120 == 1)){
// Write time to RTC if it looks reasonable
setenv("TZ","UTC",1);
- struct tm sys_time = get_time();
+ struct tm sys_time = util::get_time();
- if (time_valid(sys_time)){
+ if (util::time_valid(sys_time)){
struct tm rtc_time = panda->get_rtc();
double seconds = difftime(mktime(&rtc_time), mktime(&sys_time));
@@ -358,7 +344,10 @@ void panda_state_thread(bool spoofing_started) {
// build msg
MessageBuilder msg;
- auto ps = msg.initEvent().initPandaState();
+ auto evt = msg.initEvent();
+ evt.setValid(panda->comms_healthy);
+
+ auto ps = evt.initPandaState();
ps.setUptime(pandaState.uptime);
if (Hardware::TICI()) {
@@ -390,6 +379,8 @@ void panda_state_thread(bool spoofing_started) {
ps.setFanSpeedRpm(fan_speed_rpm);
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));
// Convert faults bitset to capnp list
std::bitset fault_bits(pandaState.faults);
@@ -543,6 +534,7 @@ void pigeon_thread() {
} else if (!ignition && ignition_last) {
// power off on falling edge of ignition
LOGD("powering off pigeon\n");
+ pigeon->stop();
pigeon->set_power(false);
}
diff --git a/selfdrive/boardd/panda.cc b/selfdrive/boardd/panda.cc
index 71f5770ed..1b563b53d 100644
--- a/selfdrive/boardd/panda.cc
+++ b/selfdrive/boardd/panda.cc
@@ -3,7 +3,6 @@
#include
#include
-#include
#include
#include
@@ -152,6 +151,7 @@ int Panda::usb_bulk_read(unsigned char endpoint, unsigned char* data, int length
if (err == LIBUSB_ERROR_TIMEOUT) {
break; // timeout is okay to exit, recv still happened
} else if (err == LIBUSB_ERROR_OVERFLOW) {
+ comms_healthy = false;
LOGE_100("overflow got 0x%x", transferred);
} else if (err != 0) {
handle_usb_issue(err, __func__);
@@ -296,9 +296,11 @@ int Panda::can_receive(kj::Array& out_buf) {
size_t num_msg = recv / 0x10;
MessageBuilder msg;
- auto canData = msg.initEvent().initCan(num_msg);
+ auto evt = msg.initEvent();
+ evt.setValid(comms_healthy);
// populate message
+ auto canData = evt.initCan(num_msg);
for (int i = 0; i < num_msg; i++) {
if (data[i*4] & 4) {
// extended
diff --git a/selfdrive/boardd/panda.h b/selfdrive/boardd/panda.h
index e725da4fa..92bd7fcf2 100644
--- a/selfdrive/boardd/panda.h
+++ b/selfdrive/boardd/panda.h
@@ -1,7 +1,5 @@
#pragma once
-#include
-
#include
#include
#include
@@ -38,6 +36,7 @@ struct __attribute__((packed)) health_t {
int16_t safety_param;
uint8_t fault_status;
uint8_t power_save_enabled;
+ uint8_t heartbeat_lost;
};
@@ -54,6 +53,7 @@ class Panda {
~Panda();
std::atomic connected = true;
+ std::atomic comms_healthy = true;
cereal::PandaState::PandaType hw_type = cereal::PandaState::PandaType::UNKNOWN;
bool has_rtc = false;
diff --git a/selfdrive/boardd/pigeon.cc b/selfdrive/boardd/pigeon.cc
index 937925e48..dc6a5e49a 100644
--- a/selfdrive/boardd/pigeon.cc
+++ b/selfdrive/boardd/pigeon.cc
@@ -6,10 +6,12 @@
#include
#include
+#include
#include "selfdrive/common/gpio.h"
#include "selfdrive/common/swaglog.h"
#include "selfdrive/common/util.h"
+#include "selfdrive/locationd/ublox_msg.h"
// Termios on macos doesn't define all baud rate constants
#ifndef B460800
@@ -22,7 +24,8 @@ extern ExitHandler do_exit;
const std::string ack = "\xb5\x62\x05\x01\x02\x00";
const std::string nack = "\xb5\x62\x05\x00\x02\x00";
-
+const std::string sos_ack = "\xb5\x62\x09\x14\x08\x00\x02\x00\x00\x00\x01\x00\x00\x00";
+const std::string sos_nack = "\xb5\x62\x09\x14\x08\x00\x02\x00\x00\x00\x00\x00\x00\x00";
Pigeon * Pigeon::connect(Panda * p){
PandaPigeon * pigeon = new PandaPigeon();
@@ -38,7 +41,7 @@ Pigeon * Pigeon::connect(const char * tty){
return pigeon;
}
-bool Pigeon::wait_for_ack(){
+bool Pigeon::wait_for_ack(std::string ack, std::string nack){
std::string s;
while (!do_exit){
s += receive();
@@ -59,6 +62,10 @@ bool Pigeon::wait_for_ack(){
return false;
}
+bool Pigeon::wait_for_ack(){
+ return wait_for_ack(ack, nack);
+}
+
bool Pigeon::send_with_ack(std::string cmd){
send(cmd);
return wait_for_ack();
@@ -110,6 +117,11 @@ void Pigeon::init() {
if (!send_with_ack("\xB5\x62\x06\x01\x03\x00\x0A\x09\x01\x1E\x70"s)) continue;
if (!send_with_ack("\xB5\x62\x06\x01\x03\x00\x0A\x0B\x01\x20\x74"s)) continue;
+ auto time = util::get_time();
+ if (util::time_valid(time)){
+ LOGW("Sending current time to ublox");
+ send(ublox::build_ubx_mga_ini_time_utc(time));
+ }
LOGW("panda GPS on");
return;
@@ -117,6 +129,22 @@ void Pigeon::init() {
LOGE("failed to initialize panda GPS");
}
+void Pigeon::stop(){
+ LOGW("Storing almanac in ublox flash");
+
+ // Controlled GNSS stop
+ send("\xB5\x62\x06\x04\x04\x00\x00\x00\x08\x00\x16\x74"s);
+
+ // Store almanac in flash
+ send("\xB5\x62\x09\x14\x04\x00\x00\x00\x00\x00\x21\xEC"s);
+
+ if (wait_for_ack(sos_ack, sos_nack)) {
+ LOGW("Done storing almanac");
+ } else {
+ LOGE("Error storing almanac");
+ }
+}
+
void PandaPigeon::connect(Panda * p) {
panda = p;
}
diff --git a/selfdrive/boardd/pigeon.h b/selfdrive/boardd/pigeon.h
index 0543c4828..ff22042dc 100644
--- a/selfdrive/boardd/pigeon.h
+++ b/selfdrive/boardd/pigeon.h
@@ -14,7 +14,9 @@ class Pigeon {
virtual ~Pigeon(){};
void init();
+ void stop();
bool wait_for_ack();
+ bool wait_for_ack(std::string ack, std::string nack);
bool send_with_ack(std::string cmd);
virtual void set_baud(int baud) = 0;
virtual void send(const std::string &s) = 0;
diff --git a/selfdrive/camerad/SConscript b/selfdrive/camerad/SConscript
index a26c20dd5..c12d25407 100644
--- a/selfdrive/camerad/SConscript
+++ b/selfdrive/camerad/SConscript
@@ -1,13 +1,10 @@
-Import('env', 'arch', 'cereal', 'messaging', 'common', 'gpucommon', 'visionipc', 'USE_WEBCAM', 'QCOM_REPLAY')
+Import('env', 'arch', 'cereal', 'messaging', 'common', 'gpucommon', 'visionipc', 'USE_WEBCAM')
libs = ['m', 'pthread', common, 'jpeg', 'OpenCL', cereal, messaging, 'zmq', 'capnp', 'kj', visionipc, gpucommon]
if arch == "aarch64":
libs += ['gsl', 'CB', 'adreno_utils', 'EGL', 'GLESv3', 'cutils', 'ui']
- if QCOM_REPLAY:
- cameras = ['cameras/camera_frame_stream.cc']
- else:
- cameras = ['cameras/camera_qcom.cc']
+ cameras = ['cameras/camera_qcom.cc']
elif arch == "larch64":
libs += ['atomic']
cameras = ['cameras/camera_qcom2.cc']
diff --git a/selfdrive/camerad/cameras/camera_common.cc b/selfdrive/camerad/cameras/camera_common.cc
index 6294c1580..cf629bde3 100644
--- a/selfdrive/camerad/cameras/camera_common.cc
+++ b/selfdrive/camerad/cameras/camera_common.cc
@@ -17,7 +17,7 @@
#include "selfdrive/common/util.h"
#include "selfdrive/hardware/hw.h"
-#if defined(QCOM) && !defined(QCOM_REPLAY)
+#ifdef QCOM
#include "selfdrive/camerad/cameras/camera_qcom.h"
#elif QCOM2
#include "selfdrive/camerad/cameras/camera_qcom2.h"
diff --git a/selfdrive/camerad/cameras/camera_common.h b/selfdrive/camerad/cameras/camera_common.h
index 337d33bdd..ab3efce28 100644
--- a/selfdrive/camerad/cameras/camera_common.h
+++ b/selfdrive/camerad/cameras/camera_common.h
@@ -1,6 +1,5 @@
#pragma once
-#include
#include
#include
diff --git a/selfdrive/camerad/cameras/camera_frame_stream.h b/selfdrive/camerad/cameras/camera_frame_stream.h
index 4a8512653..0d4d8cfb4 100644
--- a/selfdrive/camerad/cameras/camera_frame_stream.h
+++ b/selfdrive/camerad/cameras/camera_frame_stream.h
@@ -1,7 +1,5 @@
#pragma once
-#include
-
#define CL_USE_DEPRECATED_OPENCL_1_2_APIS
#ifdef __APPLE__
#include
diff --git a/selfdrive/camerad/cameras/camera_qcom.cc b/selfdrive/camerad/cameras/camera_qcom.cc
index 7d5b1611c..aa386e5c8 100644
--- a/selfdrive/camerad/cameras/camera_qcom.cc
+++ b/selfdrive/camerad/cameras/camera_qcom.cc
@@ -4,8 +4,6 @@
#include
#include
#include
-#include
-#include
#include
#include
#include
diff --git a/selfdrive/camerad/cameras/camera_qcom.h b/selfdrive/camerad/cameras/camera_qcom.h
index 55792c4ff..1bcfed205 100644
--- a/selfdrive/camerad/cameras/camera_qcom.h
+++ b/selfdrive/camerad/cameras/camera_qcom.h
@@ -1,7 +1,5 @@
#pragma once
-#include
-#include
#include
#include
diff --git a/selfdrive/camerad/cameras/camera_qcom2.cc b/selfdrive/camerad/cameras/camera_qcom2.cc
index 0f0fb10b5..44f77d80b 100644
--- a/selfdrive/camerad/cameras/camera_qcom2.cc
+++ b/selfdrive/camerad/cameras/camera_qcom2.cc
@@ -273,7 +273,7 @@ void sensors_init(int video0_fd, int sensor_fd, int camera_num) {
power->count = 1;
power->cmd_type = CAMERA_SENSOR_CMD_TYPE_PWR_UP;
power->power_settings[0].power_seq_type = 0;
- power->power_settings[0].config_val_low = 24000000; //Hz
+ power->power_settings[0].config_val_low = 19200000; //Hz
power = power_set_wait(power, 10);
// 8,1 is this reset?
diff --git a/selfdrive/camerad/cameras/camera_qcom2.h b/selfdrive/camerad/cameras/camera_qcom2.h
index ac37f557a..851dab9f4 100644
--- a/selfdrive/camerad/cameras/camera_qcom2.h
+++ b/selfdrive/camerad/cameras/camera_qcom2.h
@@ -1,7 +1,6 @@
#pragma once
#include
-#include
#include
#include
diff --git a/selfdrive/camerad/cameras/sensor2_i2c.h b/selfdrive/camerad/cameras/sensor2_i2c.h
index 6fb771b0a..5898bd4cc 100644
--- a/selfdrive/camerad/cameras/sensor2_i2c.h
+++ b/selfdrive/camerad/cameras/sensor2_i2c.h
@@ -8,7 +8,7 @@ struct i2c_random_wr_payload init_array_ar0231[] = {
{0x302A, 0x0006}, // VT_PIX_CLK_DIV
{0x302C, 0x0001}, // VT_SYS_CLK_DIV
{0x302E, 0x0002}, // PRE_PLL_CLK_DIV
- {0x3030, 0x0028}, // PLL_MULTIPLIER
+ {0x3030, 0x0032}, // PLL_MULTIPLIER
{0x3036, 0x000A}, // OP_WORD_CLK_DIV
{0x3038, 0x0001}, // OP_SYS_CLK_DIV
diff --git a/selfdrive/camerad/main.cc b/selfdrive/camerad/main.cc
index 6cfa85bdb..9636fd27b 100644
--- a/selfdrive/camerad/main.cc
+++ b/selfdrive/camerad/main.cc
@@ -15,7 +15,7 @@
#include "selfdrive/common/util.h"
#include "selfdrive/hardware/hw.h"
-#if defined(QCOM) && !defined(QCOM_REPLAY)
+#ifdef QCOM
#include "selfdrive/camerad/cameras/camera_qcom.h"
#elif QCOM2
#include "selfdrive/camerad/cameras/camera_qcom2.h"
diff --git a/selfdrive/camerad/snapshot/snapshot.py b/selfdrive/camerad/snapshot/snapshot.py
index eb7bb93af..b7dd300da 100755
--- a/selfdrive/camerad/snapshot/snapshot.py
+++ b/selfdrive/camerad/snapshot/snapshot.py
@@ -1,18 +1,21 @@
#!/usr/bin/env python3
import os
-import signal
import subprocess
import time
import numpy as np
from PIL import Image
+from typing import List
import cereal.messaging as messaging
-from common.basedir import BASEDIR
from common.params import Params
-from common.transformations.camera import eon_f_frame_size, eon_d_frame_size, leon_d_frame_size, tici_f_frame_size
+from common.realtime import DT_MDL
+from common.transformations.camera import eon_f_frame_size, eon_d_frame_size, tici_f_frame_size
from selfdrive.hardware import TICI
from selfdrive.controls.lib.alertmanager import set_offroad_alert
+from selfdrive.manager.process_config import managed_processes
+
+LM_THRESH = 120 # defined in selfdrive/camerad/imgproc/utils.h
def jpeg_write(fn, dat):
@@ -29,8 +32,14 @@ def extract_image(dat, frame_sizes):
return np.dstack([r, g, b])
-def get_snapshots(frame="roadCameraState", front_frame="driverCameraState"):
- frame_sizes = [eon_f_frame_size, eon_d_frame_size, leon_d_frame_size, tici_f_frame_size]
+def rois_in_focus(lapres: List[float]) -> float:
+ sz = len(lapres)
+ return sum([1. / sz for sharpness in
+ lapres if sharpness >= LM_THRESH])
+
+
+def get_snapshots(frame="roadCameraState", front_frame="driverCameraState", focus_perc_threshold=0.):
+ frame_sizes = [eon_f_frame_size, eon_d_frame_size, tici_f_frame_size]
frame_sizes = {w * h: (w, h) for (w, h) in frame_sizes}
sockets = []
@@ -39,10 +48,17 @@ def get_snapshots(frame="roadCameraState", front_frame="driverCameraState"):
if front_frame is not None:
sockets.append(front_frame)
+ # wait 4 sec from camerad startup for focus and exposure
sm = messaging.SubMaster(sockets)
- while min(sm.logMonoTime.values()) == 0:
+ while sm[sockets[0]].frameId < int(4. / DT_MDL):
sm.update()
+ start_t = time.monotonic()
+ while time.monotonic() - start_t < 10:
+ sm.update()
+ if min(sm.rcv_frame.values()) > 1 and rois_in_focus(sm[frame].sharpnessScore) >= focus_perc_threshold:
+ break
+
rear = extract_image(sm[frame].image, frame_sizes) if frame is not None else None
front = extract_image(sm[front_frame].image, frame_sizes) if front_frame is not None else None
return rear, front
@@ -63,7 +79,6 @@ def snapshot():
# Check if camerad is already started
try:
subprocess.check_call(["pgrep", "camerad"])
-
print("Camerad already running")
params.put_bool("IsTakingSnapshot", False)
params.delete("Offroad_IsTakingSnapshot")
@@ -71,23 +86,19 @@ def snapshot():
except subprocess.CalledProcessError:
pass
- env = os.environ.copy()
- env["SEND_ROAD"] = "1"
- env["SEND_WIDE_ROAD"] = "1"
+ os.environ["SEND_ROAD"] = "1"
+ os.environ["SEND_WIDE_ROAD"] = "1"
if front_camera_allowed:
- env["SEND_DRIVER"] = "1"
-
- proc = subprocess.Popen(os.path.join(BASEDIR, "selfdrive/camerad/camerad"),
- cwd=os.path.join(BASEDIR, "selfdrive/camerad"), env=env)
- time.sleep(3.0)
+ os.environ["SEND_DRIVER"] = "1"
+ managed_processes['camerad'].start()
frame = "wideRoadCameraState" if TICI else "roadCameraState"
front_frame = "driverCameraState" if front_camera_allowed else None
- rear, front = get_snapshots(frame, front_frame)
+ focus_perc_threshold = 0. if TICI else 10 / 12.
- proc.send_signal(signal.SIGINT)
- proc.communicate()
+ rear, front = get_snapshots(frame, front_frame, focus_perc_threshold)
+ managed_processes['camerad'].stop()
params.put_bool("IsTakingSnapshot", False)
set_offroad_alert("Offroad_IsTakingSnapshot", False)
@@ -103,6 +114,7 @@ if __name__ == "__main__":
if pic is not None:
print(pic.shape)
jpeg_write("/tmp/back.jpg", pic)
- jpeg_write("/tmp/front.jpg", fpic)
+ if fpic is not None:
+ jpeg_write("/tmp/front.jpg", fpic)
else:
print("Error taking snapshot")
diff --git a/selfdrive/car/car_helpers.py b/selfdrive/car/car_helpers.py
index 9b6d13e58..ba214410d 100644
--- a/selfdrive/car/car_helpers.py
+++ b/selfdrive/car/car_helpers.py
@@ -2,7 +2,7 @@ import os
from common.params import Params
from common.basedir import BASEDIR
from selfdrive.version import comma_remote, tested_branch
-from selfdrive.car.fingerprints import eliminate_incompatible_cars, all_known_cars
+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
from selfdrive.swaglog import cloudlog
@@ -13,14 +13,17 @@ from cereal import car
EventName = car.CarEvent.EventName
-def get_startup_event(car_recognized, controller_available, fuzzy_fingerprint):
+def get_startup_event(car_recognized, controller_available, fuzzy_fingerprint, fw_seen):
if comma_remote and tested_branch:
event = EventName.startup
else:
event = EventName.startupMaster
if not car_recognized:
- event = EventName.startupNoCar
+ if fw_seen:
+ event = EventName.startupNoCar
+ else:
+ event = EventName.startupNoFw
elif car_recognized and not controller_available:
event = EventName.startupNoControl
elif car_recognized and fuzzy_fingerprint:
@@ -115,7 +118,7 @@ def fingerprint(logcan, sendcan):
Params().put("CarVin", vin)
finger = gen_empty_fingerprint()
- candidate_cars = {i: all_known_cars() for i in [0, 1]} # attempt fingerprint on both bus 0 and 1
+ candidate_cars = {i: all_legacy_fingerprint_cars() for i in [0, 1]} # attempt fingerprint on both bus 0 and 1
frame = 0
frame_fingerprint = 10 # 0.1s
car_fingerprint = None
diff --git a/selfdrive/car/chrysler/carstate.py b/selfdrive/car/chrysler/carstate.py
index e7f8ee65b..ba85a89c3 100644
--- a/selfdrive/car/chrysler/carstate.py
+++ b/selfdrive/car/chrysler/carstate.py
@@ -9,48 +9,47 @@ from selfdrive.car.chrysler.values import DBC, STEER_THRESHOLD
class CarState(CarStateBase):
def __init__(self, CP):
super().__init__(CP)
- can_define = CANDefine(DBC[CP.carFingerprint]['pt'])
- self.shifter_values = can_define.dv["GEAR"]['PRNDL']
+ can_define = CANDefine(DBC[CP.carFingerprint]["pt"])
+ self.shifter_values = can_define.dv["GEAR"]["PRNDL"]
def update(self, cp, cp_cam):
ret = car.CarState.new_message()
- self.frame = int(cp.vl["EPS_STATUS"]['COUNTER'])
+ self.frame = int(cp.vl["EPS_STATUS"]["COUNTER"])
- ret.doorOpen = any([cp.vl["DOORS"]['DOOR_OPEN_FL'],
- cp.vl["DOORS"]['DOOR_OPEN_FR'],
- cp.vl["DOORS"]['DOOR_OPEN_RL'],
- cp.vl["DOORS"]['DOOR_OPEN_RR']])
- ret.seatbeltUnlatched = cp.vl["SEATBELT_STATUS"]['SEATBELT_DRIVER_UNLATCHED'] == 1
+ ret.doorOpen = any([cp.vl["DOORS"]["DOOR_OPEN_FL"],
+ cp.vl["DOORS"]["DOOR_OPEN_FR"],
+ cp.vl["DOORS"]["DOOR_OPEN_RL"],
+ cp.vl["DOORS"]["DOOR_OPEN_RR"]])
+ ret.seatbeltUnlatched = cp.vl["SEATBELT_STATUS"]["SEATBELT_DRIVER_UNLATCHED"] == 1
- ret.brakePressed = cp.vl["BRAKE_2"]['BRAKE_PRESSED_2'] == 5 # human-only
+ ret.brakePressed = cp.vl["BRAKE_2"]["BRAKE_PRESSED_2"] == 5 # human-only
ret.brake = 0
- ret.brakeLights = ret.brakePressed
- ret.gas = cp.vl["ACCEL_GAS_134"]['ACCEL_134']
+ ret.gas = cp.vl["ACCEL_GAS_134"]["ACCEL_134"]
ret.gasPressed = ret.gas > 1e-5
- ret.espDisabled = (cp.vl["TRACTION_BUTTON"]['TRACTION_OFF'] == 1)
+ ret.espDisabled = (cp.vl["TRACTION_BUTTON"]["TRACTION_OFF"] == 1)
- ret.wheelSpeeds.fl = cp.vl['WHEEL_SPEEDS']['WHEEL_SPEED_FL']
- ret.wheelSpeeds.rr = cp.vl['WHEEL_SPEEDS']['WHEEL_SPEED_RR']
- ret.wheelSpeeds.rl = cp.vl['WHEEL_SPEEDS']['WHEEL_SPEED_RL']
- ret.wheelSpeeds.fr = cp.vl['WHEEL_SPEEDS']['WHEEL_SPEED_FR']
- ret.vEgoRaw = (cp.vl['SPEED_1']['SPEED_LEFT'] + cp.vl['SPEED_1']['SPEED_RIGHT']) / 2.
+ ret.wheelSpeeds.fl = cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_FL"]
+ ret.wheelSpeeds.rr = cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_RR"]
+ ret.wheelSpeeds.rl = cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_RL"]
+ ret.wheelSpeeds.fr = cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_FR"]
+ ret.vEgoRaw = (cp.vl["SPEED_1"]["SPEED_LEFT"] + cp.vl["SPEED_1"]["SPEED_RIGHT"]) / 2.
ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw)
ret.standstill = not ret.vEgoRaw > 0.001
- ret.leftBlinker = cp.vl["STEERING_LEVERS"]['TURN_SIGNALS'] == 1
- ret.rightBlinker = cp.vl["STEERING_LEVERS"]['TURN_SIGNALS'] == 2
- ret.steeringAngleDeg = cp.vl["STEERING"]['STEER_ANGLE']
- ret.steeringRateDeg = cp.vl["STEERING"]['STEERING_RATE']
- ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(cp.vl['GEAR']['PRNDL'], None))
+ ret.leftBlinker = cp.vl["STEERING_LEVERS"]["TURN_SIGNALS"] == 1
+ ret.rightBlinker = cp.vl["STEERING_LEVERS"]["TURN_SIGNALS"] == 2
+ ret.steeringAngleDeg = cp.vl["STEERING"]["STEER_ANGLE"]
+ ret.steeringRateDeg = cp.vl["STEERING"]["STEERING_RATE"]
+ ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(cp.vl["GEAR"]["PRNDL"], None))
- ret.cruiseState.enabled = cp.vl["ACC_2"]['ACC_STATUS_2'] == 7 # ACC is green.
+ ret.cruiseState.enabled = cp.vl["ACC_2"]["ACC_STATUS_2"] == 7 # ACC is green.
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
+ 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"]
@@ -58,15 +57,15 @@ class CarState(CarStateBase):
steer_state = cp.vl["EPS_STATUS"]["LKAS_STATE"]
ret.steerError = steer_state == 4 or (steer_state == 0 and ret.vEgo > self.CP.minSteerSpeed)
- ret.genericToggle = bool(cp.vl["STEERING_LEVERS"]['HIGH_BEAM_FLASH'])
-
- if self.CP.enableBsm:
- ret.leftBlindspot = cp.vl["BLIND_SPOT_WARNINGS"]['BLIND_SPOT_LEFT'] == 1
- ret.rightBlindspot = cp.vl["BLIND_SPOT_WARNINGS"]['BLIND_SPOT_RIGHT'] == 1
+ ret.genericToggle = bool(cp.vl["STEERING_LEVERS"]["HIGH_BEAM_FLASH"])
- self.lkas_counter = cp_cam.vl["LKAS_COMMAND"]['COUNTER']
- self.lkas_car_model = cp_cam.vl["LKAS_HUD"]['CAR_MODEL']
- self.lkas_status_ok = cp_cam.vl["LKAS_HEARTBIT"]['LKAS_STATUS_OK']
+ if self.CP.enableBsm:
+ ret.leftBlindspot = cp.vl["BLIND_SPOT_WARNINGS"]["BLIND_SPOT_LEFT"] == 1
+ ret.rightBlindspot = cp.vl["BLIND_SPOT_WARNINGS"]["BLIND_SPOT_RIGHT"] == 1
+
+ self.lkas_counter = cp_cam.vl["LKAS_COMMAND"]["COUNTER"]
+ self.lkas_car_model = cp_cam.vl["LKAS_HUD"]["CAR_MODEL"]
+ self.lkas_status_ok = cp_cam.vl["LKAS_HEARTBIT"]["LKAS_STATUS_OK"]
return ret
@@ -126,7 +125,7 @@ class CarState(CarStateBase):
]
checks += [("BLIND_SPOT_WARNINGS", 2)]
- return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 0)
+ return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 0)
@staticmethod
def get_cam_can_parser(CP):
@@ -142,4 +141,4 @@ class CarState(CarStateBase):
("LKAS_HUD", 4),
]
- return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 2)
+ return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 2)
diff --git a/selfdrive/car/chrysler/values.py b/selfdrive/car/chrysler/values.py
index 2ded7b685..8f842083e 100644
--- a/selfdrive/car/chrysler/values.py
+++ b/selfdrive/car/chrysler/values.py
@@ -39,11 +39,9 @@ FINGERPRINTS = {
{55: 8, 257: 5, 258: 8, 264: 8, 268: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 516: 7, 517: 7, 520: 8, 524: 8, 526: 6, 528: 8, 532: 8, 542: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 656: 4, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 678: 8, 680: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 746: 5, 752: 2, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 808: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 882: 8, 897: 8, 924: 8, 926: 3, 937: 8, 947: 8, 948: 8, 969: 4, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1098: 8, 1100: 8, 1537: 8, 1538: 8, 1562: 8},
{55: 8, 257: 5, 258: 8, 264: 8, 268: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 516: 7, 517: 7, 520: 8, 524: 8, 526: 6, 528: 8, 532: 8, 542: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 4, 571: 3, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 656: 4, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 678: 8, 680: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 746: 5, 752: 2, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 808: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 882: 8, 897: 8, 924: 3, 926: 3, 937: 8, 947: 8, 948: 8, 969: 4, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1098: 8, 1100: 8, 1537: 8, 1538: 8, 1562: 8},
],
- CAR.PACIFICA_2020: [
- {
- 55: 8, 179: 8, 181: 8, 257: 5, 258: 8, 264: 8, 268: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 528: 8, 532: 8, 542: 8, 544: 8, 557: 8, 559: 8, 560: 8, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 650: 8, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 676: 8, 678: 8, 680: 8, 683: 8, 703: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 746: 5, 752: 2, 754: 8, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 782: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 808: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 847: 1, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 882: 8, 897: 8, 906: 8, 924: 8, 926: 3, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 962: 8, 969: 4, 973: 8, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1098: 8, 1100: 8, 1216: 8, 1218: 8, 1220: 8, 1223: 7, 1225: 8, 1235: 8, 1242: 8, 1246: 8, 1250: 8, 1251: 8, 1252: 8, 1284: 8, 1568: 8, 1570: 8, 1856: 8, 1858: 8, 1860: 8, 1863: 8, 1865: 8, 1875: 8, 1882: 8, 1886: 8, 1890: 8, 1891: 8, 1892: 8, 2016: 8, 2017:8, 2024: 8, 2025: 8
- }
- ],
+ CAR.PACIFICA_2020: [{
+ 55: 8, 179: 8, 181: 8, 257: 5, 258: 8, 264: 8, 268: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 352: 8, 362: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 528: 8, 532: 8, 536: 8, 542: 8, 544: 8, 557: 8, 559: 8, 560: 8, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 650: 8, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 676: 8, 678: 8, 680: 8, 683: 8, 703: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 746: 5, 752: 2, 754: 8, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 776: 8, 779: 8, 782: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 808: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 847: 1, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 882: 8, 897: 8, 906: 8, 924: 8, 926: 3, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 962: 8, 969: 4, 973: 8, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1098: 8, 1100: 8, 1216: 8, 1218: 8, 1220: 8, 1223: 7, 1225: 8, 1227: 8, 1235: 8, 1242: 8, 1246: 8, 1250: 8, 1251: 8, 1252: 8, 1284: 8, 1543: 8, 1568: 8, 1570: 8, 1856: 8, 1858: 8, 1860: 8, 1863: 8, 1865: 8, 1867: 8, 1875: 8, 1882: 8, 1886: 8, 1890: 8, 1891: 8, 1892: 8, 2016: 8, 2017:8, 2024: 8, 2025: 8
+ }],
CAR.PACIFICA_2018_HYBRID: [
{68: 8, 168: 8, 257: 5, 258: 8, 264: 8, 268: 8, 270: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 291: 8, 292: 8, 294: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 344: 8, 368: 8, 376: 3, 384: 8, 388: 4, 448: 6, 456: 4, 464: 8, 469: 8, 480: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 528: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 624: 8, 625: 8, 632: 8, 639: 8, 653: 8, 654: 8, 655: 8, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 680: 8, 701: 8, 704: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 736: 8, 737: 8, 746: 5, 760: 8, 764: 8, 766: 8, 770: 8, 773: 8, 779: 8, 782: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 808: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 832: 8, 838: 2, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 878: 8, 882: 8, 897: 8, 908: 8, 924: 8, 926: 3, 929: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 958: 8, 959: 8, 969: 4, 974: 5, 979: 8, 980: 8, 981: 8, 982: 8, 983: 8, 984: 8, 992: 8, 993: 7, 995: 8, 996: 8, 1000: 8, 1001: 8, 1002: 8, 1003: 8, 1008: 8, 1009: 8, 1010: 8, 1011: 8, 1012: 8, 1013: 8, 1014: 8, 1015: 8, 1024: 8, 1025: 8, 1026: 8, 1031: 8, 1033: 8, 1050: 8, 1059: 8, 1082: 8, 1083: 8, 1098: 8, 1100: 8},
# based on 9ae7821dc4e92455|2019-07-01--16-42-55
diff --git a/selfdrive/car/fingerprints.py b/selfdrive/car/fingerprints.py
index 64dc56625..b09e14a42 100644
--- a/selfdrive/car/fingerprints.py
+++ b/selfdrive/car/fingerprints.py
@@ -36,7 +36,6 @@ def get_attr_from_cars(attr, result=dict, combine_brands=True):
FW_VERSIONS = get_attr_from_cars('FW_VERSIONS')
_FINGERPRINTS = get_attr_from_cars('FINGERPRINTS')
-IGNORED_FINGERPRINTS = get_attr_from_cars('IGNORED_FINGERPRINTS', list)
_DEBUG_ADDRESS = {1880: 8} # reserved for debug purposes
@@ -59,9 +58,6 @@ def eliminate_incompatible_cars(msg, candidate_cars):
compatible_cars = []
for car_name in candidate_cars:
- if car_name in IGNORED_FINGERPRINTS:
- continue
-
car_fingerprints = _FINGERPRINTS[car_name]
for fingerprint in car_fingerprints:
@@ -76,4 +72,9 @@ def eliminate_incompatible_cars(msg, candidate_cars):
def all_known_cars():
"""Returns a list of all known car strings."""
+ return list({*FW_VERSIONS.keys(), *_FINGERPRINTS.keys()})
+
+
+def all_legacy_fingerprint_cars():
+ """Returns a list of all known car strings, FPv1 only."""
return list(_FINGERPRINTS.keys())
diff --git a/selfdrive/car/ford/carstate.py b/selfdrive/car/ford/carstate.py
index 756c4b876..100d47240 100644
--- a/selfdrive/car/ford/carstate.py
+++ b/selfdrive/car/ford/carstate.py
@@ -10,26 +10,25 @@ WHEEL_RADIUS = 0.33
class CarState(CarStateBase):
def update(self, cp):
ret = car.CarState.new_message()
- ret.wheelSpeeds.rr = cp.vl["WheelSpeed_CG1"]['WhlRr_W_Meas'] * WHEEL_RADIUS
- ret.wheelSpeeds.rl = cp.vl["WheelSpeed_CG1"]['WhlRl_W_Meas'] * WHEEL_RADIUS
- ret.wheelSpeeds.fr = cp.vl["WheelSpeed_CG1"]['WhlFr_W_Meas'] * WHEEL_RADIUS
- ret.wheelSpeeds.fl = cp.vl["WheelSpeed_CG1"]['WhlFl_W_Meas'] * WHEEL_RADIUS
+ ret.wheelSpeeds.rr = cp.vl["WheelSpeed_CG1"]["WhlRr_W_Meas"] * WHEEL_RADIUS
+ ret.wheelSpeeds.rl = cp.vl["WheelSpeed_CG1"]["WhlRl_W_Meas"] * WHEEL_RADIUS
+ ret.wheelSpeeds.fr = cp.vl["WheelSpeed_CG1"]["WhlFr_W_Meas"] * WHEEL_RADIUS
+ ret.wheelSpeeds.fl = cp.vl["WheelSpeed_CG1"]["WhlFl_W_Meas"] * WHEEL_RADIUS
ret.vEgoRaw = mean([ret.wheelSpeeds.rr, ret.wheelSpeeds.rl, ret.wheelSpeeds.fr, ret.wheelSpeeds.fl])
ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw)
ret.standstill = not ret.vEgoRaw > 0.001
- ret.steeringAngleDeg = cp.vl["Steering_Wheel_Data_CG1"]['SteWhlRelInit_An_Sns']
- 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.available = cp.vl["Cruise_Status"]['Cruise_State'] != 0
- ret.gas = cp.vl["EngineData_14"]['ApedPosScal_Pc_Actl'] / 100.
+ ret.steeringAngleDeg = cp.vl["Steering_Wheel_Data_CG1"]["SteWhlRelInit_An_Sns"]
+ 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.available = cp.vl["Cruise_Status"]["Cruise_State"] != 0
+ ret.gas = cp.vl["EngineData_14"]["ApedPosScal_Pc_Actl"] / 100.
ret.gasPressed = ret.gas > 1e-6
ret.brakePressed = bool(cp.vl["Cruise_Status"]["Brake_Drv_Appl"])
- ret.brakeLights = bool(cp.vl["BCM_to_HS_Body"]["Brake_Lights"])
ret.genericToggle = bool(cp.vl["Steering_Buttons"]["Dist_Incr"])
# TODO: we also need raw driver torque, needed for Assisted Lane Change
- self.lkas_state = cp.vl["Lane_Keep_Assist_Status"]['LaActAvail_D_Actl']
+ self.lkas_state = cp.vl["Lane_Keep_Assist_Status"]["LaActAvail_D_Actl"]
return ret
@@ -50,7 +49,6 @@ class CarState(CarStateBase):
("ApedPosScal_Pc_Actl", "EngineData_14", 0.),
("Dist_Incr", "Steering_Buttons", 0.),
("Brake_Drv_Appl", "Cruise_Status", 0.),
- ("Brake_Lights", "BCM_to_HS_Body", 0.),
]
checks = []
- return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 0, enforce_checks=False)
+ return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 0, enforce_checks=False)
diff --git a/selfdrive/car/fw_versions.py b/selfdrive/car/fw_versions.py
index 0e3e03822..d3057c28b 100755
--- a/selfdrive/car/fw_versions.py
+++ b/selfdrive/car/fw_versions.py
@@ -69,6 +69,11 @@ OBD_VERSION_RESPONSE = b'\x49\x04'
DEFAULT_RX_OFFSET = 0x8
VOLKSWAGEN_RX_OFFSET = 0x6a
+MAZDA_VERSION_REQUEST = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER]) + \
+ p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_ECU_SOFTWARE_NUMBER)
+MAZDA_VERSION_RESPONSE = bytes([uds.SERVICE_TYPE.READ_DATA_BY_IDENTIFIER + 0x40]) + \
+ p16(uds.DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_ECU_SOFTWARE_NUMBER)
+
# brand, request, response, response offset
REQUESTS = [
# Hyundai
@@ -129,6 +134,13 @@ REQUESTS = [
[VOLKSWAGEN_VERSION_RESPONSE],
DEFAULT_RX_OFFSET,
),
+ # Mazda
+ (
+ "mazda",
+ [MAZDA_VERSION_REQUEST],
+ [MAZDA_VERSION_RESPONSE],
+ DEFAULT_RX_OFFSET,
+ )
]
@@ -209,7 +221,7 @@ def match_fw_to_car_exact(fw_versions_dict):
continue
# On some Toyota models, the engine can show on two different addresses
- if ecu_type == Ecu.engine and candidate in [TOYOTA.COROLLA_TSS2, TOYOTA.CHR, TOYOTA.LEXUS_IS, TOYOTA.AVALON] 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
diff --git a/selfdrive/car/gm/carstate.py b/selfdrive/car/gm/carstate.py
index 954b3ec74..c9f1de8ba 100644
--- a/selfdrive/car/gm/carstate.py
+++ b/selfdrive/car/gm/carstate.py
@@ -11,62 +11,62 @@ from selfdrive.car.gm.values import DBC, CAR, AccState, CanBus, \
class CarState(CarStateBase):
def __init__(self, CP):
super().__init__(CP)
- can_define = CANDefine(DBC[CP.carFingerprint]['pt'])
+ can_define = CANDefine(DBC[CP.carFingerprint]["pt"])
self.shifter_values = can_define.dv["ECMPRDNL"]["PRNDL"]
def update(self, pt_cp):
ret = car.CarState.new_message()
self.prev_cruise_buttons = self.cruise_buttons
- self.cruise_buttons = pt_cp.vl["ASCMSteeringButton"]['ACCButtons']
+ self.cruise_buttons = pt_cp.vl["ASCMSteeringButton"]["ACCButtons"]
- ret.wheelSpeeds.fl = pt_cp.vl["EBCMWheelSpdFront"]['FLWheelSpd'] * CV.KPH_TO_MS
- ret.wheelSpeeds.fr = pt_cp.vl["EBCMWheelSpdFront"]['FRWheelSpd'] * CV.KPH_TO_MS
- ret.wheelSpeeds.rl = pt_cp.vl["EBCMWheelSpdRear"]['RLWheelSpd'] * CV.KPH_TO_MS
- ret.wheelSpeeds.rr = pt_cp.vl["EBCMWheelSpdRear"]['RRWheelSpd'] * CV.KPH_TO_MS
+ ret.wheelSpeeds.fl = pt_cp.vl["EBCMWheelSpdFront"]["FLWheelSpd"] * CV.KPH_TO_MS
+ ret.wheelSpeeds.fr = pt_cp.vl["EBCMWheelSpdFront"]["FRWheelSpd"] * CV.KPH_TO_MS
+ ret.wheelSpeeds.rl = pt_cp.vl["EBCMWheelSpdRear"]["RLWheelSpd"] * CV.KPH_TO_MS
+ ret.wheelSpeeds.rr = pt_cp.vl["EBCMWheelSpdRear"]["RRWheelSpd"] * CV.KPH_TO_MS
ret.vEgoRaw = mean([ret.wheelSpeeds.fl, ret.wheelSpeeds.fr, ret.wheelSpeeds.rl, ret.wheelSpeeds.rr])
ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw)
ret.standstill = ret.vEgoRaw < 0.01
- ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(pt_cp.vl["ECMPRDNL"]['PRNDL'], None))
- ret.brake = pt_cp.vl["EBCMBrakePedalPosition"]['BrakePedalPosition'] / 0xd0
+ ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(pt_cp.vl["ECMPRDNL"]["PRNDL"], None))
+ 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["AcceleratorPedal"]["AcceleratorPedal"] / 254.
ret.gasPressed = ret.gas > 1e-5
- ret.steeringAngleDeg = pt_cp.vl["PSCMSteeringAngle"]['SteeringWheelAngle']
- ret.steeringRateDeg = pt_cp.vl["PSCMSteeringAngle"]['SteeringWheelRate']
- ret.steeringTorque = pt_cp.vl["PSCMStatus"]['LKADriverAppldTrq']
- ret.steeringTorqueEps = pt_cp.vl["PSCMStatus"]['LKATorqueDelivered']
+ ret.steeringAngleDeg = pt_cp.vl["PSCMSteeringAngle"]["SteeringWheelAngle"]
+ ret.steeringRateDeg = pt_cp.vl["PSCMSteeringAngle"]["SteeringWheelRate"]
+ ret.steeringTorque = pt_cp.vl["PSCMStatus"]["LKADriverAppldTrq"]
+ ret.steeringTorqueEps = pt_cp.vl["PSCMStatus"]["LKATorqueDelivered"]
ret.steeringPressed = abs(ret.steeringTorque) > STEER_THRESHOLD
# 0 inactive, 1 active, 2 temporarily limited, 3 failed
- self.lkas_status = pt_cp.vl["PSCMStatus"]['LKATorqueDeliveredStatus']
+ self.lkas_status = pt_cp.vl["PSCMStatus"]["LKATorqueDeliveredStatus"]
ret.steerWarning = self.lkas_status not in [0, 1]
# 1 - open, 0 - closed
- ret.doorOpen = (pt_cp.vl["BCMDoorBeltStatus"]['FrontLeftDoor'] == 1 or
- pt_cp.vl["BCMDoorBeltStatus"]['FrontRightDoor'] == 1 or
- pt_cp.vl["BCMDoorBeltStatus"]['RearLeftDoor'] == 1 or
- pt_cp.vl["BCMDoorBeltStatus"]['RearRightDoor'] == 1)
+ ret.doorOpen = (pt_cp.vl["BCMDoorBeltStatus"]["FrontLeftDoor"] == 1 or
+ pt_cp.vl["BCMDoorBeltStatus"]["FrontRightDoor"] == 1 or
+ pt_cp.vl["BCMDoorBeltStatus"]["RearLeftDoor"] == 1 or
+ pt_cp.vl["BCMDoorBeltStatus"]["RearRightDoor"] == 1)
# 1 - latched
- ret.seatbeltUnlatched = pt_cp.vl["BCMDoorBeltStatus"]['LeftSeatBelt'] == 0
- ret.leftBlinker = pt_cp.vl["BCMTurnSignals"]['TurnSignals'] == 1
- ret.rightBlinker = pt_cp.vl["BCMTurnSignals"]['TurnSignals'] == 2
+ ret.seatbeltUnlatched = pt_cp.vl["BCMDoorBeltStatus"]["LeftSeatBelt"] == 0
+ ret.leftBlinker = pt_cp.vl["BCMTurnSignals"]["TurnSignals"] == 1
+ 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.espDisabled = pt_cp.vl["ESPStatus"]['TractionControlOn'] != 1
- self.pcm_acc_status = pt_cp.vl["AcceleratorPedal2"]['CruiseState']
+ self.park_brake = pt_cp.vl["EPBStatus"]["EPBClosed"]
+ ret.cruiseState.available = bool(pt_cp.vl["ECMEngineStatus"]["CruiseMainOn"])
+ 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 bool(pt_cp.vl["EBCMRegenPaddle"]["RegenPaddle"])
ret.cruiseState.enabled = self.pcm_acc_status != AccState.OFF
ret.cruiseState.standstill = self.pcm_acc_status == AccState.STANDSTILL
@@ -129,4 +129,4 @@ class CarState(CarStateBase):
("EBCMRegenPaddle", 50),
]
- return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, CanBus.POWERTRAIN)
+ return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, CanBus.POWERTRAIN)
diff --git a/selfdrive/car/honda/carcontroller.py b/selfdrive/car/honda/carcontroller.py
index 4d1c60d4a..53304583b 100644
--- a/selfdrive/car/honda/carcontroller.py
+++ b/selfdrive/car/honda/carcontroller.py
@@ -101,6 +101,10 @@ class CarController():
# send pcm acc cancel cmd if drive is disabled but pcm is still on, or if the system can't be activated
pcm_cancel_cmd = True
+ # Never send cancel command if we never enter cruise state (no cruise if pedal)
+ # Cancel cmd causes brakes to release at a standstill causing grinding
+ pcm_cancel_cmd = pcm_cancel_cmd and CS.CP.enableCruise
+
# *** rate limit after the enable check ***
self.brake_last = rate_limit(brake, self.brake_last, -2., DT_CTRL)
diff --git a/selfdrive/car/honda/carstate.py b/selfdrive/car/honda/carstate.py
index 0de09f5fc..d081fef0d 100644
--- a/selfdrive/car/honda/carstate.py
+++ b/selfdrive/car/honda/carstate.py
@@ -5,7 +5,10 @@ from opendbc.can.can_define import CANDefine
from opendbc.can.parser import CANParser
from selfdrive.config import Conversions as CV
from selfdrive.car.interfaces import CarStateBase
-from selfdrive.car.honda.values import CAR, DBC, STEER_THRESHOLD, SPEED_FACTOR, HONDA_BOSCH
+from selfdrive.car.honda.values import CAR, DBC, STEER_THRESHOLD, SPEED_FACTOR, HONDA_BOSCH, HONDA_BOSCH_ALT_BRAKE_SIGNAL
+
+TransmissionType = car.CarParams.TransmissionType
+
def calc_cruise_offset(offset, speed):
# euristic formula so that speed is controlled to ~ 0.3m/s below pid_speed
@@ -19,7 +22,7 @@ def calc_cruise_offset(offset, speed):
return min(_K0 + _K1 * speed + _K2 * speed * offset, 0.)
-def get_can_signals(CP):
+def get_can_signals(CP, gearbox_msg="GEARBOX"):
# this function generates lists for signal, messages and initial values
signals = [
("XMISSION_SPEED", "ENGINE_DATA", 0),
@@ -33,7 +36,7 @@ def get_can_signals(CP):
("STEER_TORQUE_SENSOR", "STEER_STATUS", 0),
("LEFT_BLINKER", "SCM_FEEDBACK", 0),
("RIGHT_BLINKER", "SCM_FEEDBACK", 0),
- ("GEAR", "GEARBOX", 0),
+ ("GEAR", gearbox_msg, 0),
("SEATBELT_DRIVER_LAMP", "SEATBELT_STATUS", 1),
("SEATBELT_DRIVER_LATCHED", "SEATBELT_STATUS", 0),
("BRAKE_PRESSED", "POWERTRAIN_DATA", 0),
@@ -43,7 +46,7 @@ def get_can_signals(CP):
("USER_BRAKE", "VSA_STATUS", 0),
("BRAKE_HOLD_ACTIVE", "VSA_STATUS", 0),
("STEER_STATUS", "STEER_STATUS", 5),
- ("GEAR_SHIFTER", "GEARBOX", 0),
+ ("GEAR_SHIFTER", gearbox_msg, 0),
("PEDAL_GAS", "POWERTRAIN_DATA", 0),
("CRUISE_SETTING", "SCM_BUTTONS", 0),
("ACC_STATUS", "POWERTRAIN_DATA", 0),
@@ -74,19 +77,18 @@ def get_can_signals(CP):
if CP.carFingerprint in (CAR.CRV_HYBRID, CAR.CIVIC_BOSCH_DIESEL, CAR.ACURA_RDX_3G):
checks += [
- ("GEARBOX", 50),
+ (gearbox_msg, 50),
]
else:
checks += [
- ("GEARBOX", 100),
+ (gearbox_msg, 100),
]
- if CP.carFingerprint in HONDA_BOSCH:
- # Civic is only bosch to use the same brake message as other hondas.
- if CP.carFingerprint not in (CAR.ACCORDH, CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_HYBRID, CAR.INSIGHT):
- signals += [("BRAKE_PRESSED", "BRAKE_MODULE", 0)]
- checks += [("BRAKE_MODULE", 50)]
+ if CP.carFingerprint in HONDA_BOSCH_ALT_BRAKE_SIGNAL:
+ signals += [("BRAKE_PRESSED", "BRAKE_MODULE", 0)]
+ checks += [("BRAKE_MODULE", 50)]
+ if CP.carFingerprint in HONDA_BOSCH:
signals += [
("CAR_GAS", "GAS_PEDAL_2", 0),
("MAIN_ON", "SCM_FEEDBACK", 0),
@@ -118,7 +120,8 @@ def get_can_signals(CP):
checks += [("CRUISE_PARAMS", 10)]
else:
checks += [("CRUISE_PARAMS", 50)]
- if CP.carFingerprint in (CAR.ACCORD, CAR.ACCORD_15, CAR.ACCORDH, CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_HYBRID, CAR.INSIGHT, CAR.ACURA_RDX_3G):
+
+ if CP.carFingerprint in (CAR.ACCORD, CAR.ACCORDH, CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_HYBRID, CAR.INSIGHT, CAR.ACURA_RDX_3G):
signals += [("DRIVERS_DOOR_OPEN", "SCM_FEEDBACK", 1)]
elif CP.carFingerprint == CAR.ODYSSEY_CHN:
signals += [("DRIVERS_DOOR_OPEN", "SCM_BUTTONS", 1)]
@@ -195,13 +198,17 @@ def get_can_signals(CP):
class CarState(CarStateBase):
def __init__(self, CP):
super().__init__(CP)
- can_define = CANDefine(DBC[CP.carFingerprint]['pt'])
- self.shifter_values = can_define.dv["GEARBOX"]["GEAR_SHIFTER"]
+ can_define = CANDefine(DBC[CP.carFingerprint]["pt"])
+ self.gearbox_msg = "GEARBOX"
+ if CP.carFingerprint == CAR.ACCORD and CP.transmissionType == TransmissionType.cvt:
+ self.gearbox_msg = "GEARBOX_15T"
+
+ 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.user_gas, self.user_gas_pressed = 0., 0
self.brake_switch_prev = 0
- self.brake_switch_ts = 0
+ self.brake_switch_prev_ts = 0
self.cruise_setting = 0
self.v_cruise_pcm_prev = 0
self.cruise_mode = 0
@@ -219,119 +226,115 @@ class CarState(CarStateBase):
# ******************* parse out can *******************
# TODO: find wheels moving bit in dbc
- if self.CP.carFingerprint in (CAR.ACCORD, CAR.ACCORD_15, CAR.ACCORDH, CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_HYBRID, CAR.INSIGHT, CAR.ACURA_RDX_3G):
- ret.standstill = cp.vl["ENGINE_DATA"]['XMISSION_SPEED'] < 0.1
- ret.doorOpen = bool(cp.vl["SCM_FEEDBACK"]['DRIVERS_DOOR_OPEN'])
+ if self.CP.carFingerprint in (CAR.ACCORD, CAR.ACCORDH, CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_HYBRID, CAR.INSIGHT, CAR.ACURA_RDX_3G):
+ ret.standstill = cp.vl["ENGINE_DATA"]["XMISSION_SPEED"] < 0.1
+ ret.doorOpen = bool(cp.vl["SCM_FEEDBACK"]["DRIVERS_DOOR_OPEN"])
elif self.CP.carFingerprint == CAR.ODYSSEY_CHN:
- ret.standstill = cp.vl["ENGINE_DATA"]['XMISSION_SPEED'] < 0.1
- ret.doorOpen = bool(cp.vl["SCM_BUTTONS"]['DRIVERS_DOOR_OPEN'])
+ ret.standstill = cp.vl["ENGINE_DATA"]["XMISSION_SPEED"] < 0.1
+ ret.doorOpen = bool(cp.vl["SCM_BUTTONS"]["DRIVERS_DOOR_OPEN"])
elif self.CP.carFingerprint == CAR.HRV:
- ret.doorOpen = bool(cp.vl["SCM_BUTTONS"]['DRIVERS_DOOR_OPEN'])
+ ret.doorOpen = bool(cp.vl["SCM_BUTTONS"]["DRIVERS_DOOR_OPEN"])
else:
- ret.standstill = not cp.vl["STANDSTILL"]['WHEELS_MOVING']
- ret.doorOpen = any([cp.vl["DOORS_STATUS"]['DOOR_OPEN_FL'], cp.vl["DOORS_STATUS"]['DOOR_OPEN_FR'],
- cp.vl["DOORS_STATUS"]['DOOR_OPEN_RL'], cp.vl["DOORS_STATUS"]['DOOR_OPEN_RR']])
- ret.seatbeltUnlatched = bool(cp.vl["SEATBELT_STATUS"]['SEATBELT_DRIVER_LAMP'] or not cp.vl["SEATBELT_STATUS"]['SEATBELT_DRIVER_LATCHED'])
+ ret.standstill = not cp.vl["STANDSTILL"]["WHEELS_MOVING"]
+ ret.doorOpen = any([cp.vl["DOORS_STATUS"]["DOOR_OPEN_FL"], cp.vl["DOORS_STATUS"]["DOOR_OPEN_FR"],
+ cp.vl["DOORS_STATUS"]["DOOR_OPEN_RL"], cp.vl["DOORS_STATUS"]["DOOR_OPEN_RR"]])
+ ret.seatbeltUnlatched = bool(cp.vl["SEATBELT_STATUS"]["SEATBELT_DRIVER_LAMP"] or not cp.vl["SEATBELT_STATUS"]["SEATBELT_DRIVER_LATCHED"])
- steer_status = self.steer_status_values[cp.vl["STEER_STATUS"]['STEER_STATUS']]
- ret.steerError = steer_status not in ['NORMAL', 'NO_TORQUE_ALERT_1', 'NO_TORQUE_ALERT_2', 'LOW_SPEED_LOCKOUT', 'TMP_FAULT']
+ 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"]
# 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:
- 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
+ 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
speed_factor = SPEED_FACTOR[self.CP.carFingerprint]
- ret.wheelSpeeds.fl = cp.vl["WHEEL_SPEEDS"]['WHEEL_SPEED_FL'] * CV.KPH_TO_MS * speed_factor
- ret.wheelSpeeds.fr = cp.vl["WHEEL_SPEEDS"]['WHEEL_SPEED_FR'] * CV.KPH_TO_MS * speed_factor
- ret.wheelSpeeds.rl = cp.vl["WHEEL_SPEEDS"]['WHEEL_SPEED_RL'] * CV.KPH_TO_MS * speed_factor
- ret.wheelSpeeds.rr = cp.vl["WHEEL_SPEEDS"]['WHEEL_SPEED_RR'] * CV.KPH_TO_MS * speed_factor
+ ret.wheelSpeeds.fl = cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_FL"] * CV.KPH_TO_MS * speed_factor
+ ret.wheelSpeeds.fr = cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_FR"] * CV.KPH_TO_MS * speed_factor
+ ret.wheelSpeeds.rl = cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_RL"] * CV.KPH_TO_MS * speed_factor
+ ret.wheelSpeeds.rr = cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_RR"] * CV.KPH_TO_MS * speed_factor
v_wheel = (ret.wheelSpeeds.fl + ret.wheelSpeeds.fr + ret.wheelSpeeds.rl + ret.wheelSpeeds.rr)/4.
# blend in transmission speed at low speed, since it has more low speed accuracy
v_weight = interp(v_wheel, v_weight_bp, v_weight_v)
- ret.vEgoRaw = (1. - v_weight) * cp.vl["ENGINE_DATA"]['XMISSION_SPEED'] * CV.KPH_TO_MS * speed_factor + v_weight * v_wheel
+ ret.vEgoRaw = (1. - v_weight) * cp.vl["ENGINE_DATA"]["XMISSION_SPEED"] * CV.KPH_TO_MS * speed_factor + v_weight * v_wheel
ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw)
- ret.steeringAngleDeg = cp.vl["STEERING_SENSORS"]['STEER_ANGLE']
- ret.steeringRateDeg = cp.vl["STEERING_SENSORS"]['STEER_ANGLE_RATE']
+ ret.steeringAngleDeg = cp.vl["STEERING_SENSORS"]["STEER_ANGLE"]
+ ret.steeringRateDeg = cp.vl["STEERING_SENSORS"]["STEER_ANGLE_RATE"]
- self.cruise_setting = cp.vl["SCM_BUTTONS"]['CRUISE_SETTING']
- self.cruise_buttons = cp.vl["SCM_BUTTONS"]['CRUISE_BUTTONS']
+ self.cruise_setting = cp.vl["SCM_BUTTONS"]["CRUISE_SETTING"]
+ self.cruise_buttons = cp.vl["SCM_BUTTONS"]["CRUISE_BUTTONS"]
- ret.leftBlinker = cp.vl["SCM_FEEDBACK"]['LEFT_BLINKER'] != 0
- ret.rightBlinker = cp.vl["SCM_FEEDBACK"]['RIGHT_BLINKER'] != 0
- self.brake_hold = cp.vl["VSA_STATUS"]['BRAKE_HOLD_ACTIVE']
+ ret.leftBlinker = cp.vl["SCM_FEEDBACK"]["LEFT_BLINKER"] != 0
+ ret.rightBlinker = cp.vl["SCM_FEEDBACK"]["RIGHT_BLINKER"] != 0
+ self.brake_hold = cp.vl["VSA_STATUS"]["BRAKE_HOLD_ACTIVE"]
- if self.CP.carFingerprint in (CAR.CIVIC, CAR.ODYSSEY, CAR.CRV_5G, CAR.ACCORD, CAR.ACCORD_15, CAR.ACCORDH, CAR.CIVIC_BOSCH,
+ if self.CP.carFingerprint in (CAR.CIVIC, CAR.ODYSSEY, CAR.CRV_5G, CAR.ACCORD, CAR.ACCORDH, CAR.CIVIC_BOSCH,
CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_HYBRID, CAR.INSIGHT, CAR.ACURA_RDX_3G):
- self.park_brake = cp.vl["EPB_STATUS"]['EPB_STATE'] != 0
- main_on = cp.vl["SCM_FEEDBACK"]['MAIN_ON']
+ self.park_brake = cp.vl["EPB_STATUS"]["EPB_STATE"] != 0
+ main_on = cp.vl["SCM_FEEDBACK"]["MAIN_ON"]
elif self.CP.carFingerprint == CAR.ODYSSEY_CHN:
- self.park_brake = cp.vl["EPB_STATUS"]['EPB_STATE'] != 0
- main_on = cp.vl["SCM_BUTTONS"]['MAIN_ON']
+ self.park_brake = cp.vl["EPB_STATUS"]["EPB_STATE"] != 0
+ main_on = cp.vl["SCM_BUTTONS"]["MAIN_ON"]
else:
self.park_brake = 0 # TODO
- main_on = cp.vl["SCM_BUTTONS"]['MAIN_ON']
+ main_on = cp.vl["SCM_BUTTONS"]["MAIN_ON"]
- gear = int(cp.vl["GEARBOX"]['GEAR_SHIFTER'])
+ gear = int(cp.vl[self.gearbox_msg]["GEAR_SHIFTER"])
ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(gear, None))
- self.pedal_gas = cp.vl["POWERTRAIN_DATA"]['PEDAL_GAS']
+ self.pedal_gas = cp.vl["POWERTRAIN_DATA"]["PEDAL_GAS"]
# crv doesn't include cruise control
if self.CP.carFingerprint in (CAR.CRV, CAR.CRV_EU, CAR.HRV, CAR.ODYSSEY, CAR.ACURA_RDX, CAR.RIDGELINE, CAR.PILOT_2019, CAR.ODYSSEY_CHN):
ret.gas = self.pedal_gas / 256.
else:
- ret.gas = cp.vl["GAS_PEDAL_2"]['CAR_GAS'] / 256.
+ ret.gas = cp.vl["GAS_PEDAL_2"]["CAR_GAS"] / 256.
# 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:
- self.user_gas = (cp.vl["GAS_SENSOR"]['INTERCEPTOR_GAS'] + cp.vl["GAS_SENSOR"]['INTERCEPTOR_GAS2']) / 2.
+ self.user_gas = (cp.vl["GAS_SENSOR"]["INTERCEPTOR_GAS"] + cp.vl["GAS_SENSOR"]["INTERCEPTOR_GAS2"]) / 2.
self.user_gas_pressed = self.user_gas > 1e-5 # this works because interceptor read < 0 when pedal position is 0. Once calibrated, this will change
ret.gasPressed = self.user_gas_pressed
else:
ret.gasPressed = self.pedal_gas > 1e-5
- ret.steeringTorque = cp.vl["STEER_STATUS"]['STEER_TORQUE_SENSOR']
- ret.steeringTorqueEps = cp.vl["STEER_MOTOR_TORQUE"]['MOTOR_TORQUE']
+ ret.steeringTorque = cp.vl["STEER_STATUS"]["STEER_TORQUE_SENSOR"]
+ ret.steeringTorqueEps = cp.vl["STEER_MOTOR_TORQUE"]["MOTOR_TORQUE"]
ret.steeringPressed = abs(ret.steeringTorque) > STEER_THRESHOLD[self.CP.carFingerprint]
- self.brake_switch = cp.vl["POWERTRAIN_DATA"]['BRAKE_SWITCH'] != 0
-
if self.CP.carFingerprint in HONDA_BOSCH:
- self.cruise_mode = cp.vl["ACC_HUD"]['CRUISE_CONTROL_LABEL']
- ret.cruiseState.standstill = cp.vl["ACC_HUD"]['CRUISE_SPEED'] == 252.
+ self.cruise_mode = cp.vl["ACC_HUD"]["CRUISE_CONTROL_LABEL"]
+ ret.cruiseState.standstill = cp.vl["ACC_HUD"]["CRUISE_SPEED"] == 252.
ret.cruiseState.speedOffset = calc_cruise_offset(0, ret.vEgo)
- if self.CP.carFingerprint in (CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.ACCORDH, CAR.CRV_HYBRID, CAR.INSIGHT):
- 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_ts))
- self.brake_switch_prev = self.brake_switch
- self.brake_switch_ts = cp.ts["POWERTRAIN_DATA"]['BRAKE_SWITCH']
- else:
- ret.brakePressed = cp.vl["BRAKE_MODULE"]['BRAKE_PRESSED'] != 0
# On set, cruise set speed pulses between 254~255 and the set speed prev is set to avoid this.
- ret.cruiseState.speed = self.v_cruise_pcm_prev if cp.vl["ACC_HUD"]['CRUISE_SPEED'] > 160.0 else cp.vl["ACC_HUD"]['CRUISE_SPEED'] * CV.KPH_TO_MS
+ ret.cruiseState.speed = self.v_cruise_pcm_prev if cp.vl["ACC_HUD"]["CRUISE_SPEED"] > 160.0 else cp.vl["ACC_HUD"]["CRUISE_SPEED"] * CV.KPH_TO_MS
self.v_cruise_pcm_prev = ret.cruiseState.speed
else:
- ret.cruiseState.speedOffset = calc_cruise_offset(cp.vl["CRUISE_PARAMS"]['CRUISE_SPEED_OFFSET'], ret.vEgo)
- ret.cruiseState.speed = cp.vl["CRUISE"]['CRUISE_SPEED_PCM'] * CV.KPH_TO_MS
+ ret.cruiseState.speedOffset = calc_cruise_offset(cp.vl["CRUISE_PARAMS"]["CRUISE_SPEED_OFFSET"], ret.vEgo)
+ 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
- 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_ts))
- self.brake_switch_prev = self.brake_switch
- self.brake_switch_ts = cp.ts["POWERTRAIN_DATA"]['BRAKE_SWITCH']
+ # 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))
- ret.brake = cp.vl["VSA_STATUS"]['USER_BRAKE']
- ret.cruiseState.enabled = cp.vl["POWERTRAIN_DATA"]['ACC_STATUS'] != 0
+ self.brake_switch_prev = self.brake_switch
+ self.brake_switch_prev_ts = cp.ts["POWERTRAIN_DATA"]["BRAKE_SWITCH"]
+
+ ret.brake = cp.vl["VSA_STATUS"]["USER_BRAKE"]
+ ret.cruiseState.enabled = cp.vl["POWERTRAIN_DATA"]["ACC_STATUS"] != 0
ret.cruiseState.available = bool(main_on)
ret.cruiseState.nonAdaptive = self.cruise_mode != 0
@@ -341,7 +344,7 @@ class CarState(CarStateBase):
ret.brakePressed = True
# TODO: discover the CAN msg that has the imperial unit bit for all other cars
- self.is_metric = not cp.vl["HUD_SETTING"]['IMPERIAL_UNIT'] if self.CP.carFingerprint in (CAR.CIVIC) else False
+ self.is_metric = not cp.vl["HUD_SETTING"]["IMPERIAL_UNIT"] if self.CP.carFingerprint in (CAR.CIVIC) else False
if self.CP.carFingerprint in HONDA_BOSCH:
ret.stockAeb = bool(cp.vl["ACC_CONTROL"]["AEB_STATUS"] and cp.vl["ACC_CONTROL"]["ACCEL_COMMAND"] < -1e-5)
@@ -359,16 +362,15 @@ class CarState(CarStateBase):
if self.CP.enableBsm and self.CP.carFingerprint in (CAR.CRV_5G, ):
# BSM messages are on B-CAN, requires a panda forwarding B-CAN messages to CAN 0
# more info here: https://github.com/commaai/openpilot/pull/1867
- ret.leftBlindspot = cp_body.vl["BSM_STATUS_LEFT"]['BSM_ALERT'] == 1
- ret.rightBlindspot = cp_body.vl["BSM_STATUS_RIGHT"]['BSM_ALERT'] == 1
+ ret.leftBlindspot = cp_body.vl["BSM_STATUS_LEFT"]["BSM_ALERT"] == 1
+ ret.rightBlindspot = cp_body.vl["BSM_STATUS_RIGHT"]["BSM_ALERT"] == 1
return ret
- @staticmethod
- def get_can_parser(CP):
- signals, checks = get_can_signals(CP)
+ def get_can_parser(self, CP):
+ signals, checks = get_can_signals(CP, self.gearbox_msg)
bus_pt = 1 if CP.carFingerprint in HONDA_BOSCH else 0
- return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, bus_pt)
+ return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, bus_pt)
@staticmethod
def get_cam_can_parser(CP):
@@ -393,7 +395,7 @@ class CarState(CarStateBase):
("BRAKE_COMMAND", 50),
]
- return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 2)
+ return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 2)
@staticmethod
def get_body_can_parser(CP):
@@ -406,5 +408,5 @@ class CarState(CarStateBase):
("BSM_STATUS_RIGHT", 3),
]
bus_body = 0 # B-CAN is forwarded to ACC-CAN radar side (CAN 0 on fake ethernet port)
- return CANParser(DBC[CP.carFingerprint]['body'], signals, checks, bus_body)
+ return CANParser(DBC[CP.carFingerprint]["body"], signals, checks, bus_body)
return None
diff --git a/selfdrive/car/honda/interface.py b/selfdrive/car/honda/interface.py
index 673349aa1..279f95b61 100755
--- a/selfdrive/car/honda/interface.py
+++ b/selfdrive/car/honda/interface.py
@@ -2,11 +2,9 @@
import numpy as np
from cereal import car
from common.numpy_fast import clip, interp
-from common.realtime import DT_CTRL
from selfdrive.swaglog import cloudlog
from selfdrive.config import Conversions as CV
-from selfdrive.controls.lib.events import ET
-from selfdrive.car.honda.values import CruiseButtons, CAR, HONDA_BOSCH
+from selfdrive.car.honda.values import CruiseButtons, CAR, HONDA_BOSCH, HONDA_BOSCH_ALT_BRAKE_SIGNAL
from selfdrive.car import STD_CARGO_KG, CivicParams, scale_rot_inertia, scale_tire_stiffness, gen_empty_fingerprint
from selfdrive.controls.lib.longitudinal_planner import _A_CRUISE_MAX_V_FOLLOWING
from selfdrive.car.interfaces import CarInterfaceBase
@@ -15,6 +13,7 @@ A_ACC_MAX = max(_A_CRUISE_MAX_V_FOLLOWING)
ButtonType = car.CarState.ButtonEvent.Type
EventName = car.CarEvent.EventName
+TransmissionType = car.CarParams.TransmissionType
def compute_gb_honda(accel, speed):
@@ -75,9 +74,6 @@ class CarInterface(CarInterfaceBase):
def __init__(self, CP, CarController, CarState):
super().__init__(CP, CarController, CarState)
- self.last_enable_pressed = 0
- self.last_enable_sent = 0
-
if self.CS.CP.carFingerprint == CAR.ACURA_ILX:
self.compute_gb = get_compute_gb_acura()
else:
@@ -138,6 +134,10 @@ class CarInterface(CarInterfaceBase):
if candidate == CAR.CRV_5G:
ret.enableBsm = 0x12f8bfa7 in fingerprint[0]
+ # Accord 1.5T CVT has different gearbox message
+ if candidate == CAR.ACCORD and 0x191 in fingerprint[0]:
+ ret.transmissionType = TransmissionType.cvt
+
cloudlog.warning("ECU Camera Simulated: %r", ret.enableCamera)
cloudlog.warning("ECU Gas Interceptor: %r", ret.enableGasInterceptor)
@@ -196,10 +196,8 @@ class CarInterface(CarInterfaceBase):
ret.longitudinalTuning.kiBP = [0., 35.]
ret.longitudinalTuning.kiV = [0.18, 0.12]
- elif candidate in (CAR.ACCORD, CAR.ACCORD_15, CAR.ACCORDH):
+ elif candidate in (CAR.ACCORD, CAR.ACCORDH):
stop_and_go = True
- if not candidate == CAR.ACCORDH: # Hybrid uses same brake msg as hatch
- ret.safetyParam = 1 # Accord(ICE), CRV 5G, and RDX 3G use an alternate user brake msg
ret.mass = 3279. * CV.LB_TO_KG + STD_CARGO_KG
ret.wheelbase = 2.83
ret.centerToFront = ret.wheelbase * 0.39
@@ -246,7 +244,6 @@ class CarInterface(CarInterfaceBase):
elif candidate == CAR.CRV_5G:
stop_and_go = True
- ret.safetyParam = 1 # Accord(ICE), CRV 5G, and RDX 3G use an alternate user brake msg
ret.mass = 3410. * CV.LB_TO_KG + STD_CARGO_KG
ret.wheelbase = 2.66
ret.centerToFront = ret.wheelbase * 0.41
@@ -324,7 +321,6 @@ class CarInterface(CarInterfaceBase):
elif candidate == CAR.ACURA_RDX_3G:
stop_and_go = True
- ret.safetyParam = 1 # Accord(ICE), CRV 5G, and RDX 3G use an alternate user brake msg
ret.mass = 4068. * CV.LB_TO_KG + STD_CARGO_KG
ret.wheelbase = 2.75
ret.centerToFront = ret.wheelbase * 0.41
@@ -410,6 +406,10 @@ class CarInterface(CarInterfaceBase):
else:
raise ValueError("unsupported car %s" % candidate)
+ # These cars use alternate user brake msg (0x1BE)
+ if candidate in HONDA_BOSCH_ALT_BRAKE_SIGNAL:
+ ret.safetyParam = 1
+
# min speed to enable ACC. if car can do stop and go, then set enabling speed
# to a negative value, so it won't matter. Otherwise, add 0.5 mph margin to not
# conflict with PCM acc
@@ -450,10 +450,6 @@ class CarInterface(CarInterfaceBase):
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)
- # FIXME: read sendcan for brakelights
- brakelights_threshold = 0.02 if self.CS.CP.carFingerprint == CAR.CIVIC else 0.1
- ret.brakeLights = bool(self.CS.brake_switch or
- c.actuators.brake > brakelights_threshold)
buttonEvents = []
@@ -492,7 +488,7 @@ class CarInterface(CarInterfaceBase):
ret.buttonEvents = buttonEvents
# events
- events = self.create_common_events(ret, pcm_enable=False)
+ events = self.create_common_events(ret, pcm_enable=self.CP.enableCruise)
if self.CS.brake_error:
events.add(EventName.brakeUnavailable)
if self.CS.brake_hold and self.CS.CP.openpilotLongitudinalControl:
@@ -515,34 +511,18 @@ class CarInterface(CarInterfaceBase):
if self.CS.CP.minEnableSpeed > 0 and ret.vEgo < 0.001:
events.add(EventName.manualRestart)
- cur_time = self.frame * DT_CTRL
- enable_pressed = False
# 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:
- self.last_enable_pressed = cur_time
- enable_pressed = True
+ if not self.CP.enableCruise:
+ events.add(EventName.buttonEnable)
# do disable on button down
- if b.type == "cancel" and b.pressed:
+ if b.type == ButtonType.cancel and b.pressed:
events.add(EventName.buttonCancel)
- if self.CP.enableCruise:
- # KEEP THIS EVENT LAST! send enable event if button is pressed and there are
- # NO_ENTRY events, so controlsd will display alerts. Also not send enable events
- # too close in time, so a no_entry will not be followed by another one.
- # TODO: button press should be the only thing that triggers enable
- if ((cur_time - self.last_enable_pressed) < 0.2 and
- (cur_time - self.last_enable_sent) > 0.2 and
- ret.cruiseState.enabled) or \
- (enable_pressed and events.any(ET.NO_ENTRY)):
- events.add(EventName.buttonEnable)
- self.last_enable_sent = cur_time
- elif enable_pressed:
- events.add(EventName.buttonEnable)
-
ret.events = events.to_msg()
self.CS.out = ret.as_reader()
diff --git a/selfdrive/car/honda/values.py b/selfdrive/car/honda/values.py
index a63b45976..79bc28d29 100644
--- a/selfdrive/car/honda/values.py
+++ b/selfdrive/car/honda/values.py
@@ -34,8 +34,7 @@ VISUAL_HUD = {
VisualAlert.speedTooHigh: 8}
class CAR:
- ACCORD = "HONDA ACCORD 2T 2018"
- ACCORD_15 = "HONDA ACCORD 1.5T 2018"
+ ACCORD = "HONDA ACCORD 2018"
ACCORDH = "HONDA ACCORD HYBRID 2018"
CIVIC = "HONDA CIVIC 2016"
CIVIC_BOSCH = "HONDA CIVIC (BOSCH) 2019"
@@ -63,9 +62,6 @@ FINGERPRINTS = {
CAR.ACCORD: [{
148: 8, 228: 5, 304: 8, 330: 8, 344: 8, 380: 8, 399: 7, 419: 8, 420: 8, 427: 3, 432: 7, 441: 5, 446: 3, 450: 8, 464: 8, 477: 8, 479: 8, 495: 8, 545: 6, 662: 4, 773: 7, 777: 8, 780: 8, 804: 8, 806: 8, 808: 8, 829: 5, 862: 8, 884: 8, 891: 8, 927: 8, 929: 8, 1302: 8, 1600: 5, 1601: 8, 1652: 8
}],
- CAR.ACCORD_15: [{
- 148: 8, 228: 5, 304: 8, 330: 8, 344: 8, 380: 8, 399: 7, 401: 8, 420: 8, 427: 3, 432: 7, 441: 5, 446: 3, 450: 8, 464: 8, 477: 8, 479: 8, 495: 8, 545: 6, 662: 4, 773: 7, 777: 8, 780: 8, 804: 8, 806: 8, 808: 8, 829: 5, 862: 8, 884: 8, 891: 8, 927: 8, 929: 8, 1302: 8, 1600: 5, 1601: 8, 1652: 8
- }],
CAR.ACCORDH: [{
148: 8, 228: 5, 304: 8, 330: 8, 344: 8, 380: 8, 387: 8, 388: 8, 399: 7, 419: 8, 420: 8, 427: 3, 432: 7, 441: 5, 450: 8, 464: 8, 477: 8, 479: 8, 495: 8, 525: 8, 545: 6, 662: 4, 773: 7, 777: 8, 780: 8, 804: 8, 806: 8, 808: 8, 829: 5, 862: 8, 884: 8, 891: 8, 927: 8, 929: 8, 1302: 8, 1600: 5, 1601: 8, 1652: 8
}],
@@ -76,9 +72,6 @@ FINGERPRINTS = {
CAR.ACURA_RDX: [{
57: 3, 145: 8, 229: 4, 308: 5, 316: 8, 342: 6, 344: 8, 380: 8, 392: 6, 398: 3, 399: 6, 404: 4, 420: 8, 422: 8, 426: 8, 432: 7, 464: 8, 474: 5, 476: 4, 487: 4, 490: 8, 506: 8, 512: 6, 513: 6, 542: 7, 545: 4, 597: 8, 660: 8, 773: 7, 777: 8, 780: 8, 800: 8, 804: 8, 808: 8, 819: 7, 821: 5, 829: 5, 882: 2, 884: 7, 887: 8, 888: 8, 892: 8, 923: 2, 929: 4, 963: 8, 965: 8, 966: 8, 967: 8, 983: 8, 985: 3, 1024: 5, 1027: 5, 1029: 8, 1033: 5, 1034: 5, 1036: 8, 1039: 8, 1057: 5, 1064: 7, 1108: 8, 1365: 5, 1424: 5, 1729: 1
}],
- CAR.ACURA_RDX_3G: [{
- 57: 3, 148: 8, 228: 5, 304: 8, 330: 8, 344: 8, 380: 8, 399: 7, 401: 8, 420: 8, 423: 2, 427: 3, 428: 8, 432: 7, 441: 5, 450: 8, 464: 8, 470: 2, 476: 7, 477: 8, 479: 8, 490: 8, 493: 5, 495: 8, 506: 8, 507: 1, 545: 6, 597: 8, 662: 4, 773: 7, 777: 8, 780: 8, 795: 8, 800: 8, 804: 8, 806: 8, 808: 8, 815: 8, 825: 4, 829: 5, 846: 8, 862: 8, 881: 8, 882: 4, 884: 8, 888: 8, 891: 8, 892: 8, 918: 7, 927: 8, 929: 8, 983: 8, 985: 3, 1024: 5, 1027: 5, 1029: 8, 1036: 8, 1039: 8, 1064: 6, 1092: 1, 1108: 8, 1115: 2, 1125: 8, 1127: 2, 1296: 8, 1302: 8, 1322: 5, 1361: 5, 1365: 5, 1424: 5, 1600: 5, 1601: 8, 1633: 8
- }],
CAR.CIVIC: [{
57: 3, 148: 8, 228: 5, 304: 8, 330: 8, 344: 8, 380: 8, 399: 7, 401: 8, 420: 8, 427: 3, 428: 8, 432: 7, 450: 8, 464: 8, 470: 2, 476: 7, 487: 4, 490: 8, 493: 5, 506: 8, 512: 6, 513: 6, 545: 6, 597: 8, 662: 4, 773: 7, 777: 8, 780: 8, 795: 8, 800: 8, 804: 8, 806: 8, 808: 8, 829: 5, 862: 8, 884: 8, 891: 8, 892: 8, 927: 8, 929: 8, 985: 3, 1024: 5, 1027: 5, 1029: 8, 1036: 8, 1039: 8, 1108: 8, 1302: 8, 1322: 5, 1361: 5, 1365: 5, 1424: 5, 1633: 8,
}],
@@ -90,29 +83,12 @@ FINGERPRINTS = {
{
57: 3, 148: 8, 228: 5, 304: 8, 330: 8, 344: 8, 380: 8, 399: 7, 401: 8, 420: 8, 423: 2, 427: 3, 428: 8, 432: 7, 441: 5, 450: 8, 464: 8, 470: 2, 476: 7, 477: 8, 479: 8, 490: 8, 493: 5, 495: 8, 506: 8, 545: 6, 597: 8, 662: 4, 773: 7, 777: 8, 780: 8, 795: 8, 800: 8, 804: 8, 806: 8, 808: 8, 815: 8, 825: 4, 829: 5, 846: 8, 862: 8, 881: 8, 882: 4, 884: 8, 888: 8, 891: 8, 892: 8, 918: 7, 927: 8, 929: 8, 983: 8, 985: 3, 1024: 5, 1027: 5, 1029: 8, 1036: 8, 1039: 8, 1064: 7, 1092: 1, 1108: 8, 1125: 8, 1127: 2, 1296: 8, 1302: 8, 1322: 5, 1361: 5, 1365: 5, 1424: 5, 1600: 5, 1601: 8, 1633: 8
}],
- CAR.CIVIC_BOSCH_DIESEL: [{
- # 2019 Civic Sedan 1.6 i-dtec Diesel European
- 57: 3, 148: 8, 228: 5, 308: 5, 316: 8, 330: 8, 344: 8, 380: 8, 399: 7, 419: 8, 420: 8, 426: 8, 427: 3, 432: 7, 441: 5, 450: 8, 464: 8, 470: 2, 476: 7, 477: 8, 479: 8, 490: 8, 493: 5, 495: 8, 506: 8, 507: 1, 545: 6, 597: 8, 662: 4, 773: 7, 777: 8, 780: 8, 795: 8, 800: 8, 801: 3, 804: 8, 806: 8, 808: 8, 815: 8, 824: 8, 825: 4, 829: 5, 837: 5, 862: 8, 881: 8, 882: 4, 884: 8, 887: 8, 888: 8, 891: 8, 902: 8, 918: 7, 927: 8, 929: 8, 983: 8, 985: 3, 1024: 5, 1027: 5, 1029: 8, 1036: 8, 1039: 8, 1064: 7, 1092: 1, 1108: 8, 1115: 2, 1125: 8, 1296: 8, 1302: 8, 1322: 5, 1337: 5, 1361: 5, 1365: 5, 1424: 5, 1600: 5, 1601: 8
- }],
- CAR.CRV: [{
- 57: 3, 145: 8, 316: 8, 340: 8, 342: 6, 344: 8, 380: 8, 398: 3, 399: 6, 401: 8, 404: 4, 420: 8, 422: 8, 426: 8, 432: 7, 464: 8, 474: 5, 476: 4, 487: 4, 490: 8, 493: 3, 506: 8, 507: 1, 512: 6, 513: 6, 542: 7, 545: 4, 597: 8, 660: 8, 661: 4, 773: 7, 777: 8, 780: 8, 800: 8, 804: 8, 808: 8, 829: 5, 882: 2, 884: 7, 888: 8, 891: 8, 892: 8, 923: 2, 929: 8, 983: 8, 985: 3, 1024: 5, 1027: 5, 1029: 8, 1033: 5, 1036: 8, 1039: 8, 1057: 5, 1064: 7, 1108: 8, 1125: 8, 1296: 8, 1365: 5, 1424: 5, 1600: 5, 1601: 8,
- }],
CAR.CRV_5G: [{
57: 3, 148: 8, 199: 4, 228: 5, 231: 5, 232: 7, 304: 8, 330: 8, 340: 8, 344: 8, 380: 8, 399: 7, 401: 8, 420: 8, 423: 2, 427: 3, 428: 8, 432: 7, 441: 5, 446: 3, 450: 8, 464: 8, 467: 2, 469: 3, 470: 2, 474: 8, 476: 7, 477: 8, 479: 8, 490: 8, 493: 5, 495: 8, 507: 1, 545: 6, 597: 8, 661: 4, 662: 4, 773: 7, 777: 8, 780: 8, 795: 8, 800: 8, 804: 8, 806: 8, 808: 8, 814: 4, 815: 8, 817: 4, 825: 4, 829: 5, 862: 8, 881: 8, 882: 4, 884: 8, 888: 8, 891: 8, 927: 8, 918: 7, 929: 8, 983: 8, 985: 3, 1024: 5, 1027: 5, 1029: 8, 1036: 8, 1039: 8, 1064: 7, 1108: 8, 1092: 1, 1115: 2, 1125: 8, 1127: 2, 1296: 8, 1302: 8, 1322: 5, 1361: 5, 1365: 5, 1424: 5, 1600: 5, 1601: 8, 1618: 5, 1633: 8, 1670: 5
}],
- # 1057: 5 1024: 5 are also on the OBD2 bus. their lengths differ from the camera's f-can bus. re-fingerprint after obd2 connection is split in panda firmware from bus 1.
- CAR.CRV_EU: [{
- 57: 3, 145: 8, 308: 5, 316: 8, 342: 6, 344: 8, 380: 8, 398: 3, 399: 6, 404: 4, 419: 8, 420: 8, 422: 8, 426: 8, 432: 7, 464: 8, 474: 5, 476: 4, 487: 4, 490: 8, 493: 3, 506: 8, 507: 1, 510: 3, 538: 3, 542: 7, 545: 4, 597: 8, 660: 8, 661: 4, 768: 8, 769: 8, 773: 7, 777: 8, 780: 8, 800: 8, 801: 3, 803: 8, 804: 8, 808: 8, 824: 8, 829: 5, 837: 5, 862: 8, 882: 2, 884: 7, 888: 8, 891: 8, 892: 8, 923: 2, 927: 8, 929: 8, 930: 8, 931: 8, 983: 8, 1024: 8, 1027: 5, 1029: 8, 1033: 5, 1036: 8, 1039: 8, 1040: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1045: 8, 1046: 8, 1047: 8, 1056: 8, 1057: 8, 1058: 8, 1059: 8, 1060: 8, 1064: 7, 1072: 8, 1073: 8, 1074: 8, 1075: 8, 1076: 8, 1077: 8, 1078: 8, 1079: 8, 1080: 8, 1081: 8, 1088: 8, 1089: 8, 1090: 8, 1091: 8, 1092: 8, 1093: 8, 1108: 8, 1125: 8, 1279: 8, 1280: 8, 1296: 8, 1297: 8, 1365: 5, 1424: 5, 1600: 5, 1601: 8,
- }],
- CAR.CRV_HYBRID: [{
- 57: 3, 148: 8, 228: 5, 304: 8, 330: 8, 344: 8, 380: 8, 387: 8, 388: 8, 399: 7, 408: 6, 415: 6, 419: 8, 420: 8, 427: 3, 428: 8, 432: 7, 441: 5, 450: 8, 464: 8, 477: 8, 479: 8, 490: 8, 495: 8, 525: 8, 531: 8, 545: 6, 662: 4, 773: 7, 777: 8, 780: 8, 804: 8, 806: 8, 808: 8, 814: 4, 829: 5, 833: 6, 862: 8, 884: 8, 891: 8, 927: 8, 929: 8, 930: 8, 931: 8, 1302: 8, 1361: 5, 1365: 5, 1600: 5, 1601: 8, 1626: 5, 1627: 5
- }],
CAR.FIT: [{
57: 3, 145: 8, 228: 5, 304: 8, 342: 6, 344: 8, 380: 8, 399: 7, 401: 8, 420: 8, 422: 8, 427: 3, 428: 8, 432: 7, 464: 8, 487: 4, 490: 8, 506: 8, 597: 8, 660: 8, 661: 4, 773: 7, 777: 8, 780: 8, 800: 8, 804: 8, 808: 8, 829: 5, 862: 8, 884: 7, 892: 8, 929: 8, 985: 3, 1024: 5, 1027: 5, 1029: 8, 1036: 8, 1039: 8, 1108: 8, 1322: 5, 1361: 5, 1365: 5, 1424: 5, 1600: 5, 1601: 8
}],
- CAR.HRV: [{
- 57: 3, 145: 8, 228: 5, 316: 8, 340: 8, 342: 6, 344: 8, 380: 8, 399: 7, 401: 8, 420: 8, 422: 8, 423: 2, 426: 8, 427: 3, 432: 7, 441: 5, 450: 8, 464: 8, 474: 8, 490: 8, 493: 3, 506: 8, 538: 5, 578: 2, 597: 8, 660: 8, 661: 4, 773: 7, 777: 8, 780: 8, 804: 8, 808: 8, 829: 5, 862: 8, 882: 2, 884: 7, 892: 8, 929: 8, 985: 3, 1030: 5, 1033: 5, 1108: 8, 1137: 8, 1348: 5, 1361: 5, 1365: 5, 1600: 5, 1601: 8, 1618: 5
- }],
# 2018 Odyssey w/ Added Comma Pedal Support (512L & 513L)
CAR.ODYSSEY: [{
57: 3, 148: 8, 228: 5, 229: 4, 316: 8, 342: 6, 344: 8, 380: 8, 399: 7, 411: 5, 419: 8, 420: 8, 427: 3, 432: 7, 450: 8, 463: 8, 464: 8, 476: 4, 490: 8, 506: 8, 512: 6, 513: 6, 542: 7, 545: 6, 597: 8, 662: 4, 773: 7, 777: 8, 780: 8, 795: 8, 800: 8, 804: 8, 806: 8, 808: 8, 817: 4, 819: 7, 821: 5, 825: 4, 829: 5, 837: 5, 856: 7, 862: 8, 871: 8, 881: 8, 882: 4, 884: 8, 891: 8, 892: 8, 905: 8, 923: 2, 927: 8, 929: 8, 963: 8, 965: 8, 966: 8, 967: 8, 983: 8, 985: 3, 1029: 8, 1036: 8, 1052: 8, 1064: 7, 1088: 8, 1089: 8, 1092: 1, 1108: 8, 1110: 8, 1125: 8, 1296: 8, 1302: 8, 1600: 5, 1601: 8, 1612: 5, 1613: 5, 1614: 5, 1615: 8, 1616: 5, 1619: 5, 1623: 5, 1668: 5
@@ -136,23 +112,8 @@ FINGERPRINTS = {
{
57: 3, 145: 8, 228: 5, 229: 4, 308: 5, 316: 8, 339: 7, 342: 6, 344: 8, 380: 8, 392: 6, 399: 7, 411: 5, 419: 8, 420: 8, 422: 8, 425: 8, 426: 8, 427: 3, 432: 7, 464: 8, 476: 4, 490: 8, 506: 8, 512: 6, 513: 6, 542: 7, 545: 5, 546: 3, 597: 8, 660: 8, 773: 7, 777: 8, 780: 8, 795: 8, 800: 8, 804: 8, 808: 8, 817: 4, 819: 7, 821: 5, 829: 5, 871: 8, 881: 8, 882: 2, 884: 7, 891: 8, 892: 8, 923: 2, 927: 8, 929: 8, 963: 8, 965: 8, 966: 8, 967: 8, 983: 8, 985: 3, 1027: 5, 1029: 8, 1039: 8, 1064: 7, 1088: 8, 1089: 8, 1092: 1, 1108: 8, 1125: 8, 1296: 8, 1424: 5, 1445: 8, 1600: 5, 1601: 8, 1612: 5, 1613: 5, 1616: 5, 1617: 8, 1618: 5, 1623: 5, 1668: 5
}],
- # Ridgeline w/ Added Comma Pedal Support (512L & 513L)
- CAR.RIDGELINE: [{
- 57: 3, 145: 8, 228: 5, 229: 4, 308: 5, 316: 8, 339: 7, 342: 6, 344: 8, 380: 8, 392: 6, 399: 7, 419: 8, 420: 8, 422: 8, 425: 8, 426: 8, 427: 3, 432: 7, 464: 8, 471: 3, 476: 4, 490: 8, 506: 8, 512: 6, 513: 6, 545: 5, 546: 3, 597: 8, 660: 8, 773: 7, 777: 8, 780: 8, 795: 8, 800: 8, 804: 8, 808: 8, 819: 7, 821: 5, 829: 5, 871: 8, 882: 2, 884: 7, 892: 8, 923: 2, 927: 8, 929: 8, 963: 8, 965: 8, 966: 8, 967: 8, 983: 8, 985: 3, 1027: 5, 1029: 8, 1036: 8, 1039: 8, 1064: 7, 1088: 8, 1089: 8, 1108: 8, 1125: 8, 1296: 8, 1365: 5, 1424: 5, 1600: 5, 1601: 8, 1613: 5, 1616: 5, 1618: 5, 1668: 5, 2015: 3
- },
- # 2019 Ridgeline
- {
- 57: 3, 145: 8, 228: 5, 229: 4, 308: 5, 316: 8, 339: 7, 342: 6, 344: 8, 380: 8, 392: 6, 399: 7, 419: 8, 420: 8, 422: 8, 425: 8, 426: 8, 427: 3, 432: 7, 464: 8, 476: 4, 490: 8, 512: 6, 513: 6, 545: 5, 546: 3, 597: 8, 660: 8, 773: 7, 777: 8, 795: 8, 800: 8, 804: 8, 808: 8, 819: 7, 821: 5, 871: 8, 882: 2, 884: 7, 892: 8, 923: 2, 929: 8, 963: 8, 965: 8, 966: 8, 967: 8, 983: 8, 985: 3, 1027: 5, 1029: 8, 1036: 8, 1039: 8, 1064: 7, 1088: 8, 1089: 8, 1092: 1, 1108: 8, 1125: 8, 1296: 8, 1365: 5, 424: 5, 1613: 5, 1616: 5, 1618: 5, 1623: 5, 1668: 5
- }],
- # 2019 Insight
- CAR.INSIGHT: [{
- 57: 3, 148: 8, 228: 5, 304: 8, 330: 8, 344: 8, 380: 8, 387: 8, 388: 8, 399: 7, 419: 8, 420: 8, 427: 3, 432: 7, 441: 5, 450: 8, 464: 8, 476: 8, 477: 8, 479: 8, 490: 8, 495: 8, 507: 1, 525: 8, 531: 8, 545: 6, 547: 6, 597: 8, 662: 4, 773: 7, 777: 8, 780: 8, 795: 8, 804: 8, 806: 8, 808: 8, 814: 4, 815: 8, 829: 5, 832: 3, 862: 8, 884: 8, 891: 8, 927: 8, 929: 8, 954: 2, 985: 3, 1029: 8, 1093: 4, 1115: 2, 1302: 8, 1361: 5, 1365: 5, 1600: 5, 1601: 8, 1652: 8, 2015: 3
- }]
}
-# Don't use theses fingerprints for fingerprinting, they are still needed for ECU detection
-IGNORED_FINGERPRINTS = [CAR.INSIGHT, CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_EU, CAR.HRV, CAR.ACURA_RDX_3G]
-
# add DIAG_MSGS to fingerprints
for c in FINGERPRINTS:
for f, _ in enumerate(FINGERPRINTS[c]):
@@ -173,6 +134,19 @@ FW_VERSIONS = {
b'37805-6B2-A820\x00\x00',
b'37805-6B2-A920\x00\x00',
b'37805-6B2-M520\x00\x00',
+ b'37805-6A0-9520\x00\x00',
+ b'37805-6A0-9620\x00\x00',
+ b'37805-6A0-9720\x00\x00',
+ b'37805-6A0-A540\x00\x00',
+ b'37805-6A0-A550\x00\x00',
+ b'37805-6A0-A650\x00\x00',
+ b'37805-6A0-A740\x00\x00',
+ b'37805-6A0-A750\x00\x00',
+ b'37805-6A0-A840\x00\x00',
+ b'37805-6A0-A850\x00\x00',
+ b'37805-6A0-C540\x00\x00',
+ b'37805-6A1-H650\x00\x00',
+ b'37805-6M4-B730\x00\x00',
],
(Ecu.shiftByWire, 0x18da0bf1, None): [
b'54008-TVC-A910\x00\x00',
@@ -184,25 +158,43 @@ FW_VERSIONS = {
b'28102-6B8-A800\x00\x00',
b'28102-6B8-C570\x00\x00',
b'28102-6B8-M520\x00\x00',
+ b'28101-6A7-A220\x00\x00',
+ b'28101-6A7-A230\x00\x00',
+ b'28101-6A7-A320\x00\x00',
+ b'28101-6A7-A330\x00\x00',
+ b'28101-6A7-A410\x00\x00',
+ b'28101-6A7-A510\x00\x00',
+ b'28101-6A9-H140\x00\x00',
+ b'28101-6A9-H420\x00\x00',
],
(Ecu.electricBrakeBooster, 0x18da2bf1, None): [
b'46114-TVA-A060\x00\x00',
b'46114-TVA-A080\x00\x00',
b'46114-TVA-A120\x00\x00',
b'46114-TVA-A320\x00\x00',
+ b'46114-TVA-A050\x00\x00',
+ b'46114-TVE-H550\x00\x00',
+ b'46114-TVE-H560\x00\x00',
],
(Ecu.vsa, 0x18da28f1, None): [
b'57114-TVA-C040\x00\x00',
b'57114-TVA-C050\x00\x00',
b'57114-TVA-C060\x00\x00',
b'57114-TVA-C530\x00\x00',
+ b'57114-TVA-B040\x00\x00',
+ b'57114-TVA-B050\x00\x00',
+ b'57114-TVA-B060\x00\x00',
+ b'57114-TVE-H250\x00\x00',
],
(Ecu.eps, 0x18da30f1, None): [
- b'39990-TVA,A150\x00\x00', # modified firmware
+ b'39990-TVA,A150\x00\x00',
b'39990-TVA-A150\x00\x00',
b'39990-TVA-A160\x00\x00',
b'39990-TVA-A340\x00\x00',
b'39990-TVA-X030\x00\x00',
+ b'39990-TVA-A140\x00\x00',
+ b'39990-TVE-H130\x00\x00',
+ b'39990-TBX-H120\x00\x00',
],
(Ecu.unknown, 0x18da3af1, None): [
b'39390-TVA-A020\x00\x00',
@@ -211,6 +203,8 @@ FW_VERSIONS = {
b'77959-TVA-A460\x00\x00',
b'77959-TVA-L420\x00\x00',
b'77959-TVA-X330\x00\x00',
+ b'77959-TVA-H230\x00\x00',
+ b'77959-TBX-H230\x00\x00',
],
(Ecu.combinationMeter, 0x18da60f1, None): [
b'78109-TVA-A210\x00\x00',
@@ -225,71 +219,11 @@ FW_VERSIONS = {
b'78109-TVC-L010\x00\x00',
b'78109-TVC-L210\x00\x00',
b'78109-TVC-M510\x00\x00',
- ],
- (Ecu.hud, 0x18da61f1, None): [
- b'78209-TVA-A010\x00\x00',
- ],
- (Ecu.fwdRadar, 0x18dab0f1, None): [
- b'36802-TVA-A160\x00\x00',
- b'36802-TVA-A170\x00\x00',
- b'36802-TVC-A330\x00\x00',
- b'36802-TWA-A070\x00\x00',
- ],
- (Ecu.fwdCamera, 0x18dab5f1, None): [
- b'36161-TVA-A060\x00\x00',
- b'36161-TVC-A330\x00\x00',
- b'36161-TWA-A070\x00\x00',
- ],
- (Ecu.gateway, 0x18daeff1, None): [
- b'38897-TVA-A010\x00\x00',
- b'38897-TVA-A020\x00\x00',
- ],
- },
- CAR.ACCORD_15: {
- (Ecu.programmedFuelInjection, 0x18da10f1, None): [
- b'37805-6A0-9520\x00\x00',
- b'37805-6A0-9620\x00\x00',
- b'37805-6A0-9720\x00\x00',
- b'37805-6A0-A540\x00\x00',
- b'37805-6A0-A550\x00\x00',
- b'37805-6A0-A640\x00\x00',
- b'37805-6A0-A650\x00\x00',
- b'37805-6A0-A740\x00\x00',
- b'37805-6A0-A750\x00\x00',
- b'37805-6A0-A840\x00\x00',
- b'37805-6A0-A850\x00\x00',
- b'37805-6A0-C540\x00\x00',
- b'37805-6A1-H650\x00\x00',
- b'37805-6M4-B730\x00\x00',
- ],
- (Ecu.transmission, 0x18da1ef1, None): [
- b'28101-6A7-A220\x00\x00',
- b'28101-6A7-A230\x00\x00',
- b'28101-6A7-A320\x00\x00',
- b'28101-6A7-A330\x00\x00',
- b'28101-6A7-A410\x00\x00',
- b'28101-6A7-A510\x00\x00',
- b'28101-6A9-H140\x00\x00',
- b'28101-6A9-H420\x00\x00',
- ],
- (Ecu.gateway, 0x18daeff1, None): [
- b'38897-TVA-A230\x00\x00',
- ],
- (Ecu.electricBrakeBooster, 0x18da2bf1, None): [
- b'46114-TVA-A050\x00\x00',
- b'46114-TVA-A060\x00\x00',
- b'46114-TVA-A080\x00\x00',
- b'46114-TVA-A120\x00\x00',
- b'46114-TVE-H550\x00\x00',
- b'46114-TVE-H560\x00\x00',
- ],
- (Ecu.combinationMeter, 0x18da60f1, None): [
b'78109-TBX-H310\x00\x00',
b'78109-TVA-A010\x00\x00',
b'78109-TVA-A020\x00\x00',
b'78109-TVA-A110\x00\x00',
b'78109-TVA-A120\x00\x00',
- b'78109-TVA-A210\x00\x00',
b'78109-TVA-A220\x00\x00',
b'78109-TVA-A310\x00\x00',
b'78109-TVA-C010\x00\x00',
@@ -301,35 +235,26 @@ FW_VERSIONS = {
(Ecu.hud, 0x18da61f1, None): [
b'78209-TVA-A010\x00\x00',
],
- (Ecu.fwdCamera, 0x18dab5f1, None): [
- b'36161-TVA-A060\x00\x00',
- b'36161-TVE-H050\x00\x00',
- b'36161-TBX-H130\x00\x00',
- ],
- (Ecu.srs, 0x18da53f1, None): [
- b'77959-TVA-A460\x00\x00',
- b'77959-TVA-H230\x00\x00',
- b'77959-TBX-H230\x00\x00',
- ],
- (Ecu.vsa, 0x18da28f1, None): [
- b'57114-TVA-B040\x00\x00',
- b'57114-TVA-B050\x00\x00',
- b'57114-TVA-B060\x00\x00',
- b'57114-TVE-H250\x00\x00',
- ],
(Ecu.fwdRadar, 0x18dab0f1, None): [
- b'36802-TVA-A150\x00\x00',
b'36802-TVA-A160\x00\x00',
b'36802-TVA-A170\x00\x00',
+ b'36802-TVC-A330\x00\x00',
+ b'36802-TWA-A070\x00\x00',
+ b'36802-TVA-A150\x00\x00',
b'36802-TVE-H070\x00\x00',
b'36802-TBX-H140\x00\x00',
],
- (Ecu.eps, 0x18da30f1, None): [
- b'39990-TVA-A140\x00\x00',
- b'39990-TVA-A150\x00\x00', # Are these two different steerRatio?
- b'39990-TVA-A160\x00\x00', # Sport, Sport 2.0T and Touring 2.0T have different ratios
- b'39990-TVE-H130\x00\x00',
- b'39990-TBX-H120\x00\x00',
+ (Ecu.fwdCamera, 0x18dab5f1, None): [
+ b'36161-TVA-A060\x00\x00',
+ b'36161-TVC-A330\x00\x00',
+ b'36161-TWA-A070\x00\x00',
+ b'36161-TVE-H050\x00\x00',
+ b'36161-TBX-H130\x00\x00',
+ ],
+ (Ecu.gateway, 0x18daeff1, None): [
+ b'38897-TVA-A010\x00\x00',
+ b'38897-TVA-A020\x00\x00',
+ b'38897-TVA-A230\x00\x00',
],
},
CAR.ACCORDH: {
@@ -1072,12 +997,16 @@ FW_VERSIONS = {
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',
],
(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): [
@@ -1090,8 +1019,11 @@ FW_VERSIONS = {
b'78109-TG7-AP20\x00\x00',
b'78109-TG7-AS20\x00\x00',
b'78109-TG7-AU20\x00\x00',
+ b'78109-TG7-DJ10\x00\x00',
+ b'78109-TG7-YK20\x00\x00',
b'78109-TG8-AJ10\x00\x00',
b'78109-TG8-AJ20\x00\x00',
+ b'78109-TG8-AK20\x00\x00',
b'78109-TGS-AK20\x00\x00',
b'78109-TGS-AP20\x00\x00',
b'78109-TGT-AJ20\x00\x00',
@@ -1100,6 +1032,7 @@ FW_VERSIONS = {
b'57114-TG7-A630\x00\x00',
b'57114-TG7-A730\x00\x00',
b'57114-TG8-A630\x00\x00',
+ b'57114-TG8-A730\x00\x00',
b'57114-TGS-A530\x00\x00',
b'57114-TGT-A530\x00\x00',
],
@@ -1295,9 +1228,8 @@ FW_VERSIONS = {
}
DBC = {
- CAR.ACCORD: dbc_dict('honda_accord_s2t_2018_can_generated', None),
- CAR.ACCORD_15: dbc_dict('honda_accord_lx15t_2018_can_generated', None),
- CAR.ACCORDH: dbc_dict('honda_accord_s2t_2018_can_generated', None),
+ CAR.ACCORD: dbc_dict('honda_accord_2018_can_generated', None),
+ CAR.ACCORDH: dbc_dict('honda_accord_2018_can_generated', None),
CAR.ACURA_ILX: dbc_dict('acura_ilx_2016_can_generated', 'acura_ilx_2016_nidec'),
CAR.ACURA_RDX: dbc_dict('acura_rdx_2018_can_generated', 'acura_ilx_2016_nidec'),
CAR.ACURA_RDX_3G: dbc_dict('acura_rdx_2020_can_generated', None),
@@ -1320,7 +1252,6 @@ DBC = {
STEER_THRESHOLD = {
CAR.ACCORD: 1200,
- CAR.ACCORD_15: 1200,
CAR.ACCORDH: 1200,
CAR.ACURA_ILX: 1200,
CAR.ACURA_RDX: 400,
@@ -1344,7 +1275,6 @@ STEER_THRESHOLD = {
SPEED_FACTOR = {
CAR.ACCORD: 1.,
- CAR.ACCORD_15: 1.,
CAR.ACCORDH: 1.,
CAR.ACURA_ILX: 1.,
CAR.ACURA_RDX: 1.,
@@ -1366,4 +1296,5 @@ SPEED_FACTOR = {
CAR.INSIGHT: 1.,
}
-HONDA_BOSCH = set([CAR.ACCORD, CAR.ACCORD_15, CAR.ACCORDH, CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_5G, CAR.CRV_HYBRID, CAR.INSIGHT, CAR.ACURA_RDX_3G])
+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])
+HONDA_BOSCH_ALT_BRAKE_SIGNAL = set([CAR.ACCORD, CAR.CRV_5G, CAR.ACURA_RDX_3G])
diff --git a/selfdrive/car/hyundai/carcontroller.py b/selfdrive/car/hyundai/carcontroller.py
index cf4756e8f..5f7019fdf 100644
--- a/selfdrive/car/hyundai/carcontroller.py
+++ b/selfdrive/car/hyundai/carcontroller.py
@@ -49,8 +49,8 @@ class CarController():
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
- # disable if steer angle reach 90 deg, otherwise mdps fault in some models
- lkas_active = enabled and abs(CS.out.steeringAngleDeg) < CS.CP.maxSteeringAngleDeg
+ # disable when temp fault is active
+ lkas_active = enabled and not CS.out.steerWarning
# fix for Genesis hard fault at low speed
if CS.out.vEgo < 16.7 and self.car_fingerprint == CAR.HYUNDAI_GENESIS:
@@ -81,8 +81,8 @@ class CarController():
self.last_resume_frame = frame
# 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.IONIQ_EV_2020, CAR.KIA_CEED, CAR.KIA_SELTOS]:
+ if frame % 5 == 0 and self.car_fingerprint in [CAR.SONATA, CAR.PALISADE, CAR.IONIQ, CAR.KIA_NIRO_EV, CAR.KONA_EV,
+ CAR.IONIQ_EV_2020, CAR.KIA_CEED, CAR.KIA_SELTOS, CAR.ELANTRA_2021]:
can_sends.append(create_lfahda_mfc(self.packer, enabled))
return can_sends
diff --git a/selfdrive/car/hyundai/carstate.py b/selfdrive/car/hyundai/carstate.py
index c74a83b92..868838827 100644
--- a/selfdrive/car/hyundai/carstate.py
+++ b/selfdrive/car/hyundai/carstate.py
@@ -12,58 +12,55 @@ class CarState(CarStateBase):
def update(self, cp, cp_cam):
ret = car.CarState.new_message()
- ret.doorOpen = any([cp.vl["CGW1"]['CF_Gway_DrvDrSw'], cp.vl["CGW1"]['CF_Gway_AstDrSw'],
- cp.vl["CGW2"]['CF_Gway_RLDrSw'], cp.vl["CGW2"]['CF_Gway_RRDrSw']])
+ ret.doorOpen = any([cp.vl["CGW1"]["CF_Gway_DrvDrSw"], cp.vl["CGW1"]["CF_Gway_AstDrSw"],
+ cp.vl["CGW2"]["CF_Gway_RLDrSw"], cp.vl["CGW2"]["CF_Gway_RRDrSw"]])
- ret.seatbeltUnlatched = cp.vl["CGW1"]['CF_Gway_DrvSeatBeltSw'] == 0
+ ret.seatbeltUnlatched = cp.vl["CGW1"]["CF_Gway_DrvSeatBeltSw"] == 0
- ret.wheelSpeeds.fl = cp.vl["WHL_SPD11"]['WHL_SPD_FL'] * CV.KPH_TO_MS
- ret.wheelSpeeds.fr = cp.vl["WHL_SPD11"]['WHL_SPD_FR'] * CV.KPH_TO_MS
- ret.wheelSpeeds.rl = cp.vl["WHL_SPD11"]['WHL_SPD_RL'] * CV.KPH_TO_MS
- ret.wheelSpeeds.rr = cp.vl["WHL_SPD11"]['WHL_SPD_RR'] * CV.KPH_TO_MS
+ ret.wheelSpeeds.fl = cp.vl["WHL_SPD11"]["WHL_SPD_FL"] * CV.KPH_TO_MS
+ ret.wheelSpeeds.fr = cp.vl["WHL_SPD11"]["WHL_SPD_FR"] * CV.KPH_TO_MS
+ ret.wheelSpeeds.rl = cp.vl["WHL_SPD11"]["WHL_SPD_RL"] * CV.KPH_TO_MS
+ ret.wheelSpeeds.rr = cp.vl["WHL_SPD11"]["WHL_SPD_RR"] * CV.KPH_TO_MS
ret.vEgoRaw = (ret.wheelSpeeds.fl + ret.wheelSpeeds.fr + ret.wheelSpeeds.rl + ret.wheelSpeeds.rr) / 4.
ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw)
ret.standstill = ret.vEgoRaw < 0.1
- ret.steeringAngleDeg = cp.vl["SAS11"]['SAS_Angle']
- ret.steeringRateDeg = cp.vl["SAS11"]['SAS_Speed']
- ret.yawRate = cp.vl["ESP12"]['YAW_RATE']
- ret.leftBlinker, ret.rightBlinker = self.update_blinker(50, cp.vl["CGW1"]['CF_Gway_TurnSigLh'],
- cp.vl["CGW1"]['CF_Gway_TurnSigRh'])
- ret.steeringTorque = cp.vl["MDPS12"]['CR_Mdps_StrColTq']
- ret.steeringTorqueEps = cp.vl["MDPS12"]['CR_Mdps_OutTq']
+ ret.steeringAngleDeg = cp.vl["SAS11"]["SAS_Angle"]
+ ret.steeringRateDeg = cp.vl["SAS11"]["SAS_Speed"]
+ ret.yawRate = cp.vl["ESP12"]["YAW_RATE"]
+ ret.leftBlinker, ret.rightBlinker = self.update_blinker(50, cp.vl["CGW1"]["CF_Gway_TurnSigLh"],
+ cp.vl["CGW1"]["CF_Gway_TurnSigRh"])
+ ret.steeringTorque = cp.vl["MDPS12"]["CR_Mdps_StrColTq"]
+ ret.steeringTorqueEps = cp.vl["MDPS12"]["CR_Mdps_OutTq"]
ret.steeringPressed = abs(ret.steeringTorque) > STEER_THRESHOLD
- ret.steerWarning = cp.vl["MDPS12"]['CF_Mdps_ToiUnavail'] != 0 or cp.vl["MDPS12"]['CF_Mdps_ToiFlt'] != 0
+ ret.steerWarning = cp.vl["MDPS12"]["CF_Mdps_ToiUnavail"] != 0 or cp.vl["MDPS12"]["CF_Mdps_ToiFlt"] != 0
# cruise state
if self.CP.openpilotLongitudinalControl:
- ret.cruiseState.available = cp.vl["TCS13"]['ACCEnable'] == 0
- ret.cruiseState.enabled = cp.vl["TCS13"]['ACC_REQ'] == 1
- ret.cruiseState.standstill = cp.vl["TCS13"]['StandStill'] == 1
+ ret.cruiseState.available = cp.vl["TCS13"]["ACCEnable"] == 0
+ ret.cruiseState.enabled = cp.vl["TCS13"]["ACC_REQ"] == 1
+ ret.cruiseState.standstill = cp.vl["TCS13"]["StandStill"] == 1
else:
- ret.cruiseState.available = cp.vl["SCC11"]['MainMode_ACC'] == 1
- ret.cruiseState.enabled = cp.vl["SCC12"]['ACCMode'] != 0
- ret.cruiseState.standstill = cp.vl["SCC11"]['SCCInfoDisplay'] == 4.
+ ret.cruiseState.available = cp.vl["SCC11"]["MainMode_ACC"] == 1
+ ret.cruiseState.enabled = cp.vl["SCC12"]["ACCMode"] != 0
+ ret.cruiseState.standstill = cp.vl["SCC11"]["SCCInfoDisplay"] == 4.
if ret.cruiseState.enabled:
speed_conv = CV.MPH_TO_MS if cp.vl["CLU11"]["CF_Clu_SPEED_UNIT"] else CV.KPH_TO_MS
- ret.cruiseState.speed = cp.vl["SCC11"]['VSetDis'] * speed_conv
+ ret.cruiseState.speed = cp.vl["SCC11"]["VSetDis"] * speed_conv
else:
ret.cruiseState.speed = 0
# TODO: Find brake pressure
ret.brake = 0
- ret.brakePressed = cp.vl["TCS13"]['DriverBraking'] != 0
-
- # TODO: Check this
- ret.brakeLights = bool(cp.vl["TCS13"]['BrakeLight'] or ret.brakePressed)
+ ret.brakePressed = cp.vl["TCS13"]["DriverBraking"] != 0
if self.CP.carFingerprint in EV_HYBRID:
- ret.gas = cp.vl["E_EMS11"]['Accel_Pedal_Pos'] / 256.
+ ret.gas = cp.vl["E_EMS11"]["Accel_Pedal_Pos"] / 256.
ret.gasPressed = ret.gas > 0
else:
- ret.gas = cp.vl["EMS12"]['PV_AV_CAN'] / 100
+ ret.gas = cp.vl["EMS12"]["PV_AV_CAN"] / 100
ret.gasPressed = bool(cp.vl["EMS16"]["CF_Ems_AclAct"])
# TODO: refactor gear parsing in function
@@ -119,11 +116,11 @@ class CarState(CarStateBase):
ret.gearShifter = GearShifter.unknown
if self.CP.carFingerprint in FEATURES["use_fca"]:
- ret.stockAeb = cp.vl["FCA11"]['FCA_CmdAct'] != 0
- ret.stockFcw = cp.vl["FCA11"]['CF_VSM_Warn'] == 2
+ ret.stockAeb = cp.vl["FCA11"]["FCA_CmdAct"] != 0
+ ret.stockFcw = cp.vl["FCA11"]["CF_VSM_Warn"] == 2
else:
- ret.stockAeb = cp.vl["SCC12"]['AEB_CmdAct'] != 0
- ret.stockFcw = cp.vl["SCC12"]['CF_VSM_Warn'] == 2
+ ret.stockAeb = cp.vl["SCC12"]["AEB_CmdAct"] != 0
+ ret.stockFcw = cp.vl["SCC12"]["CF_VSM_Warn"] == 2
if self.CP.enableBsm:
ret.leftBlindspot = cp.vl["LCA11"]["CF_Lca_IndLeft"] != 0
@@ -132,11 +129,11 @@ class CarState(CarStateBase):
# save the entire LKAS11 and CLU11
self.lkas11 = copy.copy(cp_cam.vl["LKAS11"])
self.clu11 = copy.copy(cp.vl["CLU11"])
- self.park_brake = cp.vl["TCS13"]['PBRAKE_ACT'] == 1
- self.steer_state = cp.vl["MDPS12"]['CF_Mdps_ToiActive'] # 0 NOT ACTIVE, 1 ACTIVE
- self.lead_distance = cp.vl["SCC11"]['ACC_ObjDist']
- self.brake_hold = cp.vl["TCS15"]['AVH_LAMP'] == 2 # 0 OFF, 1 ERROR, 2 ACTIVE, 3 READY
- self.brake_error = cp.vl["TCS13"]['ACCEnable'] != 0 # 0 ACC CONTROL ENABLED, 1-3 ACC CONTROL DISABLED
+ self.park_brake = cp.vl["TCS13"]["PBRAKE_ACT"] == 1
+ self.steer_state = cp.vl["MDPS12"]["CF_Mdps_ToiActive"] # 0 NOT ACTIVE, 1 ACTIVE
+ self.lead_distance = cp.vl["SCC11"]["ACC_ObjDist"]
+ self.brake_hold = cp.vl["TCS15"]["AVH_LAMP"] == 2 # 0 OFF, 1 ERROR, 2 ACTIVE, 3 READY
+ self.brake_error = cp.vl["TCS13"]["ACCEnable"] != 0 # 0 ACC CONTROL ENABLED, 1-3 ACC CONTROL DISABLED
self.prev_cruise_buttons = self.cruise_buttons
self.cruise_buttons = cp.vl["CLU11"]["CF_Clu_CruiseSwState"]
@@ -181,7 +178,6 @@ class CarState(CarStateBase):
("ACCEnable", "TCS13", 0),
("ACC_REQ", "TCS13", 0),
- ("BrakeLight", "TCS13", 0),
("DriverBraking", "TCS13", 0),
("StandStill", "TCS13", 0),
("PBRAKE_ACT", "TCS13", 0),
@@ -290,7 +286,7 @@ class CarState(CarStateBase):
("CF_VSM_Warn", "SCC12", 0),
]
- return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 0)
+ return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 0)
@staticmethod
def get_cam_can_parser(CP):
@@ -318,4 +314,4 @@ class CarState(CarStateBase):
("LKAS11", 100)
]
- return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 2)
+ return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 2)
diff --git a/selfdrive/car/hyundai/hyundaican.py b/selfdrive/car/hyundai/hyundaican.py
index 228ccfece..23645a125 100644
--- a/selfdrive/car/hyundai/hyundaican.py
+++ b/selfdrive/car/hyundai/hyundaican.py
@@ -17,7 +17,7 @@ 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.SANTA_FE, CAR.IONIQ_EV_2020, CAR.KIA_SELTOS]:
+ if car_fingerprint in [CAR.SONATA, CAR.PALISADE, CAR.KIA_NIRO_EV, CAR.SANTA_FE, CAR.IONIQ_EV_2020, CAR.KIA_SELTOS, CAR.ELANTRA_2021]:
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 5334471a7..c4ff372df 100644
--- a/selfdrive/car/hyundai/interface.py
+++ b/selfdrive/car/hyundai/interface.py
@@ -27,14 +27,8 @@ class CarInterface(CarInterfaceBase):
ret.steerLimitTimer = 0.4
tire_stiffness_factor = 1.
- ret.maxSteeringAngleDeg = 90.
ret.startAccel = 1.0
- eps_modified = False
- for fw in car_fw:
- if fw.ecu == "eps" and b"," in fw.fwVersion:
- eps_modified = True
-
if candidate == CAR.SANTA_FE:
ret.lateralTuning.pid.kf = 0.00005
ret.mass = 3982. * CV.LB_TO_KG + STD_CARGO_KG
@@ -66,8 +60,6 @@ class CarInterface(CarInterfaceBase):
ret.steerRatio = 13.75 * 1.15
ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]]
ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.3], [0.05]]
- if eps_modified:
- ret.maxSteeringAngleDeg = 1000.
elif candidate in [CAR.ELANTRA, CAR.ELANTRA_GT_I30]:
ret.lateralTuning.pid.kf = 0.00006
ret.mass = 1275. + STD_CARGO_KG
@@ -77,6 +69,14 @@ class CarInterface(CarInterfaceBase):
ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]]
ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]]
ret.minSteerSpeed = 32 * CV.MPH_TO_MS
+ elif candidate == CAR.ELANTRA_2021:
+ ret.lateralTuning.pid.kf = 0.00005
+ ret.mass = (2800. * CV.LB_TO_KG) + STD_CARGO_KG
+ ret.wheelbase = 2.72
+ ret.steerRatio = 13.27 * 1.15 # 15% higher at the center seems reasonable
+ tire_stiffness_factor = 0.65
+ ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]]
+ ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.25], [0.05]]
elif candidate == CAR.HYUNDAI_GENESIS:
ret.lateralTuning.pid.kf = 0.00005
ret.mass = 2060. + STD_CARGO_KG
@@ -222,7 +222,7 @@ class CarInterface(CarInterfaceBase):
# these cars require a special panda safety mode due to missing counters and checksums in the messages
if candidate in [CAR.HYUNDAI_GENESIS, CAR.IONIQ_EV_2020, CAR.IONIQ_EV_LTD, CAR.IONIQ, CAR.KONA_EV, CAR.KIA_SORENTO,
CAR.SONATA_LF, CAR.KIA_NIRO_EV, CAR.KIA_OPTIMA, CAR.VELOSTER, CAR.KIA_STINGER, CAR.KIA_SELTOS,
- CAR.GENESIS_G70, CAR.GENESIS_G80, CAR.KIA_CEED]:
+ CAR.GENESIS_G70, CAR.GENESIS_G80, CAR.KIA_CEED, CAR.ELANTRA]:
ret.safetyModel = car.CarParams.SafetyModel.hyundaiLegacy
ret.centerToFront = ret.wheelbase * 0.4
diff --git a/selfdrive/car/hyundai/values.py b/selfdrive/car/hyundai/values.py
index 9f778ebfd..c69789598 100644
--- a/selfdrive/car/hyundai/values.py
+++ b/selfdrive/car/hyundai/values.py
@@ -7,7 +7,7 @@ Ecu = car.CarParams.Ecu
# Steer torque limits
class CarControllerParams:
def __init__(self, CP):
- if CP.carFingerprint in [CAR.SONATA, CAR.PALISADE, CAR.SANTA_FE, CAR.VELOSTER, CAR.GENESIS_G70, CAR.IONIQ_EV_2020, CAR.KIA_CEED, CAR.KIA_SELTOS]:
+ if CP.carFingerprint in [CAR.SONATA, CAR.PALISADE, CAR.SANTA_FE, CAR.VELOSTER, CAR.GENESIS_G70, CAR.IONIQ_EV_2020, CAR.KIA_CEED, CAR.KIA_SELTOS, CAR.ELANTRA_2021]:
self.STEER_MAX = 384
else:
self.STEER_MAX = 255
@@ -21,6 +21,7 @@ class CarControllerParams:
class CAR:
# Hyundai
ELANTRA = "HYUNDAI ELANTRA 2017"
+ ELANTRA_2021 = "HYUNDAI ELANTRA 2021"
ELANTRA_GT_I30 = "HYUNDAI I30 N LINE 2019 & GT 2018 DCT"
HYUNDAI_GENESIS = "HYUNDAI GENESIS 2015-2016"
IONIQ = "HYUNDAI IONIQ HYBRID 2017-2019"
@@ -109,9 +110,6 @@ FINGERPRINTS = {
CAR.KIA_STINGER: [{
67: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 358: 6, 359: 8, 544: 8, 576: 8, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1064: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1168: 7, 1170: 8, 1173: 8, 1184: 8, 1265: 4, 1280: 1, 1281: 4, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1371: 8, 1378: 4, 1379: 8, 1384: 8, 1407: 8, 1419: 8, 1425: 2, 1427: 6, 1456: 4, 1470: 8
}],
- CAR.GENESIS_G70: [{
- 67: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 358: 6, 544: 8, 576: 8, 593: 8, 608: 8, 688: 5, 809: 8, 832:8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1064: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1156: 8, 1168: 7, 1170: 8, 1173:8, 1184: 8, 1186: 2, 1191: 2, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1379: 8, 1384: 8, 1407: 8, 1419:8, 1427: 6, 1456: 4, 1470: 8, 1988: 8, 1996: 8, 2000: 8, 2004: 8, 2008: 8, 2012: 8, 2015: 8
- }],
CAR.GENESIS_G80: [{
67: 8, 68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 358: 6, 544: 8, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 916: 8, 1024: 2, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1156: 8, 1168: 7, 1170: 8, 1173: 8, 1184: 8, 1191: 2, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1370: 8, 1371: 8, 1378: 4, 1384: 8, 1407: 8, 1419: 8, 1425: 2, 1427: 6, 1434: 2, 1456: 4, 1470: 8
},
@@ -133,18 +131,12 @@ FINGERPRINTS = {
CAR.IONIQ: [{
68:8, 127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 524: 8, 544: 8, 576:8, 593: 8, 688: 5, 832: 8, 881: 8, 882: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1136: 6, 1151: 6, 1155: 8, 1156: 8, 1157: 4, 1164: 8, 1168: 7, 1173: 8, 1183: 8, 1186: 2, 1191: 2, 1225: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1379: 8, 1407: 8, 1419: 8, 1426: 8, 1427: 6, 1429: 8, 1430: 8, 1448: 8, 1456: 4, 1470: 8, 1473: 8, 1476: 8, 1507: 8, 1535: 8, 1988: 8, 1996: 8, 2000: 8, 2004: 8, 2005: 8, 2008: 8, 2012: 8, 2013: 8
}],
- CAR.KONA: [{
- 67: 8, 127: 8, 304: 8, 320: 8, 339: 8, 354: 3, 356: 4, 544: 8, 593: 8, 608: 8, 688: 5, 809: 8, 832 : 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1064: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1156: 8, 1170: 8, 1173: 8, 1186: 2, 1191: 2, 1193: 8, 1265: 4,1280: 1, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1378: 8, 1384: 8, 1394: 8, 1407: 8, 1414: 3, 1419: 8, 1427: 6, 1456: 4, 1470: 8, 1988: 8, 1996: 8, 2000: 8, 2001: 8, 2004: 8, 2008: 8, 2009: 8, 2012: 8
- }],
CAR.KONA_EV: [{
127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 544: 8, 549: 8, 593: 8, 688: 5, 832: 8, 881: 8, 882: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1136: 8, 1151: 6, 1168: 7, 1173: 8, 1183: 8, 1186: 2, 1191: 2, 1225: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1294: 8, 1307: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1378: 4, 1407: 8, 1419: 8, 1426: 8, 1427: 6, 1429: 8, 1430: 8, 1456: 4, 1470: 8, 1473: 8, 1507: 8, 1535: 8, 2000: 8, 2004: 8, 2008: 8, 2012: 8, 1157: 4, 1193: 8, 1379: 8, 1988: 8, 1996: 8
}],
CAR.KIA_NIRO_EV: [{
127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 516: 8, 544: 8, 593: 8, 688: 5, 832: 8, 881: 8, 882: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1136: 8, 1151: 6, 1156: 8, 1157: 4, 1168: 7, 1173: 8, 1183: 8, 1186: 2, 1191: 2, 1193: 8, 1225: 8, 1260: 8, 1265: 4, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1407: 8, 1419: 8, 1426: 8, 1427: 6, 1429: 8, 1430: 8, 1456: 4, 1470: 8, 1473: 8, 1507: 8, 1535: 8, 1990: 8, 1998: 8, 1996: 8, 2000: 8, 2004: 8, 2008: 8, 2012: 8, 2015: 8
}],
- CAR.KIA_CEED: [{
- 67: 8, 127: 8, 304: 8, 320: 8, 339: 8, 354: 3, 356: 4, 544: 8, 576: 8, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1107: 5, 1136: 8, 1151: 6, 1155: 8, 1157: 4, 1168: 7, 1170: 8, 1173: 8, 1183: 8, 1186: 2, 1191: 2, 1225: 8, 1265: 4, 1280: 4, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1384: 8, 1394: 8, 1407: 8, 1414: 3, 1427: 6, 1456: 4, 2015: 8
- }],
CAR.KIA_FORTE: [{
67: 8, 127: 8, 304: 8, 320: 8, 339: 8, 354: 3, 356: 4, 544: 8, 576: 8, 593: 8, 608: 8, 688: 5, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1078: 4, 1107: 5, 1136: 8, 1156: 8, 1170: 8, 1173: 8, 1186: 2, 1191: 2, 1225: 8, 1265: 4, 1280: 4, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1384: 8, 1394: 8, 1407: 8, 1414: 3, 1419: 8, 1427: 6, 1456: 4, 1470: 8, 1988: 8, 1996: 8, 2000: 8, 2004: 8, 2008: 8, 2012: 8, 2015: 8
}],
@@ -154,19 +146,11 @@ FINGERPRINTS = {
{
68: 8, 127: 8, 304: 8, 320: 8, 339: 8, 352: 8, 356: 4, 544: 8, 576: 8, 593: 8, 688: 5, 881: 8, 882: 8, 897: 8, 902: 8, 903: 8, 909: 8, 912: 7, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1136: 6, 1151: 6, 1168: 7, 1173: 8, 1180: 8, 1186: 2, 1191: 2, 1265: 4, 1268: 8, 1280: 1, 1287: 4, 1290: 8, 1291: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1355: 8, 1363: 8, 1369: 8, 1371: 8, 1407: 8, 1419: 8, 1420: 8, 1425: 2, 1427: 6, 1429: 8, 1430: 8, 1448: 8, 1456: 4, 1470: 8, 1476: 8, 1535: 8
}],
- CAR.KIA_SELTOS: [{
- 67: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 524: 8, 544: 8, 593: 8, 608: 8, 688: 6, 809: 8, 832: 8, 854: 8, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 905: 8, 909: 8, 910: 5, 911: 5, 913: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1064: 8, 1078: 4, 1102: 8, 1107: 5, 1114: 8, 1136: 8, 1145: 8, 1151: 8, 1155: 8, 1156: 8, 1157: 4, 1162: 8, 1164: 8, 1168: 8, 1170: 8, 1173: 8, 1186: 2, 1191: 2, 1225: 8, 1265: 4, 1280: 8, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1379: 8, 1384: 8, 1394: 8, 1407: 8, 1419: 8, 1427: 6, 1446: 8, 1456: 4, 1470: 8, 1485: 8, 1988: 8, 1996: 8, 2000: 8, 2004: 8, 2008: 8, 2012: 8, 2015: 8
- }],
CAR.PALISADE: [{
67: 8, 127: 8, 304: 8, 320: 8, 339: 8, 356: 4, 544: 8, 546: 8, 547: 8, 548: 8, 549: 8, 576: 8, 593: 8, 608: 8, 688: 6, 809: 8, 832: 8, 854: 7, 870: 7, 871: 8, 872: 8, 897: 8, 902: 8, 903: 8, 905: 8, 909: 8, 913: 8, 916: 8, 1040: 8, 1042: 8, 1056: 8, 1057: 8, 1064: 8, 1078: 4, 1107: 5, 1123: 8, 1136: 8, 1151: 6, 1155: 8, 1156: 8, 1157: 4, 1162: 8, 1164: 8, 1168: 7, 1170: 8, 1173: 8, 1180: 8, 1186: 2, 1191: 2, 1193: 8, 1210: 8, 1225: 8, 1227: 8, 1265: 4, 1280: 8, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1363: 8, 1369: 8, 1371: 8, 1378: 8, 1384: 8, 1407: 8, 1419: 8, 1427: 6, 1456: 4, 1470: 8, 1988: 8, 1996: 8, 2000: 8, 2004: 8, 2005: 8, 2008: 8, 2012: 8
}],
- CAR.VELOSTER: [{
- 64: 8, 66: 8, 67: 8, 68: 8, 127: 8, 128: 8, 129: 8, 273: 8, 274: 8, 275: 8, 339: 8, 354: 3, 356: 4, 399: 8, 512: 6, 544: 8, 558: 8, 593: 8, 608: 8, 688: 5, 790: 8, 809: 8, 832: 8, 884: 8, 897: 8, 899: 8, 902: 8, 903: 8, 905: 8, 909: 8, 916: 8, 1040: 8, 1056: 8, 1057: 8, 1078: 4, 1170: 8, 1181: 5, 1186: 2, 1191: 2, 1265: 4, 1280: 1, 1282: 4, 1287: 4, 1290: 8, 1292: 8, 1294: 8, 1312: 8, 1322: 8, 1342: 6, 1345: 8, 1348: 8, 1349: 8, 1351: 8, 1353: 8, 1356: 8, 1363: 8, 1365: 8, 1366: 8, 1367: 8, 1369: 8, 1378: 4, 1407: 8, 1414: 3, 1415: 8, 1419: 8, 1427: 6, 1440: 8, 1456: 4, 1470: 8, 1486: 8, 1487: 8, 1491: 8, 1530: 8, 1532: 5, 1872: 8, 1988: 8, 1996: 8, 2000: 8, 2001: 8, 2004: 8, 2008: 8, 2009: 8, 2012: 8, 2015: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8
- }]
}
-# Don't use these fingerprints for fingerprinting, they are still used for ECU detection
-IGNORED_FINGERPRINTS = [CAR.VELOSTER, CAR.GENESIS_G70, CAR.KONA, CAR.KIA_CEED, CAR.KIA_SELTOS]
FW_VERSIONS = {
CAR.IONIQ_EV_2020: {
@@ -397,6 +381,7 @@ FW_VERSIONS = {
b'\xf1\x00LX ESC \x01 103\x31\t\020 58910-S8360\xf1\xa01.03',
b'\xf1\x00LX ESC \x0b 101\x19\x03\x17 58910-S8330\xf1\xa01.01',
b'\xf1\x00LX ESC \x0b 102\x19\x05\x07 58910-S8330',
+ b'\xf1\x00LX ESC \x0b 103\x19\t\x07 58910-S8330\xf1\xa01.03',
b'\xf1\x00LX ESC \x0b 103\x19\t\x10 58910-S8360',
b'\xf1\x00LX ESC \x0b 104 \x10\x16 58910-S8360\xf1\xa01.04',
b'\xf1\x00ON ESC \x0b 100\x18\x12\x18 58910-S9360\xf1\xa01.00',
@@ -436,6 +421,7 @@ FW_VERSIONS = {
b'\xf1\x87LDLVBN673087KF37\x97www\x86fvgx\x99\x97\x89\x99\xaa\xa9\x9ag\x88\x86x\xe9_\xf8\xff\x98w\x7f\xff"\xad\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB3X\xa8\xc08',
b'\xf1\x87LDLVBN681363KF37\x98\x88\x88\x88\x97x\x87\x88y\xaa\xa7\x9a\x88\x88\x98\x88\x88\x88\x88\x88vo\xf6\xffvD\x7f\xff%v\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB3X\xa8\xc08',
b'\xf1\x87LDLVBN713890KF26\xb9\x99\x89\x98\xa9\x99\x99\x99x\x99\x97\x89\x88\x99\xa8\x89\x88\x99\xb8\x89Do\xf7\xff\xa9\x88o\xffs\r\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB3X\xa8\xc08',
+ b'\xf1\x87LDLVBN733215KF37\x99\x98y\x87\x97wwwi\x99\xa6\x99x\x99\xa7\x89V\x88\x95h\x86o\xf7\xffeDO\xff\x12\xe7\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB3X\xa8\xc08',
b'\xf1\x87LDLVBN750044KF37\xca\xa9\x8a\x98\xa7wwwy\xaa\xb7\x9ag\x88\x96x\x88\x99\xa8\x89\xb9\x7f\xf6\xff\xa8w\x7f\xff\xbe\xde\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB3X\xa8\xc08',
b'\xf1\x87LDLVBN752612KF37\xba\xaa\x8a\xa8\x87w\x87xy\xaa\xa7\x9a\x88\x99\x98\x89x\x88\x97\x88\x96o\xf6\xffvU_\xffh\x1b\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB3X\xa8\xc08',
b'\xf1\x87LDLVBN755553KF37\x87xw\x87\x97w\x87xy\x99\xa7\x99\x99\x99\xa9\x99Vw\x95gwo\xf6\xffwUO\xff\xb5T\xf1\x81U891\x00\x00\x00\x00\x00\x00\xf1\x00bcsh8p54 U891\x00\x00\x00\x00\x00\x00SLX4G38NB3X\xa8\xc08',
@@ -558,12 +544,20 @@ FW_VERSIONS = {
(Ecu.engine, 0x7e0, None): [
b'\xf1\x81616D2051\000\000\000\000\000\000\000\000',
b'\001TSP2KNL06F100J0K',
+ b'\001TSP2KNL06F200J0K',
],
- (Ecu.eps, 0x7d4, None): [b'\xf1\000SP2 MDPS C 1.00 1.04 56300Q5200 ',],
- (Ecu.fwdCamera, 0x7c4, None): [b'\xf1\000SP2 MFC AT USA LHD 1.00 1.04 99210-Q5000 191114',],
+ (Ecu.eps, 0x7d4, None): [
+ b'\xf1\000SP2 MDPS C 1.00 1.04 56300Q5200 ',
+ b'\xf1\000SP2 MDPS C 1.01 1.05 56300Q5200 ',
+ ],
+ (Ecu.fwdCamera, 0x7c4, None): [
+ b'\xf1\000SP2 MFC AT USA LHD 1.00 1.04 99210-Q5000 191114',
+ b'\xf1\000SP2 MFC AT USA LHD 1.00 1.05 99210-Q5000 201012',
+ ],
(Ecu.transmission, 0x7e1, None): [
b'\xf1\x87CZLUB49370612JF7h\xa8y\x87\x99\xa7hv\x99\x97fv\x88\x87x\x89x\x96O\xff\x88\xff\xff\xff.@\xf1\x816V2C2051\000\000\xf1\0006V2B0_C2\000\0006V2C2051\000\000CSP4N20NS3\000\000\000\000',
b'\xf1\x87954A22D200\xf1\x81T01950A1 \xf1\000T0190XBL T01950A1 DSP2T16X4X950NS6\xd30\xa5\xb9',
+ b'\xf1\x87954A22D200\xf1\x81T01950A1 \xf1\000T0190XBL T01950A1 DSP2T16X4X950NS8\r\xfe\x9c\x8b',
],
},
CAR.KIA_OPTIMA: {
@@ -577,10 +571,28 @@ FW_VERSIONS = {
(Ecu.fwdCamera, 0x7c4, None): [b'\xf1\x00JFA LKAS AT USA LHD 1.00 1.02 95895-D5000 h31'],
(Ecu.transmission, 0x7e1, None): [b'\xf1\x816U2V8051\x00\x00\xf1\x006U2V0_C2\x00\x006U2V8051\x00\x00DJF0T16NL0\t\xd2GW'],
},
+ CAR.ELANTRA_2021: {
+ (Ecu.fwdRadar, 0x7d0, None): [b'\xf1\x00CN7_ SCC FHCUP 1.00 1.01 99110-AA000 '],
+ (Ecu.eps, 0x7d4, None): [
+ b'\xf1\x87\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\xf1\x00CN7 MDPS C 1.00 1.06 \x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00 4CNDC106\xf1\xa01.06',
+ b'\xf1\x8756310AA050\x00\xf1\x00CN7 MDPS C 1.00 1.06 56310AA050\x00 4CNDC106\xf1\xa01.06',
+ ],
+ (Ecu.fwdCamera, 0x7c4, None): [b'\xf1\x00CN7 MFC AT USA LHD 1.00 1.00 99210-AB000 200819'],
+ (Ecu.esp, 0x7d1, None): [
+ b'\xf1\x8758910-AB800\xf1\x00CN ESC \t 101 \x10\x03 58910-AB800\xf1\xa01.01',
+ b'\xf1\x00CN ESC \t 101 \x10\x03 58910-AB800',
+ ],
+ (Ecu.transmission, 0x7e1, None): [
+ b'\xf1\x00HT6WA280BLHT6VA640A1CCN0N20NS5\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ b'\xf1\x00HT6WA280BLHT6VA640A1CCN0N20NS5\x00\x00\x00\x00\x00\x00\xe8\xba\xce\xfa',
+ b'\xf1\x87CXMQFM2135005JB2E\xb9\x89\x98W\xa9y\x97h\xa9\x98\x99wxvwh\x87\177\xffx\xff\xff\xff,,\xf1\x89HT6VA640A1\xf1\x82CCN0N20NS5\x00\x00\x00\x00\x00\x00',
+ ],
+ (Ecu.engine, 0x7e0, None): [b'\xf1\x82CNCWD0AMFCXCSFFA'],
+ }
}
CHECKSUM = {
- "crc8": [CAR.SANTA_FE, CAR.SONATA, CAR.PALISADE, CAR.KIA_SELTOS],
+ "crc8": [CAR.SANTA_FE, CAR.SONATA, CAR.PALISADE, CAR.KIA_SELTOS, CAR.ELANTRA_2021],
"6B": [CAR.KIA_SORENTO, CAR.HYUNDAI_GENESIS],
}
@@ -591,13 +603,14 @@ FEATURES = {
"use_elect_gears": set([CAR.KIA_NIRO_EV, CAR.KIA_OPTIMA_H, CAR.IONIQ_EV_LTD, CAR.KONA_EV, CAR.IONIQ, CAR.IONIQ_EV_2020]),
# these cars use the FCA11 message for the AEB and FCW signals, all others use SCC12
- "use_fca": set([CAR.SONATA, CAR.ELANTRA, CAR.ELANTRA_GT_I30, CAR.KIA_STINGER, CAR.IONIQ, CAR.IONIQ_EV_2020, CAR.KONA_EV, CAR.KIA_FORTE, CAR.KIA_NIRO_EV, CAR.PALISADE, CAR.GENESIS_G70, CAR.KONA, CAR.SANTA_FE, CAR.KIA_SELTOS]),
+ "use_fca": set([CAR.SONATA, CAR.ELANTRA, CAR.ELANTRA_2021, CAR.ELANTRA_GT_I30, CAR.KIA_STINGER, CAR.IONIQ, CAR.IONIQ_EV_2020, CAR.KONA_EV, CAR.KIA_FORTE, CAR.KIA_NIRO_EV, CAR.PALISADE, CAR.GENESIS_G70, CAR.KONA, CAR.SANTA_FE, CAR.KIA_SELTOS]),
}
EV_HYBRID = set([CAR.IONIQ_EV_2020, CAR.IONIQ_EV_LTD, CAR.IONIQ, CAR.KONA_EV, CAR.KIA_NIRO_EV])
DBC = {
CAR.ELANTRA: dbc_dict('hyundai_kia_generic', None),
+ CAR.ELANTRA_2021: dbc_dict('hyundai_kia_generic', None),
CAR.ELANTRA_GT_I30: dbc_dict('hyundai_kia_generic', None),
CAR.GENESIS_G70: dbc_dict('hyundai_kia_generic', None),
CAR.GENESIS_G80: dbc_dict('hyundai_kia_generic', None),
diff --git a/selfdrive/car/isotp_parallel_query.py b/selfdrive/car/isotp_parallel_query.py
index c95ef2c71..f95152258 100644
--- a/selfdrive/car/isotp_parallel_query.py
+++ b/selfdrive/car/isotp_parallel_query.py
@@ -1,6 +1,7 @@
import time
from collections import defaultdict
from functools import partial
+from typing import Optional
import cereal.messaging as messaging
from selfdrive.swaglog import cloudlog
@@ -8,7 +9,7 @@ from selfdrive.boardd.boardd import can_list_to_can_capnp
from panda.python.uds import CanClient, IsoTpMessage, FUNCTIONAL_ADDRS, get_rx_addr_for_tx_addr
-class IsoTpParallelQuery():
+class IsoTpParallelQuery:
def __init__(self, sendcan, logcan, bus, addrs, request, response, response_offset=0x8, functional_addr=False, debug=False):
self.sendcan = sendcan
self.logcan = logcan
@@ -103,7 +104,7 @@ class IsoTpParallelQuery():
break
for tx_addr, msg in msgs.items():
- dat = msg.recv()
+ dat: Optional[bytes] = msg.recv()
if not dat:
continue
@@ -121,7 +122,7 @@ class IsoTpParallelQuery():
request_done[tx_addr] = True
else:
request_done[tx_addr] = True
- cloudlog.warning(f"iso-tp query bad response: 0x{bytes.hex(dat)}")
+ cloudlog.warning(f"iso-tp query bad response: 0x{dat.hex()}")
if time.time() - start_time > timeout:
break
diff --git a/selfdrive/car/mazda/carstate.py b/selfdrive/car/mazda/carstate.py
index 7b8293570..fb720ad8f 100644
--- a/selfdrive/car/mazda/carstate.py
+++ b/selfdrive/car/mazda/carstate.py
@@ -9,8 +9,8 @@ class CarState(CarStateBase):
def __init__(self, CP):
super().__init__(CP)
- can_define = CANDefine(DBC[CP.carFingerprint]['pt'])
- self.shifter_values = can_define.dv["GEAR"]['GEAR']
+ can_define = CANDefine(DBC[CP.carFingerprint]["pt"])
+ self.shifter_values = can_define.dv["GEAR"]["GEAR"]
self.cruise_speed = 0
self.acc_active_last = False
@@ -21,43 +21,42 @@ class CarState(CarStateBase):
def update(self, cp, cp_cam):
ret = car.CarState.new_message()
- ret.wheelSpeeds.fl = cp.vl["WHEEL_SPEEDS"]['FL'] * CV.KPH_TO_MS
- ret.wheelSpeeds.fr = cp.vl["WHEEL_SPEEDS"]['FR'] * CV.KPH_TO_MS
- ret.wheelSpeeds.rl = cp.vl["WHEEL_SPEEDS"]['RL'] * CV.KPH_TO_MS
- ret.wheelSpeeds.rr = cp.vl["WHEEL_SPEEDS"]['RR'] * CV.KPH_TO_MS
+ ret.wheelSpeeds.fl = cp.vl["WHEEL_SPEEDS"]["FL"] * CV.KPH_TO_MS
+ ret.wheelSpeeds.fr = cp.vl["WHEEL_SPEEDS"]["FR"] * CV.KPH_TO_MS
+ ret.wheelSpeeds.rl = cp.vl["WHEEL_SPEEDS"]["RL"] * CV.KPH_TO_MS
+ ret.wheelSpeeds.rr = cp.vl["WHEEL_SPEEDS"]["RR"] * CV.KPH_TO_MS
ret.vEgoRaw = (ret.wheelSpeeds.fl + ret.wheelSpeeds.fr + ret.wheelSpeeds.rl + ret.wheelSpeeds.rr) / 4.
ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw)
# Match panda speed reading
- speed_kph = cp.vl["ENGINE_DATA"]['SPEED']
+ speed_kph = cp.vl["ENGINE_DATA"]["SPEED"]
ret.standstill = speed_kph < .1
- can_gear = int(cp.vl["GEAR"]['GEAR'])
+ can_gear = int(cp.vl["GEAR"]["GEAR"])
ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(can_gear, None))
- ret.leftBlinker = cp.vl["BLINK_INFO"]['LEFT_BLINK'] == 1
- ret.rightBlinker = cp.vl["BLINK_INFO"]['RIGHT_BLINK'] == 1
+ ret.leftBlinker = cp.vl["BLINK_INFO"]["LEFT_BLINK"] == 1
+ ret.rightBlinker = cp.vl["BLINK_INFO"]["RIGHT_BLINK"] == 1
- ret.steeringAngleDeg = cp.vl["STEER"]['STEER_ANGLE']
- ret.steeringTorque = cp.vl["STEER_TORQUE"]['STEER_TORQUE_SENSOR']
+ ret.steeringAngleDeg = cp.vl["STEER"]["STEER_ANGLE"]
+ ret.steeringTorque = cp.vl["STEER_TORQUE"]["STEER_TORQUE_SENSOR"]
ret.steeringPressed = abs(ret.steeringTorque) > LKAS_LIMITS.STEER_THRESHOLD
- ret.steeringTorqueEps = cp.vl["STEER_TORQUE"]['STEER_TORQUE_MOTOR']
- ret.steeringRateDeg = cp.vl["STEER_RATE"]['STEER_ANGLE_RATE']
+ ret.steeringTorqueEps = cp.vl["STEER_TORQUE"]["STEER_TORQUE_MOTOR"]
+ ret.steeringRateDeg = cp.vl["STEER_RATE"]["STEER_ANGLE_RATE"]
- ret.brakePressed = cp.vl["PEDALS"]['BRAKE_ON'] == 1
- ret.brake = cp.vl["BRAKE"]['BRAKE_PRESSURE']
- ret.brakeLights = ret.brakePressed
+ ret.brakePressed = cp.vl["PEDALS"]["BRAKE_ON"] == 1
+ ret.brake = cp.vl["BRAKE"]["BRAKE_PRESSURE"]
- ret.seatbeltUnlatched = cp.vl["SEATBELT"]['DRIVER_SEATBELT'] == 0
- ret.doorOpen = any([cp.vl["DOORS"]['FL'], cp.vl["DOORS"]['FR'],
- cp.vl["DOORS"]['BL'], cp.vl["DOORS"]['BR']])
+ ret.seatbeltUnlatched = cp.vl["SEATBELT"]["DRIVER_SEATBELT"] == 0
+ ret.doorOpen = any([cp.vl["DOORS"]["FL"], cp.vl["DOORS"]["FR"],
+ cp.vl["DOORS"]["BL"], cp.vl["DOORS"]["BR"]])
- ret.gas = cp.vl["ENGINE_DATA"]['PEDAL_GAS']
+ ret.gas = cp.vl["ENGINE_DATA"]["PEDAL_GAS"]
ret.gasPressed = ret.gas > 0
- ret.leftBlindspot = cp.vl["BSM"]['LEFT_BS1'] == 1
- ret.rightBlindspot = cp.vl["BSM"]['RIGHT_BS1'] == 1
+ ret.leftBlindspot = cp.vl["BSM"]["LEFT_BS1"] == 1
+ ret.rightBlindspot = cp.vl["BSM"]["RIGHT_BS1"] == 1
# LKAS is enabled at 52kph going up and disabled at 45kph going down
if speed_kph > LKAS_LIMITS.ENABLE_SPEED:
@@ -66,13 +65,13 @@ class CarState(CarStateBase):
self.lkas_allowed = False
# if any of the cruize buttons is pressed force state update
- if any([cp.vl["CRZ_BTNS"]['RES'],
- cp.vl["CRZ_BTNS"]['SET_P'],
- cp.vl["CRZ_BTNS"]['SET_M']]):
+ if any([cp.vl["CRZ_BTNS"]["RES"],
+ cp.vl["CRZ_BTNS"]["SET_P"],
+ cp.vl["CRZ_BTNS"]["SET_M"]]):
self.cruise_speed = ret.vEgoRaw
ret.cruiseState.available = True
- ret.cruiseState.enabled = cp.vl["CRZ_CTRL"]['CRZ_ACTIVE'] == 1
+ ret.cruiseState.enabled = cp.vl["CRZ_CTRL"]["CRZ_ACTIVE"] == 1
ret.cruiseState.speed = self.cruise_speed
if ret.cruiseState.enabled:
@@ -86,12 +85,12 @@ class CarState(CarStateBase):
self.low_speed_alert = False
# On if no driver torque the last 5 seconds
- ret.steerWarning = cp.vl["STEER_RATE"]['HANDS_OFF_5_SECONDS'] == 1
+ ret.steerWarning = cp.vl["STEER_RATE"]["HANDS_OFF_5_SECONDS"] == 1
self.acc_active_last = ret.cruiseState.enabled
self.cam_lkas = cp_cam.vl["CAM_LKAS"]
- ret.steerError = cp_cam.vl["CAM_LKAS"]['ERR_BIT_1'] == 1
+ ret.steerError = cp_cam.vl["CAM_LKAS"]["ERR_BIT_1"] == 1
return ret
@@ -158,7 +157,7 @@ class CarState(CarStateBase):
("BSM", 10),
]
- return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 0)
+ return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 0)
@staticmethod
def get_cam_can_parser(CP):
@@ -185,4 +184,4 @@ class CarState(CarStateBase):
("CAM_LKAS", 16),
]
- return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 2)
+ return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 2)
diff --git a/selfdrive/car/mazda/interface.py b/selfdrive/car/mazda/interface.py
index a7ab0ee0c..c79ff9b3a 100755
--- a/selfdrive/car/mazda/interface.py
+++ b/selfdrive/car/mazda/interface.py
@@ -44,13 +44,20 @@ class CarInterface(CarInterfaceBase):
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 == CAR.Mazda3:
+ elif candidate == CAR.MAZDA3:
ret.mass = 2875 * CV.LB_TO_KG + STD_CARGO_KG
ret.wheelbase = 2.7
ret.steerRatio = 14.0
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 == CAR.MAZDA6:
+ ret.mass = 3443 * CV.LB_TO_KG + STD_CARGO_KG
+ ret.wheelbase = 2.83
+ 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
# No steer below disable speed
ret.minSteerSpeed = LKAS_LIMITS.DISABLE_SPEED * CV.KPH_TO_MS
diff --git a/selfdrive/car/mazda/values.py b/selfdrive/car/mazda/values.py
index 60b9a8b58..6ad1da04a 100644
--- a/selfdrive/car/mazda/values.py
+++ b/selfdrive/car/mazda/values.py
@@ -17,9 +17,10 @@ class CarControllerParams:
STEER_DRIVER_FACTOR = 1 # from dbc
class CAR:
- CX5 = "Mazda CX-5 2017"
- CX9 = "Mazda CX-9 2017"
- Mazda3 = "Mazda3 2017"
+ CX5 = "MAZDA CX-5"
+ CX9 = "MAZDA CX-9"
+ MAZDA3 = "MAZDA 3"
+ MAZDA6 = "MAZDA 6"
class LKAS_LIMITS:
STEER_THRESHOLD = 15
@@ -33,49 +34,137 @@ class Buttons:
RESUME = 3
CANCEL = 4
-FINGERPRINTS = {
- CAR.CX5: [
- # CX-5 2017 GT
- {
- 64: 8, 70: 8, 80: 8, 117: 8, 118: 8, 120: 8, 121: 8, 130: 8, 134: 8, 145: 8, 154: 8, 155: 8, 157: 8, 158: 8, 159: 8, 253: 8, 304: 8, 305: 8, 357: 8, 358: 8, 359: 8, 512: 8, 514: 8, 515: 8, 529: 8, 533: 8, 535: 8, 539: 8, 540: 8, 541: 8, 542: 8, 543: 8, 552: 8, 576: 8, 577: 8, 578: 8, 579: 8, 580: 8, 581: 8, 582: 8, 605: 8, 606: 8, 607: 8, 608: 8, 628: 8, 832: 8, 836: 8, 863: 8, 865: 8, 866: 8, 867: 8, 868: 8, 869: 8, 870: 8, 976: 8, 977: 8, 978: 8, 1034: 8, 1045: 8, 1056: 8, 1061: 8, 1067: 8, 1070: 8, 1078: 8, 1080: 8, 1085: 8, 1086: 8, 1088: 8, 1093: 8, 1108: 8, 1114: 8, 1115: 8, 1116: 8, 1139: 8, 1143: 8, 1147: 8, 1154: 8, 1157: 8, 1160: 8, 1163: 8, 1166: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1183: 8, 1233: 8, 1236: 8, 1237: 8, 1238: 8, 1239: 8, 1241: 8, 1242: 8, 1243: 8, 1244: 8, 1264: 8, 1266: 8, 1267: 8, 1269: 8, 1270: 8, 1271: 8, 1272: 8, 1274: 8, 1275: 8, 1277: 8, 1278: 8, 1409: 8, 1416: 8, 1425: 8, 1430: 8, 1435: 8, 1440: 8, 1446: 8, 1456: 8, 1479: 8
- },
- # CX-5 2019 GTR
- {
- 64: 8, 70: 8, 80: 8, 117: 8, 118: 8, 120: 8, 121: 8, 130: 8, 134: 8, 145: 8, 154: 8, 155: 8, 157: 8, 158: 8, 159: 8, 253: 8, 254: 8, 304: 8, 305: 8, 357: 8, 358: 8, 359: 8, 512: 8, 514: 8, 515: 8, 529: 8, 533: 8, 535: 8, 539: 8, 540: 8, 541: 8, 542: 8, 543: 8, 552: 8, 576: 8, 577: 8, 578: 8, 579: 8, 580: 8, 581: 8, 582: 8, 605: 8, 606: 8, 607: 8, 608: 8, 628: 8, 736: 8, 832: 8, 836: 8, 863: 8, 865: 8, 866: 8, 867: 8, 868: 8, 869: 8, 870: 8, 976: 8, 977: 8, 978: 8, 1034: 8, 1045: 8, 1056: 8, 1061: 8, 1067: 8, 1078: 8, 1080: 8, 1085: 8, 1086: 8, 1088: 8, 1093: 8, 1108: 8, 1114: 8, 1115: 8, 1116: 8, 1139: 8, 1143: 8, 1147: 8, 1154: 8, 1157: 8, 1160: 8, 1163: 8, 1166: 8, 1170: 8, 1171: 8, 1173: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1183: 8, 1233: 8, 1236: 8, 1237: 8, 1238: 8, 1239: 8, 1241: 8, 1242: 8, 1244: 8, 1260: 8, 1264: 8, 1266: 8, 1267: 8, 1269: 8, 1270: 8, 1271: 8, 1272: 8, 1274: 8, 1277: 8, 1278: 8, 1409: 8, 1416: 8, 1425: 8, 1430: 8, 1435: 8, 1440: 8, 1446: 8, 1456: 8, 1479: 8, 1776: 8, 1792: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 2015: 8, 2016: 8, 2024: 8
- }
- ],
+FW_VERSIONS = {
+ CAR.CX5: {
+ (Ecu.eps, 0x730, None): [
+ b'KJ01-3210X-G-00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ b'KJ01-3210X-M-00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ b'K319-3210X-A-00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ ],
+ (Ecu.engine, 0x7e0, None): [
+ b'PYNF-188K2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ b'PYFC-188K2-J\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ b'PX2G-188K2-D\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'PX68-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ ],
+ (Ecu.fwdRadar, 0x764, None): [
+ b'K123-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ b'K131-67XK2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ b'K131-67XK2-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',
+ ],
+ (Ecu.esp, 0x760, None): [
+ b'K123-437K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ b'KL2K-437K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ b'KN0W-437K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ b'KBJ5-437K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ ],
+ (Ecu.fwdCamera, 0x706, None): [
+ b'B61L-67XK2-T\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ b'B61L-67XK2-R\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-N\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ ],
+ (Ecu.transmission, 0x7e1, None): [
+ b'PX39-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ b'PX68-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ b'PYB2-21PS1-B\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'PYB2-21PS1-G\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ ],
+ },
- CAR.CX9: [
- # CX-9 2017 Australia - old CAM connector
- {
- 64: 8, 70: 8, 80: 8, 117: 8, 118: 8, 120: 8, 121: 8, 130: 8, 134: 8, 138: 8, 145: 8, 154: 8, 155: 8, 157: 8, 158: 8, 159: 8, 253: 8, 304: 8, 305: 8, 357: 8, 358: 8, 359: 8, 512: 8, 514: 8, 515: 8, 522: 8, 529: 8, 533: 8, 535: 8, 539: 8, 540: 8, 541: 8, 542: 8, 543: 8, 552: 8, 576: 8, 577: 8, 578: 8, 579: 8, 580: 8, 581: 8, 582: 8, 583: 8, 605: 8, 606: 8, 628: 8, 832: 8, 976: 8, 977: 8, 978: 8, 1034: 8, 1045: 8, 1056: 8, 1061: 8, 1067: 8, 1078: 8, 1085: 8, 1086: 8, 1088: 8, 1093: 8, 1108: 8, 1114: 8, 1115: 8, 1116: 8, 1139: 8, 1143: 8, 1147: 8, 1154: 8, 1157: 8, 1160: 8, 1163: 8, 1166: 8, 1170: 8, 1177: 8, 1180: 8, 1183: 8, 1233: 8, 1236: 8, 1237: 8, 1238: 8, 1239: 8, 1241: 8, 1242: 8, 1243: 8, 1244: 8, 1247: 8, 1264: 8, 1266: 8, 1267: 8, 1269: 8, 1271: 8, 1272: 8, 1274: 8, 1277: 8, 1278: 8, 1409: 8, 1416: 8, 1425: 8, 1430: 8, 1435: 8, 1440: 8, 1446: 8, 1456: 8, 1479: 8
- },
+ CAR.CX9 : {
+ (Ecu.eps, 0x730, None): [
+ b'K070-3210X-C-00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ b'KJ01-3210X-L-00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ ],
+ (Ecu.engine, 0x7e0, None): [
+ b'PYFM-188K2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ b'PX23-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ b'PXN8-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ ],
+ (Ecu.fwdRadar, 0x764, None): [
+ b'TK80-67XK2-E\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',
+ ],
+ (Ecu.esp, 0x760, None): [
+ b'TK79-437K2-E\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',
+ b'TA0B-437K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ ],
+ (Ecu.fwdCamera, 0x706, None): [
+ b'TK80-67XK2-C\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-K\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ ],
+ (Ecu.transmission, 0x7e1, None): [
+ b'PYFM-21PS1-C\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'PXM7-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ ],
+ },
- # CX-9 2016 - old CAM connector
- {
- 64: 8, 70: 8, 80: 8, 117: 8, 118: 8, 120: 8, 121: 8, 130: 8, 134: 8, 145: 8, 154: 8, 155: 8, 157: 8, 158: 8, 159: 8, 253: 8, 304: 8, 305: 8, 357: 8, 358: 8, 359: 8, 512: 8, 514: 8, 515: 8, 529: 8, 533: 8, 535: 8, 539: 8, 540: 8, 541: 8, 542: 8, 543: 8, 552: 8, 576: 8, 577: 8, 578: 8, 579: 8, 580: 8, 581: 8, 582: 8, 583: 8, 605: 8, 606: 8, 608: 8, 628: 8, 832: 8, 836: 8, 976: 8, 977: 8, 978: 8, 1034: 8, 1045: 8, 1056: 8, 1061: 8, 1067: 8, 1078: 8, 1080: 8, 1085: 8, 1086: 8, 1088: 8, 1093: 8, 1108: 8, 1114: 8, 1115: 8, 1116: 8, 1139: 8, 1143: 8, 1147: 8, 1154: 8, 1157: 8, 1160: 8, 1163: 8, 1166: 8, 1170: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1183: 8, 1233: 8, 1236: 8, 1237: 8, 1238: 8, 1239: 8, 1241: 8, 1242: 8, 1244: 8, 1264: 8, 1266: 8, 1267: 8, 1269: 8, 1271: 8, 1272: 8, 1274: 8, 1277: 8, 1278: 8, 1409: 8, 1416: 8, 1425: 8, 1430: 8, 1435: 8, 1440: 8, 1446: 8, 1456: 8, 1479: 8, 1792: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 1988: 8, 1996: 8, 2000: 8, 2001: 8, 2004: 8, 2015: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8
- }
- ],
+ CAR.MAZDA3: {
+ (Ecu.eps, 0x730, None): [
+ b'PY2P-188K2-C\x00\x00\x00\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'PYKC-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ ],
+ (Ecu.fwdRadar, 0x764, None): [
+ b'GHP9-67Y10---41\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ b'K131-67XK2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ b'B63C-67XK2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ ],
+ (Ecu.esp, 0x760, None): [
+ b'B45A-437AS-0-08\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ ],
+ (Ecu.fwdCamera, 0x706, None): [
+ b'B61L-67XK2-P\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ b'B61L-67XK2-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'PYKE-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ ],
+ },
- CAR.Mazda3: [
- # Mazda 3 2017
- {
- 19: 5, 80: 8, 117: 8, 118: 8, 120: 8, 121: 8, 130: 8, 134: 8, 138: 8, 145: 8, 154: 8, 155: 8, 157: 8, 158: 8, 159: 8, 253: 8, 304: 8, 305: 8, 357: 8, 358: 8, 359: 8, 512: 8, 514: 8, 515: 8, 522: 8, 529: 8, 533: 8, 535: 8, 539: 8, 540: 8, 541: 8, 542: 8, 543: 8, 552: 8, 576: 8, 577: 8, 578: 8, 579: 8, 580: 8, 581: 8, 582: 8, 605: 8, 606: 8, 607: 8, 628: 8, 832: 8, 863: 8, 865: 8, 866: 8, 867: 8, 868: 8, 869: 8, 870: 8, 976: 8, 977: 8, 978: 8, 1034: 8, 1045: 8, 1056: 8, 1061: 8, 1067: 8, 1070: 8, 1078: 8, 1086: 8, 1088: 8, 1093: 8, 1108: 8, 1114: 8, 1115: 8, 1116: 8, 1143: 8, 1147: 8, 1154: 8, 1157: 8, 1160: 8, 1163: 8, 1166: 8, 1169: 8, 1170: 8, 1173: 8, 1177: 8, 1180: 8, 1182: 8, 1183: 8, 1232: 8, 1233: 8, 1234: 8, 1235: 8, 1236: 8, 1237: 8, 1238: 8, 1239: 8,1240: 8, 1241: 8, 1242: 8, 1243: 8, 1244: 8, 1246: 8, 1247: 8, 1264: 8, 1266: 8, 1267: 8, 1269: 8, 1270: 8, 1271: 8, 1272: 8, 1274: 8, 1275: 8, 1277: 8, 1278: 8, 1409: 8, 1416: 8, 1425: 8, 1430: 8, 1435: 8, 1440: 8, 1456: 8, 1479: 8, 2015: 8, 2024: 8, 2025: 8
- },
-
- # Mazda 6 2017 GT
- {
- 64: 8, 70: 8, 80: 8, 117: 8, 118: 8, 120: 8, 121: 8, 130: 8, 134: 8, 145: 8, 154: 8, 155: 8, 157: 8, 158: 8, 159: 8, 253: 8, 304: 8, 305: 8, 357: 8, 358: 8, 359: 8, 512: 8, 514: 8, 515: 8, 529: 8, 533: 8, 535: 8, 539: 8, 540: 8, 541: 8, 542: 8, 543: 8, 552: 8, 576: 8, 577: 8, 578: 8, 579: 8, 580: 8, 581: 8, 582: 8, 605: 8, 606: 8, 607: 8, 628: 8, 832: 8, 836: 8, 863: 8, 865: 8, 866: 8, 867: 8, 868: 8, 869: 8, 870: 8, 976: 8, 977: 8, 978: 8, 1034: 8, 1045: 8, 1056: 8, 1061: 8, 1067: 8, 1070: 8, 1078: 8, 1080: 8, 1085: 8, 1086: 8, 1088: 8, 1093: 8, 1108: 8, 1114: 8, 1115: 8, 1116: 8, 1143: 8, 1147: 8, 1154: 8, 1157: 8, 1160: 8, 1163: 8, 1166: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1182: 8, 1183: 8, 1233: 8, 1236: 8, 1237: 8, 1238: 8, 1239: 8, 1241: 8, 1242: 8, 1243: 8, 1244: 8, 1264: 8, 1266: 8, 1267: 8, 1269: 8, 1270: 8, 1271: 8, 1272: 8, 1274: 8, 1275: 8, 1277: 8, 1278: 8, 1409: 8, 1416: 8, 1425: 8, 1430: 8, 1435: 8, 1440: 8, 1456: 8, 1479: 8
- }
- ],
+ CAR.MAZDA6: {
+ (Ecu.eps, 0x730, None): [
+ b'GBEF-3210X-B-00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ ],
+ (Ecu.engine, 0x7e0, None): [
+ b'PYH7-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ ],
+ (Ecu.fwdRadar, 0x764, None): [
+ b'K131-67XK2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ ],
+ (Ecu.esp, 0x760, None): [
+ b'GBVH-437K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ ],
+ (Ecu.fwdCamera, 0x706, None): [
+ b'B61L-67XK2-S\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ ],
+ (Ecu.transmission, 0x7e1, None): [
+ b'PYH7-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
+ ],
+ }
}
DBC = {
CAR.CX5: dbc_dict('mazda_2017', None),
CAR.CX9: dbc_dict('mazda_2017', None),
- CAR.Mazda3: dbc_dict('mazda_2017', None),
+ CAR.MAZDA3: dbc_dict('mazda_2017', None),
+ CAR.MAZDA6: dbc_dict('mazda_2017', None),
}
-GEN1 = [ CAR.CX5, CAR.CX9, CAR.Mazda3 ]
+GEN1 = [ CAR.CX5, CAR.CX9, CAR.MAZDA3, CAR.MAZDA6 ]
diff --git a/selfdrive/car/nissan/carstate.py b/selfdrive/car/nissan/carstate.py
index 45a4e6935..4e5e02cdf 100644
--- a/selfdrive/car/nissan/carstate.py
+++ b/selfdrive/car/nissan/carstate.py
@@ -12,7 +12,7 @@ TORQUE_SAMPLES = 12
class CarState(CarStateBase):
def __init__(self, CP):
super().__init__(CP)
- can_define = CANDefine(DBC[CP.carFingerprint]['pt'])
+ can_define = CANDefine(DBC[CP.carFingerprint]["pt"])
self.lkas_hud_msg = None
self.lkas_hud_info_msg = None
@@ -35,9 +35,6 @@ class CarState(CarStateBase):
elif self.CP.carFingerprint in [CAR.LEAF, CAR.LEAF_IC]:
ret.brakePressed = bool(cp.vl["BRAKE_PEDAL"]["BRAKE_PEDAL"] > 3)
- if self.CP.carFingerprint in [CAR.ROGUE, CAR.XTRAIL, CAR.ALTIMA]:
- ret.brakeLights = bool(cp.vl["DOORS_LIGHTS"]["BRAKE_LIGHT"])
-
ret.wheelSpeeds.fl = cp.vl["WHEEL_SPEEDS_FRONT"]["WHEEL_SPEED_FL"] * CV.KPH_TO_MS
ret.wheelSpeeds.fr = cp.vl["WHEEL_SPEEDS_FRONT"]["WHEEL_SPEED_FR"] * CV.KPH_TO_MS
ret.wheelSpeeds.rl = cp.vl["WHEEL_SPEEDS_REAR"]["WHEEL_SPEED_RL"] * CV.KPH_TO_MS
@@ -158,7 +155,6 @@ class CarState(CarStateBase):
if CP.carFingerprint in [CAR.ROGUE, CAR.XTRAIL, CAR.ALTIMA]:
signals += [
("USER_BRAKE_PRESSED", "DOORS_LIGHTS", 1),
- ("BRAKE_LIGHT", "DOORS_LIGHTS", 1),
("GAS_PEDAL", "GAS_PEDAL", 0),
("SEATBELT_DRIVER_LATCHED", "HUD", 0),
@@ -220,7 +216,7 @@ class CarState(CarStateBase):
("LKAS_SETTINGS", 10),
("PROPILOT_HUD", 50),
]
- return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 1)
+ return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 1)
signals += [
("STEER_TORQUE_DRIVER", "STEER_TORQUE_SENSOR", 0),
@@ -229,7 +225,7 @@ class CarState(CarStateBase):
("STEER_TORQUE_SENSOR", 100),
]
- return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 0)
+ return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 0)
@staticmethod
def get_adas_can_parser(CP):
@@ -341,7 +337,7 @@ class CarState(CarStateBase):
("LKAS", 100),
]
- return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 2)
+ return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 2)
@staticmethod
def get_cam_can_parser(CP):
@@ -362,7 +358,7 @@ class CarState(CarStateBase):
checks += [
("STEER_TORQUE_SENSOR", 100),
]
- return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 0)
+ return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 0)
- return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 1)
+ return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 1)
diff --git a/selfdrive/car/nissan/values.py b/selfdrive/car/nissan/values.py
index 1bd8d8d80..3c91d3d22 100644
--- a/selfdrive/car/nissan/values.py
+++ b/selfdrive/car/nissan/values.py
@@ -50,7 +50,7 @@ FINGERPRINTS = {
],
CAR.ALTIMA: [
{
- 2: 5, 42: 6, 346: 6, 347: 5, 348: 8, 349: 7, 386: 8, 397: 8, 398: 8, 520: 2, 523: 6, 548: 8, 634: 7, 645: 8, 658: 8, 665: 8, 666: 8, 674: 2, 682: 8, 683: 8, 689: 8, 723: 8, 758: 3, 772: 8, 773: 6, 774: 7, 775: 8, 776: 6, 777: 7, 778: 6, 783: 3, 851: 8, 855: 5, 1001: 6, 1041: 8, 1042: 8, 1055: 3, 1100: 7, 1104: 4, 1105: 6, 1107: 4, 1108: 8, 1110: 7, 1111: 7, 1227: 8, 1228: 8, 1229: 8, 1232: 8, 1247: 4, 1266: 8, 1273: 7, 1306: 1, 1342: 1, 1376: 8, 1401: 8, 1497: 3, 1514: 6, 1526: 8, 1527: 5, 1792: 8, 1821: 8, 1823: 8, 1837: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 1988: 8, 2000: 8, 2001: 8, 2004: 8, 2005: 8, 2015: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8
+ 2: 5, 42: 6, 346: 6, 347: 5, 348: 8, 349: 7, 361: 8, 386: 8, 389: 8, 397: 8, 398: 8, 403: 8, 438: 8, 451: 8, 517: 8, 520: 2, 522: 8, 523: 6, 539: 8, 541: 7, 542: 8, 543: 8, 544: 8, 545: 8, 546: 8, 547: 8, 548: 8, 570: 8, 576: 8, 577: 8, 582: 8, 583: 8, 584: 8, 586: 8, 587: 8, 588: 8, 589: 8, 590: 8, 591: 8, 592: 8, 600: 8, 601: 8, 610: 8, 611: 8, 612: 8, 614: 8, 615: 8, 616: 8, 617: 8, 622: 8, 623: 8, 634: 7, 638: 8, 645: 8, 648: 5, 654: 6, 658: 8, 659: 8, 660: 8, 661: 8, 665: 8, 666: 8, 674: 2, 675: 8, 676: 8, 682: 8, 683: 8, 684: 8, 685: 8, 686: 8, 687: 8, 689: 8, 690: 8, 703: 8, 708: 7, 709: 7, 711: 7, 712: 7, 713: 7, 714: 8, 715: 8, 716: 8, 717: 7, 718: 7, 719: 7, 720: 7, 723: 8, 726: 7, 727: 7, 728: 7, 735: 8, 746: 8, 748: 6, 749: 6, 750: 8, 758: 3, 772: 8, 773: 6, 774: 7, 775: 8, 776: 6, 777: 7, 778: 6, 779: 7, 781: 7, 782: 7, 783: 3, 851: 8, 855: 5, 1001: 6, 1041: 8, 1042: 8, 1055: 3, 1100: 7, 1104: 4, 1105: 6, 1107: 4, 1108: 8, 1110: 7, 1111: 7, 1144: 7, 1145: 7, 1227: 8, 1228: 8, 1229: 8, 1232: 8, 1247: 4, 1258: 8, 1259: 8, 1266: 8, 1273: 7, 1306: 1, 1314: 8, 1323: 8, 1324: 8, 1342: 1, 1376: 8, 1401: 8, 1454: 8, 1497: 3, 1514: 6, 1526: 8, 1527: 5, 1792: 8, 1821: 8, 1823: 8, 1837: 8, 1872: 8, 1937: 8, 1953: 8, 1968: 8, 1988: 8, 2000: 8, 2001: 8, 2004: 8, 2005: 8, 2015: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8
},
]
}
diff --git a/selfdrive/car/subaru/carcontroller.py b/selfdrive/car/subaru/carcontroller.py
index a15e03b58..8ec957a65 100644
--- a/selfdrive/car/subaru/carcontroller.py
+++ b/selfdrive/car/subaru/carcontroller.py
@@ -10,7 +10,7 @@ class CarController():
self.es_distance_cnt = -1
self.es_accel_cnt = -1
self.es_lkas_cnt = -1
- self.fake_button_prev = 0
+ self.cruise_button_prev = 0
self.steer_rate_limited = False
self.packer = CANPacker(DBC[CP.carFingerprint]['pt'])
@@ -48,19 +48,19 @@ class CarController():
# 1 = main, 2 = set shallow, 3 = set deep, 4 = resume shallow, 5 = resume deep
# disengage ACC when OP is disengaged
if pcm_cancel_cmd:
- fake_button = 1
+ cruise_button = 1
# turn main on if off and past start-up state
elif not CS.out.cruiseState.available and CS.ready:
- fake_button = 1
+ cruise_button = 1
else:
- fake_button = CS.button
+ cruise_button = CS.cruise_button
# unstick previous mocked button press
- if fake_button == 1 and self.fake_button_prev == 1:
- fake_button = 0
- self.fake_button_prev = fake_button
+ if cruise_button == 1 and self.cruise_button_prev == 1:
+ cruise_button = 0
+ self.cruise_button_prev = cruise_button
- can_sends.append(subarucan.create_es_throttle_control(self.packer, fake_button, CS.es_accel_msg))
+ 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"]
else:
diff --git a/selfdrive/car/subaru/carstate.py b/selfdrive/car/subaru/carstate.py
index 1eb7699f7..888c370eb 100644
--- a/selfdrive/car/subaru/carstate.py
+++ b/selfdrive/car/subaru/carstate.py
@@ -10,70 +10,68 @@ from selfdrive.car.subaru.values import DBC, STEER_THRESHOLD, CAR, PREGLOBAL_CAR
class CarState(CarStateBase):
def __init__(self, CP):
super().__init__(CP)
- can_define = CANDefine(DBC[CP.carFingerprint]['pt'])
- self.shifter_values = can_define.dv["Transmission"]['Gear']
+ can_define = CANDefine(DBC[CP.carFingerprint]["pt"])
+ self.shifter_values = can_define.dv["Transmission"]["Gear"]
def update(self, cp, cp_cam):
ret = car.CarState.new_message()
- ret.gas = cp.vl["Throttle"]['Throttle_Pedal'] / 255.
+ ret.gas = cp.vl["Throttle"]["Throttle_Pedal"] / 255.
ret.gasPressed = ret.gas > 1e-5
if self.car_fingerprint in PREGLOBAL_CARS:
- ret.brakePressed = cp.vl["Brake_Pedal"]['Brake_Pedal'] > 2
+ ret.brakePressed = cp.vl["Brake_Pedal"]["Brake_Pedal"] > 2
else:
- ret.brakePressed = cp.vl["Brake_Pedal"]['Brake_Pedal'] > 1e-5
- ret.brakeLights = ret.brakePressed
+ ret.brakePressed = cp.vl["Brake_Pedal"]["Brake_Pedal"] > 1e-5
- ret.wheelSpeeds.fl = cp.vl["Wheel_Speeds"]['FL'] * CV.KPH_TO_MS
- ret.wheelSpeeds.fr = cp.vl["Wheel_Speeds"]['FR'] * CV.KPH_TO_MS
- ret.wheelSpeeds.rl = cp.vl["Wheel_Speeds"]['RL'] * CV.KPH_TO_MS
- ret.wheelSpeeds.rr = cp.vl["Wheel_Speeds"]['RR'] * CV.KPH_TO_MS
+ ret.wheelSpeeds.fl = cp.vl["Wheel_Speeds"]["FL"] * CV.KPH_TO_MS
+ ret.wheelSpeeds.fr = cp.vl["Wheel_Speeds"]["FR"] * CV.KPH_TO_MS
+ ret.wheelSpeeds.rl = cp.vl["Wheel_Speeds"]["RL"] * CV.KPH_TO_MS
+ ret.wheelSpeeds.rr = cp.vl["Wheel_Speeds"]["RR"] * CV.KPH_TO_MS
ret.vEgoRaw = (ret.wheelSpeeds.fl + ret.wheelSpeeds.fr + ret.wheelSpeeds.rl + ret.wheelSpeeds.rr) / 4.
# Kalman filter, even though Subaru raw wheel speed is heaviliy filtered by default
ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw)
ret.standstill = ret.vEgoRaw < 0.01
# continuous blinker signals for assisted lane change
- ret.leftBlinker, ret.rightBlinker = self.update_blinker(50, cp.vl["Dashlights"]['LEFT_BLINKER'],
- cp.vl["Dashlights"]['RIGHT_BLINKER'])
+ ret.leftBlinker, ret.rightBlinker = self.update_blinker(50, cp.vl["Dashlights"]["LEFT_BLINKER"],
+ cp.vl["Dashlights"]["RIGHT_BLINKER"])
if self.CP.enableBsm:
- ret.leftBlindspot = (cp.vl["BSD_RCTA"]['L_ADJACENT'] == 1) or (cp.vl["BSD_RCTA"]['L_APPROACHING'] == 1)
- ret.rightBlindspot = (cp.vl["BSD_RCTA"]['R_ADJACENT'] == 1) or (cp.vl["BSD_RCTA"]['R_APPROACHING'] == 1)
+ ret.leftBlindspot = (cp.vl["BSD_RCTA"]["L_ADJACENT"] == 1) or (cp.vl["BSD_RCTA"]["L_APPROACHING"] == 1)
+ ret.rightBlindspot = (cp.vl["BSD_RCTA"]["R_ADJACENT"] == 1) or (cp.vl["BSD_RCTA"]["R_APPROACHING"] == 1)
- can_gear = int(cp.vl["Transmission"]['Gear'])
+ can_gear = int(cp.vl["Transmission"]["Gear"])
ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(can_gear, None))
- ret.steeringAngleDeg = cp.vl["Steering_Torque"]['Steering_Angle']
- ret.steeringTorque = cp.vl["Steering_Torque"]['Steer_Torque_Sensor']
+ ret.steeringAngleDeg = cp.vl["Steering_Torque"]["Steering_Angle"]
+ ret.steeringTorque = cp.vl["Steering_Torque"]["Steer_Torque_Sensor"]
ret.steeringPressed = abs(ret.steeringTorque) > STEER_THRESHOLD[self.car_fingerprint]
- ret.cruiseState.enabled = cp.vl["CruiseControl"]['Cruise_Activated'] != 0
- ret.cruiseState.available = cp.vl["CruiseControl"]['Cruise_On'] != 0
- ret.cruiseState.speed = cp_cam.vl["ES_DashStatus"]['Cruise_Set_Speed'] * CV.KPH_TO_MS
+ ret.cruiseState.enabled = cp.vl["CruiseControl"]["Cruise_Activated"] != 0
+ ret.cruiseState.available = cp.vl["CruiseControl"]["Cruise_On"] != 0
+ ret.cruiseState.speed = cp_cam.vl["ES_DashStatus"]["Cruise_Set_Speed"] * CV.KPH_TO_MS
# UDM Forester, Legacy: mph = 0
- if self.car_fingerprint in [CAR.FORESTER_PREGLOBAL, CAR.LEGACY_PREGLOBAL] and cp.vl["Dash_State"]['Units'] == 0:
+ if self.car_fingerprint in [CAR.FORESTER_PREGLOBAL, CAR.LEGACY_PREGLOBAL] and cp.vl["Dash_State"]["Units"] == 0:
ret.cruiseState.speed *= CV.MPH_TO_KPH
# EDM Global: mph = 1, 2; All Outback: mph = 1, UDM Forester: mph = 7
- elif self.car_fingerprint not in [CAR.FORESTER_PREGLOBAL, CAR.LEGACY_PREGLOBAL] and cp.vl["Dash_State"]['Units'] in [1, 2, 7]:
+ elif self.car_fingerprint not in [CAR.FORESTER_PREGLOBAL, CAR.LEGACY_PREGLOBAL] and cp.vl["Dash_State"]["Units"] in [1, 2, 7]:
ret.cruiseState.speed *= CV.MPH_TO_KPH
- ret.seatbeltUnlatched = cp.vl["Dashlights"]['SEATBELT_FL'] == 1
- ret.doorOpen = any([cp.vl["BodyInfo"]['DOOR_OPEN_RR'],
- cp.vl["BodyInfo"]['DOOR_OPEN_RL'],
- cp.vl["BodyInfo"]['DOOR_OPEN_FR'],
- cp.vl["BodyInfo"]['DOOR_OPEN_FL']])
+ ret.seatbeltUnlatched = cp.vl["Dashlights"]["SEATBELT_FL"] == 1
+ ret.doorOpen = any([cp.vl["BodyInfo"]["DOOR_OPEN_RR"],
+ cp.vl["BodyInfo"]["DOOR_OPEN_RL"],
+ cp.vl["BodyInfo"]["DOOR_OPEN_FR"],
+ cp.vl["BodyInfo"]["DOOR_OPEN_FL"]])
+ ret.steerError = cp.vl["Steering_Torque"]["Steer_Error_1"] == 1
if self.car_fingerprint in PREGLOBAL_CARS:
- ret.steerError = cp.vl["Steering_Torque"]["LKA_Lockout"] == 1
- self.button = cp_cam.vl["ES_CruiseThrottle"]["Button"]
+ self.cruise_button = cp_cam.vl["ES_CruiseThrottle"]["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.steerError = cp.vl["Steering_Torque"]['Steer_Error_1'] == 1
- ret.steerWarning = cp.vl["Steering_Torque"]['Steer_Warning'] == 1
- ret.cruiseState.nonAdaptive = cp_cam.vl["ES_DashStatus"]['Conventional_Cruise'] == 1
+ 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"])
@@ -86,6 +84,7 @@ class CarState(CarStateBase):
# 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),
@@ -128,13 +127,8 @@ class CarState(CarStateBase):
("BSD_RCTA", 17),
]
- if CP.carFingerprint in PREGLOBAL_CARS:
+ if CP.carFingerprint not in PREGLOBAL_CARS:
signals += [
- ("LKA_Lockout", "Steering_Torque", 0),
- ]
- else:
- signals += [
- ("Steer_Error_1", "Steering_Torque", 0),
("Steer_Warning", "Steering_Torque", 0),
]
@@ -157,7 +151,7 @@ class CarState(CarStateBase):
("CruiseControl", 50),
]
- return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 0)
+ return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 0)
@staticmethod
def get_cam_can_parser(CP):
@@ -171,17 +165,17 @@ class CarState(CarStateBase):
("Cruise_Activated", "ES_CruiseThrottle", 0),
("Signal2", "ES_CruiseThrottle", 0),
("Brake_On", "ES_CruiseThrottle", 0),
- ("DistanceSwap", "ES_CruiseThrottle", 0),
+ ("Distance_Swap", "ES_CruiseThrottle", 0),
("Standstill", "ES_CruiseThrottle", 0),
("Signal3", "ES_CruiseThrottle", 0),
- ("CloseDistance", "ES_CruiseThrottle", 0),
+ ("Close_Distance", "ES_CruiseThrottle", 0),
("Signal4", "ES_CruiseThrottle", 0),
("Standstill_2", "ES_CruiseThrottle", 0),
- ("ES_Error", "ES_CruiseThrottle", 0),
+ ("Cruise_Fault", "ES_CruiseThrottle", 0),
("Signal5", "ES_CruiseThrottle", 0),
("Counter", "ES_CruiseThrottle", 0),
("Signal6", "ES_CruiseThrottle", 0),
- ("Button", "ES_CruiseThrottle", 0),
+ ("Cruise_Button", "ES_CruiseThrottle", 0),
("Signal7", "ES_CruiseThrottle", 0),
]
@@ -237,4 +231,4 @@ class CarState(CarStateBase):
("ES_LKAS_State", 10),
]
- return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 2)
+ return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 2)
diff --git a/selfdrive/car/subaru/interface.py b/selfdrive/car/subaru/interface.py
index bc5502f48..bb8669fb1 100644
--- a/selfdrive/car/subaru/interface.py
+++ b/selfdrive/car/subaru/interface.py
@@ -19,15 +19,16 @@ class CarInterface(CarInterfaceBase):
if candidate in PREGLOBAL_CARS:
ret.safetyModel = car.CarParams.SafetyModel.subaruLegacy
+ ret.enableBsm = 0x25c in fingerprint[0]
else:
ret.safetyModel = car.CarParams.SafetyModel.subaru
+ ret.enableBsm = 0x228 in fingerprint[0]
# Subaru port is a community feature, since we don't own one to test
ret.communityFeature = True
ret.dashcamOnly = candidate in PREGLOBAL_CARS
ret.enableCamera = True
- ret.enableBsm = 0x228 in fingerprint[0]
ret.steerRateCost = 0.7
ret.steerLimitTimer = 0.4
diff --git a/selfdrive/car/subaru/subarucan.py b/selfdrive/car/subaru/subarucan.py
index 8249d36ba..672b6873b 100644
--- a/selfdrive/car/subaru/subarucan.py
+++ b/selfdrive/car/subaru/subarucan.py
@@ -57,10 +57,10 @@ 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, fake_button, es_accel_msg):
+def create_es_throttle_control(packer, cruise_button, es_accel_msg):
values = copy.copy(es_accel_msg)
- values["Button"] = fake_button
+ values["Cruise_Button"] = cruise_button
values["Checksum"] = subaru_preglobal_checksum(packer, values, "ES_CruiseThrottle")
diff --git a/selfdrive/car/tests/test_car_interfaces.py b/selfdrive/car/tests/test_car_interfaces.py
index 7f603cb42..93dc05c83 100755
--- a/selfdrive/car/tests/test_car_interfaces.py
+++ b/selfdrive/car/tests/test_car_interfaces.py
@@ -13,7 +13,10 @@ class TestCarInterfaces(unittest.TestCase):
@parameterized.expand([(car,) for car in all_known_cars()])
def test_car_interfaces(self, car_name):
print(car_name)
- fingerprint = FINGERPRINTS[car_name][0]
+ if car_name in FINGERPRINTS:
+ fingerprint = FINGERPRINTS[car_name][0]
+ else:
+ fingerprint = {}
CarInterface, CarController, CarState = interfaces[car_name]
fingerprints = {
diff --git a/selfdrive/car/toyota/carcontroller.py b/selfdrive/car/toyota/carcontroller.py
index c961288aa..1bc18efb7 100644
--- a/selfdrive/car/toyota/carcontroller.py
+++ b/selfdrive/car/toyota/carcontroller.py
@@ -4,7 +4,8 @@ from selfdrive.car import apply_toyota_steer_torque_limits, create_gas_command,
from selfdrive.car.toyota.toyotacan import create_steer_command, create_ui_command, \
create_accel_command, create_acc_cancel_command, \
create_fcw_command, create_lta_steer_command
-from selfdrive.car.toyota.values import Ecu, CAR, STATIC_MSGS, NO_STOP_TIMER_CAR, TSS2_CAR, CarControllerParams
+from selfdrive.car.toyota.values import Ecu, CAR, STATIC_MSGS, NO_STOP_TIMER_CAR, TSS2_CAR, \
+ MIN_ACC_SPEED, PEDAL_HYST_GAP, CarControllerParams
from opendbc.can.packer import CANPacker
VisualAlert = car.CarControl.HUDControl.VisualAlert
@@ -32,8 +33,8 @@ class CarController():
self.alert_active = False
self.last_standstill = False
self.standstill_req = False
-
self.steer_rate_limited = False
+ self.use_interceptor = False
self.fake_ecus = set()
if CP.enableCamera:
@@ -49,18 +50,24 @@ class CarController():
# *** compute control surfaces ***
# gas and brake
-
- apply_gas = clip(actuators.gas, 0., 1.)
+ interceptor_gas_cmd = 0.
+ pcm_accel_cmd = actuators.gas - actuators.brake
if CS.CP.enableGasInterceptor:
- # send only negative accel if interceptor is detected. otherwise, send the regular value
- # +0.06 offset to reduce ABS pump usage when OP is engaged
- apply_accel = 0.06 - actuators.brake
- else:
- apply_accel = actuators.gas - actuators.brake
+ # handle hysteresis when around the minimum acc speed
+ if CS.out.vEgo < MIN_ACC_SPEED:
+ self.use_interceptor = True
+ elif CS.out.vEgo > MIN_ACC_SPEED + PEDAL_HYST_GAP:
+ self.use_interceptor = False
- apply_accel, self.accel_steady = accel_hysteresis(apply_accel, self.accel_steady, enabled)
- apply_accel = clip(apply_accel * CarControllerParams.ACCEL_SCALE, CarControllerParams.ACCEL_MIN, CarControllerParams.ACCEL_MAX)
+ if self.use_interceptor and enabled:
+ # only send negative accel when using interceptor. gas handles acceleration
+ # +0.06 offset to reduce ABS pump usage when OP is engaged
+ interceptor_gas_cmd = clip(actuators.gas, 0., 1.)
+ pcm_accel_cmd = 0.06 - actuators.brake
+
+ pcm_accel_cmd, self.accel_steady = accel_hysteresis(pcm_accel_cmd, self.accel_steady, enabled)
+ pcm_accel_cmd = clip(pcm_accel_cmd * CarControllerParams.ACCEL_SCALE, CarControllerParams.ACCEL_MIN, CarControllerParams.ACCEL_MAX)
# steer torque
new_steer = int(round(actuators.steer * CarControllerParams.STEER_MAX))
@@ -86,7 +93,7 @@ class CarController():
self.standstill_req = False
self.last_steer = apply_steer
- self.last_accel = apply_accel
+ self.last_accel = pcm_accel_cmd
self.last_standstill = CS.out.standstill
can_sends = []
@@ -115,14 +122,14 @@ class CarController():
if pcm_cancel_cmd and CS.CP.carFingerprint == CAR.LEXUS_IS:
can_sends.append(create_acc_cancel_command(self.packer))
elif CS.CP.openpilotLongitudinalControl:
- can_sends.append(create_accel_command(self.packer, apply_accel, pcm_cancel_cmd, self.standstill_req, lead))
+ can_sends.append(create_accel_command(self.packer, pcm_accel_cmd, pcm_cancel_cmd, self.standstill_req, lead))
else:
can_sends.append(create_accel_command(self.packer, 0, pcm_cancel_cmd, False, lead))
- if (frame % 2 == 0) and (CS.CP.enableGasInterceptor):
- # send exactly zero if apply_gas is zero. Interceptor will send the max between read value and apply_gas.
+ if frame % 2 == 0 and CS.CP.enableGasInterceptor:
+ # 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_command(self.packer, apply_gas, frame//2))
+ can_sends.append(create_gas_command(self.packer, interceptor_gas_cmd, frame // 2))
# ui mesg is at 100Hz but we send asap if:
# - there is something to display
diff --git a/selfdrive/car/toyota/carstate.py b/selfdrive/car/toyota/carstate.py
index ca2a2bcf8..1f5cae59f 100644
--- a/selfdrive/car/toyota/carstate.py
+++ b/selfdrive/car/toyota/carstate.py
@@ -10,10 +10,10 @@ from selfdrive.car.toyota.values import CAR, DBC, STEER_THRESHOLD, NO_STOP_TIMER
class CarState(CarStateBase):
def __init__(self, CP):
super().__init__(CP)
- can_define = CANDefine(DBC[CP.carFingerprint]['pt'])
- self.shifter_values = can_define.dv["GEAR_PACKET"]['GEAR']
+ can_define = CANDefine(DBC[CP.carFingerprint]["pt"])
+ self.shifter_values = can_define.dv["GEAR_PACKET"]["GEAR"]
- # On cars with cp.vl["STEER_TORQUE_SENSOR"]['STEER_ANGLE']
+ # On cars with cp.vl["STEER_TORQUE_SENSOR"]["STEER_ANGLE"]
# the signal is zeroed to where the steering angle is at start.
# Need to apply an offset as soon as the steering angle measurements are both received
self.needs_angle_offset = True
@@ -23,83 +23,82 @@ 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["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.brakePressed = cp.vl["BRAKE_MODULE"]['BRAKE_PRESSED'] != 0
- ret.brakeLights = bool(cp.vl["ESP_CONTROL"]['BRAKE_LIGHTS_ACC'] or ret.brakePressed)
+ ret.brakePressed = cp.vl["BRAKE_MODULE"]["BRAKE_PRESSED"] != 0
if self.CP.enableGasInterceptor:
- ret.gas = (cp.vl["GAS_SENSOR"]['INTERCEPTOR_GAS'] + cp.vl["GAS_SENSOR"]['INTERCEPTOR_GAS2']) / 2.
+ 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']
- ret.gasPressed = cp.vl["PCM_CRUISE"]['GAS_RELEASED'] == 0
+ ret.gas = cp.vl["GAS_PEDAL"]["GAS_PEDAL"]
+ ret.gasPressed = cp.vl["PCM_CRUISE"]["GAS_RELEASED"] == 0
- ret.wheelSpeeds.fl = cp.vl["WHEEL_SPEEDS"]['WHEEL_SPEED_FL'] * CV.KPH_TO_MS
- ret.wheelSpeeds.fr = cp.vl["WHEEL_SPEEDS"]['WHEEL_SPEED_FR'] * CV.KPH_TO_MS
- ret.wheelSpeeds.rl = cp.vl["WHEEL_SPEEDS"]['WHEEL_SPEED_RL'] * CV.KPH_TO_MS
- ret.wheelSpeeds.rr = cp.vl["WHEEL_SPEEDS"]['WHEEL_SPEED_RR'] * CV.KPH_TO_MS
+ ret.wheelSpeeds.fl = cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_FL"] * CV.KPH_TO_MS
+ ret.wheelSpeeds.fr = cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_FR"] * CV.KPH_TO_MS
+ ret.wheelSpeeds.rl = cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_RL"] * CV.KPH_TO_MS
+ ret.wheelSpeeds.rr = cp.vl["WHEEL_SPEEDS"]["WHEEL_SPEED_RR"] * CV.KPH_TO_MS
ret.vEgoRaw = mean([ret.wheelSpeeds.fl, ret.wheelSpeeds.fr, ret.wheelSpeeds.rl, ret.wheelSpeeds.rr])
ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw)
ret.standstill = ret.vEgoRaw < 0.001
# Some newer models have a more accurate angle measurement in the TORQUE_SENSOR message. Use if non-zero
- if abs(cp.vl["STEER_TORQUE_SENSOR"]['STEER_ANGLE']) > 1e-3:
+ if abs(cp.vl["STEER_TORQUE_SENSOR"]["STEER_ANGLE"]) > 1e-3:
self.accurate_steer_angle_seen = True
if self.accurate_steer_angle_seen:
- ret.steeringAngleDeg = cp.vl["STEER_TORQUE_SENSOR"]['STEER_ANGLE'] - self.angle_offset
+ ret.steeringAngleDeg = cp.vl["STEER_TORQUE_SENSOR"]["STEER_ANGLE"] - self.angle_offset
if self.needs_angle_offset:
- angle_wheel = cp.vl["STEER_ANGLE_SENSOR"]['STEER_ANGLE'] + cp.vl["STEER_ANGLE_SENSOR"]['STEER_FRACTION']
+ angle_wheel = cp.vl["STEER_ANGLE_SENSOR"]["STEER_ANGLE"] + cp.vl["STEER_ANGLE_SENSOR"]["STEER_FRACTION"]
if abs(angle_wheel) > 1e-3:
self.needs_angle_offset = False
self.angle_offset = ret.steeringAngleDeg - angle_wheel
else:
- ret.steeringAngleDeg = cp.vl["STEER_ANGLE_SENSOR"]['STEER_ANGLE'] + cp.vl["STEER_ANGLE_SENSOR"]['STEER_FRACTION']
+ ret.steeringAngleDeg = cp.vl["STEER_ANGLE_SENSOR"]["STEER_ANGLE"] + cp.vl["STEER_ANGLE_SENSOR"]["STEER_FRACTION"]
- ret.steeringRateDeg = cp.vl["STEER_ANGLE_SENSOR"]['STEER_RATE']
+ ret.steeringRateDeg = cp.vl["STEER_ANGLE_SENSOR"]["STEER_RATE"]
- can_gear = int(cp.vl["GEAR_PACKET"]['GEAR'])
+ 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["STEERING_LEVERS"]["TURN_SIGNALS"] == 1
+ ret.rightBlinker = cp.vl["STEERING_LEVERS"]["TURN_SIGNALS"] == 2
- ret.steeringTorque = cp.vl["STEER_TORQUE_SENSOR"]['STEER_TORQUE_DRIVER']
- ret.steeringTorqueEps = cp.vl["STEER_TORQUE_SENSOR"]['STEER_TORQUE_EPS']
+ ret.steeringTorque = cp.vl["STEER_TORQUE_SENSOR"]["STEER_TORQUE_DRIVER"]
+ ret.steeringTorqueEps = cp.vl["STEER_TORQUE_SENSOR"]["STEER_TORQUE_EPS"]
# 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 == CAR.LEXUS_IS:
- ret.cruiseState.available = cp.vl["DSU_CRUISE"]['MAIN_ON'] != 0
- ret.cruiseState.speed = cp.vl["DSU_CRUISE"]['SET_SPEED'] * CV.KPH_TO_MS
+ ret.cruiseState.available = cp.vl["DSU_CRUISE"]["MAIN_ON"] != 0
+ ret.cruiseState.speed = cp.vl["DSU_CRUISE"]["SET_SPEED"] * CV.KPH_TO_MS
self.low_speed_lockout = False
else:
- ret.cruiseState.available = cp.vl["PCM_CRUISE_2"]['MAIN_ON'] != 0
- ret.cruiseState.speed = cp.vl["PCM_CRUISE_2"]['SET_SPEED'] * CV.KPH_TO_MS
- self.low_speed_lockout = cp.vl["PCM_CRUISE_2"]['LOW_SPEED_LOCKOUT'] == 2
- self.pcm_acc_status = cp.vl["PCM_CRUISE"]['CRUISE_STATE']
+ ret.cruiseState.available = cp.vl["PCM_CRUISE_2"]["MAIN_ON"] != 0
+ ret.cruiseState.speed = cp.vl["PCM_CRUISE_2"]["SET_SPEED"] * CV.KPH_TO_MS
+ self.low_speed_lockout = cp.vl["PCM_CRUISE_2"]["LOW_SPEED_LOCKOUT"] == 2
+ self.pcm_acc_status = cp.vl["PCM_CRUISE"]["CRUISE_STATE"]
if self.CP.carFingerprint in NO_STOP_TIMER_CAR or self.CP.enableGasInterceptor:
# ignore standstill in hybrid vehicles, since pcm allows to restart without
# receiving any special command. Also if interceptor is detected
ret.cruiseState.standstill = False
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.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.genericToggle = bool(cp.vl["LIGHT_STALK"]['AUTO_HIGH_BEAM'])
+ 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)
- ret.espDisabled = cp.vl["ESP_CONTROL"]['TC_DISABLED'] != 0
+ ret.espDisabled = cp.vl["ESP_CONTROL"]["TC_DISABLED"] != 0
# 2 is standby, 10 is active. TODO: check that everything else is really a faulty state
- self.steer_state = cp.vl["EPS_STATUS"]['LKA_STATE']
+ self.steer_state = cp.vl["EPS_STATUS"]["LKA_STATE"]
if self.CP.enableBsm:
- ret.leftBlindspot = (cp.vl["BSM"]['L_ADJACENT'] == 1) or (cp.vl["BSM"]['L_APPROACHING'] == 1)
- ret.rightBlindspot = (cp.vl["BSM"]['R_ADJACENT'] == 1) or (cp.vl["BSM"]['R_APPROACHING'] == 1)
+ ret.leftBlindspot = (cp.vl["BSM"]["L_ADJACENT"] == 1) or (cp.vl["BSM"]["L_APPROACHING"] == 1)
+ ret.rightBlindspot = (cp.vl["BSM"]["R_ADJACENT"] == 1) or (cp.vl["BSM"]["R_APPROACHING"] == 1)
return ret
@@ -132,7 +131,6 @@ class CarState(CarStateBase):
("STEER_ANGLE", "STEER_TORQUE_SENSOR", 0),
("TURN_SIGNALS", "STEERING_LEVERS", 3), # 3 is no blinkers
("LKA_STATE", "EPS_STATUS", 0),
- ("BRAKE_LIGHTS_ACC", "ESP_CONTROL", 0),
("AUTO_HIGH_BEAM", "LIGHT_STALK", 0),
]
@@ -178,7 +176,7 @@ class CarState(CarStateBase):
("BSM", 1)
]
- return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 0)
+ return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 0)
@staticmethod
def get_cam_can_parser(CP):
@@ -194,4 +192,4 @@ class CarState(CarStateBase):
("PRE_COLLISION", 0), # TODO: figure out why freq is inconsistent
]
- return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, 2)
+ return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, 2)
diff --git a/selfdrive/car/toyota/interface.py b/selfdrive/car/toyota/interface.py
index 6a7201def..6408ad01a 100755
--- a/selfdrive/car/toyota/interface.py
+++ b/selfdrive/car/toyota/interface.py
@@ -1,7 +1,7 @@
#!/usr/bin/env python3
from cereal import car
from selfdrive.config import Conversions as CV
-from selfdrive.car.toyota.values import Ecu, CAR, TSS2_CAR, NO_DSU_CAR, CarControllerParams
+from selfdrive.car.toyota.values import Ecu, CAR, TSS2_CAR, NO_DSU_CAR, MIN_ACC_SPEED, PEDAL_HYST_GAP, CarControllerParams
from selfdrive.car import STD_CARGO_KG, scale_rot_inertia, scale_tire_stiffness, gen_empty_fingerprint
from selfdrive.swaglog import cloudlog
from selfdrive.car.interfaces import CarInterfaceBase
@@ -24,26 +24,6 @@ class CarInterface(CarInterfaceBase):
ret.steerActuatorDelay = 0.12 # Default delay, Prius has larger delay
ret.steerLimitTimer = 0.4
- # Improved longitudinal tune
- if candidate in [CAR.COROLLA_TSS2, CAR.COROLLAH_TSS2, CAR.RAV4_TSS2, CAR.RAV4H_TSS2, CAR.LEXUS_NX_TSS2]:
- ret.longitudinalTuning.deadzoneBP = [0., 8.05]
- ret.longitudinalTuning.deadzoneV = [.0, .14]
- ret.longitudinalTuning.kpBP = [0., 5., 20.]
- ret.longitudinalTuning.kpV = [1.3, 1.0, 0.7]
- ret.longitudinalTuning.kiBP = [0., 5., 12., 20., 27.]
- ret.longitudinalTuning.kiV = [.35, .23, .20, .17, .1]
- ret.stoppingBrakeRate = 0.1 # reach stopping target smoothly
- ret.startingBrakeRate = 2.0 # release brakes fast
- ret.startAccel = 1.2 # Accelerate from 0 faster
- else:
- # Default longitudinal tune
- ret.longitudinalTuning.deadzoneBP = [0., 9.]
- ret.longitudinalTuning.deadzoneV = [0., .15]
- ret.longitudinalTuning.kpBP = [0., 5., 35.]
- ret.longitudinalTuning.kiBP = [0., 35.]
- ret.longitudinalTuning.kpV = [3.6, 2.4, 1.5]
- ret.longitudinalTuning.kiV = [0.54, 0.36]
-
if candidate not in [CAR.PRIUS, CAR.RAV4, CAR.RAV4H]: # These cars use LQR/INDI
ret.lateralTuning.init('pid')
ret.lateralTuning.pid.kiBP, ret.lateralTuning.pid.kpBP = [[0.], [0.]]
@@ -176,7 +156,7 @@ class CarInterface(CarInterfaceBase):
ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.18], [0.015]] # community tuning
ret.lateralTuning.pid.kf = 0.00012 # community tuning
- elif candidate == CAR.AVALON:
+ elif candidate in [CAR.AVALON, CAR.AVALON_2019, CAR.AVALONH_2019]:
stop_and_go = False
ret.safetyParam = 73
ret.wheelbase = 2.82
@@ -335,17 +315,39 @@ class CarInterface(CarInterfaceBase):
# 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 19. * CV.MPH_TO_MS
+ 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:
- ret.gasMaxBP = [0., 9., 35]
- ret.gasMaxV = [0.2, 0.5, 0.7]
- ret.longitudinalTuning.kpV = [1.2, 0.8, 0.5]
- ret.longitudinalTuning.kiV = [0.18, 0.12]
+ # Transitions from original pedal tuning at MIN_ACC_SPEED to default tuning at MIN_ACC_SPEED + hysteresis gap
+ ret.gasMaxBP = [0., MIN_ACC_SPEED]
+ ret.gasMaxV = [0.2, 0.5]
+ ret.longitudinalTuning.kpBP = [0., 5., MIN_ACC_SPEED, MIN_ACC_SPEED + PEDAL_HYST_GAP, 35.]
+ ret.longitudinalTuning.kpV = [1.2, 0.8, 0.765, 2.255, 1.5]
+ ret.longitudinalTuning.kiBP = [0., MIN_ACC_SPEED, MIN_ACC_SPEED + PEDAL_HYST_GAP, 35.]
+ ret.longitudinalTuning.kiV = [0.18, 0.165, 0.489, 0.36]
+ elif candidate in [CAR.COROLLA_TSS2, CAR.COROLLAH_TSS2, CAR.RAV4_TSS2, CAR.RAV4H_TSS2, CAR.LEXUS_NX_TSS2]:
+ # Improved longitudinal tune
+ ret.longitudinalTuning.deadzoneBP = [0., 8.05]
+ ret.longitudinalTuning.deadzoneV = [.0, .14]
+ ret.longitudinalTuning.kpBP = [0., 5., 20.]
+ ret.longitudinalTuning.kpV = [1.3, 1.0, 0.7]
+ ret.longitudinalTuning.kiBP = [0., 5., 12., 20., 27.]
+ ret.longitudinalTuning.kiV = [.35, .23, .20, .17, .1]
+ ret.stoppingBrakeRate = 0.1 # reach stopping target smoothly
+ ret.startingBrakeRate = 2.0 # release brakes fast
+ ret.startAccel = 1.2 # Accelerate from 0 faster
+ else:
+ # Default longitudinal tune
+ ret.longitudinalTuning.deadzoneBP = [0., 9.]
+ ret.longitudinalTuning.deadzoneV = [0., .15]
+ ret.longitudinalTuning.kpBP = [0., 5., 35.]
+ ret.longitudinalTuning.kiBP = [0., 35.]
+ ret.longitudinalTuning.kpV = [3.6, 2.4, 1.5]
+ ret.longitudinalTuning.kiV = [0.54, 0.36]
return ret
diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py
index 2e3d767ff..080b70f61 100644
--- a/selfdrive/car/toyota/values.py
+++ b/selfdrive/car/toyota/values.py
@@ -1,8 +1,12 @@
# flake8: noqa
-from selfdrive.car import dbc_dict
from cereal import car
+from selfdrive.car import dbc_dict
+from selfdrive.config import Conversions as CV
+
Ecu = car.CarParams.Ecu
+MIN_ACC_SPEED = 19. * CV.MPH_TO_MS
+PEDAL_HYST_GAP = 3. * CV.MPH_TO_MS
class CarControllerParams:
ACCEL_HYST_GAP = 0.02 # don't change accel command for small oscilalitons within this value
@@ -36,8 +40,11 @@ class CAR:
HIGHLANDERH = "TOYOTA HIGHLANDER HYBRID 2018"
HIGHLANDERH_TSS2 = "TOYOTA HIGHLANDER HYBRID 2020"
AVALON = "TOYOTA AVALON 2016"
+ AVALON_2019 = "TOYOTA AVALON 2019"
+ AVALONH_2019 = "TOYOTA AVALON HYBRID 2019"
RAV4_TSS2 = "TOYOTA RAV4 2019"
COROLLA_TSS2 = "TOYOTA COROLLA TSS2 2019"
+ # LSS2 Lexus UX Hybrid is same as a TSS2 Corolla Hybrid
COROLLAH_TSS2 = "TOYOTA COROLLA HYBRID TSS2 2019"
LEXUS_ES_TSS2 = "LEXUS ES 2019"
LEXUS_ESH_TSS2 = "LEXUS ES HYBRID 2019"
@@ -112,14 +119,6 @@ FINGERPRINTS = {
CAR.COROLLA: [{
36: 8, 37: 8, 170: 8, 180: 8, 186: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 512: 6, 513: 6, 547: 8, 548: 8, 552: 4, 608: 8, 610: 5, 643: 7, 705: 8, 740: 5, 767: 4, 800: 8, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 897: 8, 900: 6, 902: 6, 905: 8, 911: 8, 916: 2, 921: 8, 933: 8, 944: 8, 945: 8, 951: 8, 955: 4, 956: 8, 979: 2, 992: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1017: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1059: 1, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1196: 8, 1227: 8, 1235: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1561: 8, 1562: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1584: 8, 1589: 8, 1592: 8, 1596: 8, 1597: 8, 1600: 8, 1664: 8, 1728: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8, 2016: 8, 2017: 8, 2018: 8, 2019: 8, 2020: 8, 2021: 8, 2022: 8, 2023: 8, 2024: 8
}],
- CAR.LEXUS_RX: [{
- # 2016 Lexus RX 350
- 36: 8, 37: 8, 114: 5, 119: 6, 120: 4, 170: 8, 180: 8, 186: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 608: 8, 610: 5, 643: 7, 705: 8, 740: 5, 742: 8, 743: 8, 767: 4, 800: 8, 810: 2, 812: 3, 818: 8, 819: 8, 820: 8, 821: 8, 822: 8, 830: 7, 835: 8, 836: 8, 845: 5, 869: 7, 870: 7, 871: 2, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1063: 8, 1077: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1349: 8, 1350: 8, 1351: 8, 1413: 8, 1414: 8, 1415: 8, 1416: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1595: 8, 1777: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8, 2015: 8, 2016: 8, 2024: 8
- },
- # 2017 Lexus RX 350
- {
- 36: 8, 37: 8, 114: 5, 119: 6, 120: 4, 170: 8, 180: 8, 186: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 608: 8, 610: 5, 643: 7, 658: 8, 705: 8, 740: 5, 742: 8, 743: 8, 767: 4, 800: 8, 810: 2, 812: 3, 814: 8, 818: 8, 819: 8, 820: 8, 821: 8, 822: 8, 830: 7, 835: 8, 836: 8, 869: 7, 870: 7, 871: 2, 898: 8, 900: 6, 902: 6, 905: 8, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1063: 8, 1077: 8, 1082: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1349: 8, 1350: 8, 1351: 8, 1413: 8, 1414: 8, 1415: 8, 1416: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1595: 8, 1777: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8
- }],
CAR.LEXUS_RXH: [{
36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 512: 6, 513: 6, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 5, 643: 7, 658: 8, 713: 8, 740: 5, 742: 8, 743: 8, 767: 4, 800: 8, 810: 2, 812: 3, 814: 8, 830: 7, 835: 8, 836: 8, 845: 5, 863: 8, 869: 7, 870: 7, 871: 2, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 6, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1005: 2, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1063: 8, 1071: 8, 1077: 8, 1082: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1595: 8, 1777: 8, 1779: 8, 1808: 8, 1810: 8, 1816: 8, 1818: 8, 1840: 8, 1848: 8, 1904: 8, 1912: 8, 1940: 8, 1941: 8, 1948: 8, 1949: 8, 1952: 8, 1956: 8, 1960: 8, 1964: 8, 1986: 8, 1990: 8, 1994: 8, 1998: 8, 2004: 8, 2012: 8
},
@@ -136,22 +135,6 @@ FINGERPRINTS = {
{
36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 5, 643: 7, 658: 8, 713: 8, 740: 5, 742: 8, 743: 8, 744: 8, 767: 4, 800: 8, 810: 2, 812: 3, 814: 8, 818: 8, 819: 8, 820: 8, 821: 8, 822: 8, 830: 7, 835: 8, 836: 8, 845: 5, 863: 8, 869: 7, 870: 7, 871: 2, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 6, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1063: 8, 1071: 8, 1077: 8, 1082: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1349: 8, 1350: 8, 1351: 8, 1413: 8, 1414: 8, 1415: 8, 1416: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1595: 8, 1745: 8, 1777: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8, 2015: 8, 2016: 8, 2024: 8
}],
- CAR.LEXUS_RX_TSS2: [
- # 2020 Lexus RX 350
- {
- 36: 8, 37: 8, 114: 5, 119: 6, 120: 4, 170: 8, 180: 8, 186: 4, 401: 8, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 608: 8, 610: 8, 643: 7, 658: 8, 705: 8, 740: 5, 742: 8, 743: 8, 764: 8, 765: 8, 767: 4, 800: 8, 810: 2, 812: 8, 814: 8, 818: 8, 824: 8, 830: 7, 835: 8, 836: 8, 865: 8, 869: 7, 870: 7, 871: 2, 877: 8, 881: 8, 891: 8, 896: 8, 898: 8, 900: 6, 902: 6, 905: 8, 918: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 976: 1, 987: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1063: 8, 1076: 8, 1077: 8, 1082: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1172: 8, 1228: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1592: 8, 1594: 8, 1595: 8, 1600: 8, 1649: 8, 1775: 8, 1777: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1808: 8, 1816: 8, 1872: 8, 1880: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8, 2015: 8, 2016: 8, 2024: 8
- }],
- CAR.LEXUS_RXH_TSS2: [
- # 2020 Lexus RX 450h
- {
- 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 401: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 643: 7, 658: 8, 713: 8, 740: 5, 742: 8, 743: 8, 744: 8, 764: 8, 765: 8, 800: 8, 810: 2, 812: 3, 814: 8, 818: 8, 822: 8, 824: 8, 830: 7, 835: 8, 836: 8, 845: 5, 863: 8, 865: 8, 869: 7, 870: 7, 871: 2, 877: 8, 881: 8, 889: 8, 891: 8, 896: 8, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 933: 8, 934: 8, 935: 8, 942: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 6, 987: 8, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1063: 8, 1071: 8, 1076: 8, 1077: 8, 1082: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1172: 8, 1228: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1592: 8, 1594: 8, 1595: 8, 1600: 8, 1649: 8, 1775: 8, 1777: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1792: 8, 1808: 8, 1809: 8, 1810: 8, 1816: 8, 1818: 8, 1840: 8, 1848: 8, 1872: 8, 1880: 8, 1904: 8, 1912: 8, 1937: 8, 1940: 8, 1941: 8, 1945: 8, 1948: 8, 1949: 8, 1952: 8, 1953: 8, 1956: 8, 1960: 8, 1961: 8, 1968: 8, 1976: 8, 1986: 8, 1990: 8, 1994: 8, 1998: 8, 2004: 8, 2012: 8, 2015: 8, 2016: 8, 2024: 8
- }],
- CAR.CHR: [{
- 36: 8, 37: 8, 170: 8, 180: 8, 186: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 608: 8, 610: 8, 614: 8, 643: 7, 658: 8, 705: 8, 740: 5, 767: 4, 800: 8, 810: 2, 812: 8, 814: 8, 830: 7, 835: 8, 836: 8, 845: 5, 869: 7, 870: 7, 871: 2, 898: 8, 913: 8, 918: 8, 921: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 976: 1, 1014: 8, 1017: 8, 1020: 8, 1021: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1082: 8, 1083: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1175: 8, 1228: 8, 1235: 8, 1237: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1595: 8, 1745: 8, 1779: 8
- }],
- CAR.CHRH: [{
- 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 614: 8, 643: 7, 658: 8, 713: 8, 740: 5, 767: 4, 800: 8, 810: 2, 812: 8, 814: 8, 829: 2, 830: 7, 835: 8, 836: 8, 845: 5, 869: 7, 870: 7, 871: 2, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 5, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1014: 8, 1017: 8, 1020: 8, 1021: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1071: 8, 1076: 8, 1077: 8, 1082: 8, 1083: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1175: 8, 1228: 8, 1235: 8, 1237: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1595: 8, 1745: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8
- }],
CAR.CAMRY: [
#XLE and LE
{
@@ -179,12 +162,6 @@ FINGERPRINTS = {
{
36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 643: 7, 658: 8, 713: 8, 728: 8, 740: 5, 761: 8, 764: 8, 767: 4, 800: 8, 810: 2, 812: 8, 814: 8, 818: 8, 824: 8, 829: 2, 830: 7, 835: 8, 836: 8, 869: 7, 870: 7, 871: 2, 888: 8, 889: 8, 898: 8, 900: 6, 902: 6, 905: 8, 918: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 5, 983: 8, 984: 8, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1011: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1071: 8, 1076: 8, 1077: 8, 1082: 8, 1084: 8, 1085: 8, 1086: 8, 1114: 8, 1132: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1228: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1595: 8, 1745: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8
}],
- CAR.CAMRY_TSS2: [{
- 36: 8, 37: 8, 114: 5, 119: 6, 120: 4, 170: 8, 180: 8, 186: 4, 401: 8, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 608: 8, 610: 8, 643: 7, 705: 8, 728: 8, 740: 5, 761: 8, 764: 8, 765: 8, 791: 8, 800: 8, 810: 2, 812: 8, 818: 8, 824: 8, 830: 7, 835: 8, 836: 8, 865: 8, 869: 7, 870: 7, 871: 2, 877: 8, 881: 8, 885: 8, 889: 8, 896: 8, 898: 8, 900: 6, 902: 6, 905: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 976: 1, 983: 8, 984: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1011: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1076: 8, 1077: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1172: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1592: 8, 1593: 8, 1594: 8, 1595: 8, 1649: 8, 1653: 8, 1654: 8, 1655: 8, 1677: 8, 1745: 8, 1775: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1792: 8, 1800: 8, 1808: 8, 1809: 8, 1816: 8, 1817: 8, 1840: 8, 1841: 8, 1848: 8, 1872: 8, 1880: 8, 1904: 8, 1912: 8, 1937: 8, 1940: 8, 1941: 8, 1945: 8, 1948: 8, 1949: 8, 1952: 8, 1953: 8, 1956: 8, 1960: 8, 1961: 8, 1964: 8, 1968: 8, 1973: 8, 1976: 8, 1981: 8, 1986: 8, 1988: 8, 1990: 8, 1994: 8, 1996: 8, 1998: 8, 2000: 8, 2001: 8, 2004: 8, 2008: 8, 2012: 8, 2016: 8, 2017: 8
- }],
- CAR.CAMRYH_TSS2: [{
- 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 401: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 643: 7, 713: 8, 728: 8, 740: 5, 761: 8, 764: 8, 765: 8, 791: 8, 800: 8, 810: 2, 812: 8, 818: 8, 824: 8, 829: 2, 830: 7, 835: 8, 836: 8, 865: 8, 869: 7, 870: 7, 871: 2, 877: 8, 881: 8, 885: 8, 889: 8, 896: 8, 898: 8, 900: 6, 902: 6, 905: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 5, 983: 8, 984: 8, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1011: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1071: 8, 1076: 8, 1077: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1172: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1592: 8, 1593: 8, 1594: 8, 1595: 8, 1649: 8, 1653: 8, 1654: 8, 1655: 8, 1677: 8, 1745: 8, 1775: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8
- }],
CAR.HIGHLANDER: [{
36: 8, 37: 8, 114: 5, 119: 6, 120: 4, 170: 8, 180: 8, 186: 4, 238: 4, 355: 5, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 545: 5, 550: 8, 552: 4, 608: 8, 610: 5, 643: 7, 705: 8, 725: 2, 740: 5, 767: 4, 800: 8, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 900: 6, 902: 6, 905: 8, 911: 8, 916: 3, 921: 8, 922: 8, 933: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 979: 2, 998: 5, 999: 7, 1000: 8, 1001: 8, 1008: 2, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1059: 1, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1182: 8, 1183: 8, 1189: 8, 1190: 8, 1191: 8, 1192: 8, 1196: 8, 1197: 8, 1198: 8, 1199: 8, 1206: 8, 1207: 8, 1212: 8, 1227: 8, 1235: 8, 1237: 8, 1279: 8, 1408: 8, 1409: 8, 1410: 8, 1552: 8, 1553: 8, 1554: 8, 1556: 8, 1557: 8, 1561: 8, 1562: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1584: 8, 1589: 8, 1592: 8, 1593: 8, 1595: 8, 1599: 8, 1656: 8, 1666: 8, 1667: 8, 1728: 8, 1745: 8, 1779: 8, 1872: 8, 1880: 8, 1904: 8, 1912: 8, 1984: 8, 1988: 8, 1992: 8, 1996: 8, 1990: 8, 1998: 8
},
@@ -200,10 +177,6 @@ FINGERPRINTS = {
{
36: 8, 37: 8, 114: 5, 119: 6, 120: 4, 170: 8, 180: 8, 186: 4, 238: 4, 355: 5, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 545: 5, 550: 8, 552: 4, 608: 8, 610: 5, 643: 7, 705: 8, 725: 2, 740: 5, 767: 4, 800: 8, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 900: 6, 902: 6, 905: 8, 911: 8, 916: 3, 918: 7, 921: 8, 922: 8, 933: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 979: 2, 998: 5, 999: 7, 1000: 8, 1001: 8, 1008: 2, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1059: 1, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1182: 8, 1183: 8, 1189: 8, 1190: 8, 1191: 8, 1192: 8, 1196: 8, 1197: 8, 1198: 8, 1199: 8, 1206: 8, 1207: 8, 1212: 8, 1227: 8, 1235: 8, 1237: 8, 1263: 8, 1279: 8, 1408: 8, 1409: 8, 1410: 8, 1552: 8, 1553: 8, 1554: 8, 1556: 8, 1557: 8, 1561: 8, 1562: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1584: 8, 1585: 8, 1589: 8, 1592: 8, 1593: 8, 1595: 8, 1599: 8, 1656: 8, 1728: 8, 1745: 8, 1779: 8, 1872: 8, 1880: 8, 1904: 8, 1912: 8, 1988: 8, 1990: 8, 1996: 8, 1998: 8, 2015: 8, 2016: 8, 2024: 8
}],
- CAR.HIGHLANDER_TSS2: [{
- # 2020 highlander limited
- 36: 8, 37: 8, 114: 5, 119: 6, 120: 4, 170: 8, 180: 8, 186: 4, 355: 5, 401: 8, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 565: 8, 608: 8, 610: 8, 643: 7, 658: 8, 705: 8, 728: 8, 740: 5, 761: 8, 764: 8, 765: 8, 767: 4, 800: 8, 810: 2, 812: 8, 814: 8, 818: 8, 824: 8, 830: 7, 835: 8, 836: 8, 865: 8, 869: 7, 870: 7, 871: 2, 877: 8, 881: 8, 885: 8, 889: 8, 896: 8, 898: 8, 900: 6, 902: 6, 905: 8, 918: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 976: 1, 987: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1063: 8, 1076: 8, 1077: 8, 1082: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1228: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1592: 8, 1594: 8, 1595: 8, 1649: 8, 1696: 8, 1775: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1808: 8, 1816: 8, 1904: 8, 1912: 8, 1952: 8, 1960: 8, 1990: 8, 1998: 8
- }],
CAR.HIGHLANDERH: [{
36: 8, 37: 8, 170: 8, 180: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 581: 5, 608: 8, 610: 5, 643: 7, 713: 8, 740: 5, 767: 4, 800: 8, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 897: 8, 900: 6, 902: 6, 905: 8, 911: 8, 916: 3, 918: 7, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 3, 955: 8, 956: 8, 979: 2, 998: 5, 999: 7, 1000: 8, 1001: 8, 1005: 2, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1059: 1, 1112: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1184: 8, 1185: 8, 1186: 8, 1189: 8, 1190: 8, 1191: 8, 1192: 8, 1196: 8, 1197: 8, 1198: 8, 1199: 8, 1206: 8, 1212: 8, 1227: 8, 1232: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1552: 8, 1553: 8, 1554: 8, 1556: 8, 1557: 8, 1561: 8, 1562: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1584: 8, 1589: 8, 1592: 8, 1593: 8, 1595: 8, 1599: 8, 1656: 8, 1728: 8, 1745: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8
},
@@ -211,9 +184,6 @@ FINGERPRINTS = {
# 2019 Highlander Hybrid Limited Platinum
36: 8, 37: 8, 170: 8, 180: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 581: 5, 608: 8, 610: 5, 643: 7, 713: 8, 740: 5, 767: 4, 800: 8, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 897: 8, 900: 6, 902: 6, 905: 8, 911: 8, 916: 3, 918: 7, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 3, 955: 8, 956: 8, 979: 2, 992: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1076: 8, 1077: 8, 1112: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1184: 8, 1185: 8, 1186: 8, 1189: 8, 1190: 8, 1191: 8, 1192: 8, 1196: 8, 1197: 8, 1198: 8, 1199: 8, 1206: 8, 1212: 8, 1227: 8, 1232: 8, 1235: 8, 1237: 8, 1263: 8, 1279: 8, 1552: 8, 1553: 8, 1554: 8, 1556: 8, 1557: 8, 1561: 8, 1562: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1584: 8, 1589: 8, 1592: 8, 1593: 8, 1595: 8, 1599: 8, 1656: 8, 1666: 8, 1667: 8, 1728: 8, 1745: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8
}],
- CAR.HIGHLANDERH_TSS2: [{
- 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 401: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 643: 7, 658: 8, 713: 8, 728: 8, 740: 5, 761: 8, 765: 8, 800: 8, 810: 2, 812: 8, 814: 8, 818: 8, 822: 8, 824: 8, 829: 2, 830: 7, 835: 8, 836: 8, 865: 8, 869: 7, 870: 7, 871: 2, 881: 8, 885: 8, 891: 8, 896: 8, 898: 8, 918: 8, 942: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 971: 7, 975: 5, 987: 8, 993: 8, 1014: 8, 1017: 8, 1020: 8, 1059: 1, 1063: 8, 1071: 8, 1082: 8, 1084: 8, 1085: 8, 1086: 8, 1114: 8, 1132: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1228: 8, 1235: 8, 1552: 8, 1553: 8, 1556: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1592: 8, 1594: 8, 1595: 8, 1649: 8, 1696: 8, 1745: 8
- }],
CAR.AVALON: [{
36: 8, 37: 8, 170: 8, 180: 8, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 547: 8, 550: 8, 552: 4, 562: 6, 608: 8, 610: 5, 643: 7, 705: 8, 740: 5, 767: 4, 800: 8, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 897: 8, 905: 8, 911: 1, 916: 2, 921: 8, 933: 6, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 979: 2, 1005: 2, 1014: 8, 1017: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1190: 8, 1191: 8, 1192: 8, 1196: 8, 1200: 8, 1201: 8, 1202: 8, 1203: 8, 1206: 8, 1227: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1552: 8, 1553: 8, 1554: 8, 1555: 8, 1556: 8, 1557: 8, 1558: 8, 1561: 8, 1562: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1584: 8, 1589: 8, 1592: 8, 1593: 8, 1595: 8, 1596: 8, 1597: 8, 1664: 8, 1728: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8
}],
@@ -226,11 +196,6 @@ FINGERPRINTS = {
{
36: 8, 37: 8, 170: 8, 180: 8, 186: 4, 401: 8, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 565: 8, 608: 8, 610: 8, 643: 7, 658: 8, 705: 8, 728: 8, 740: 5, 742: 8, 743: 8, 761: 8, 764: 8, 765: 8, 767: 4, 800: 8, 810: 2, 812: 8, 814: 8, 818: 8, 822: 8, 824: 8, 829: 2, 830: 7, 835: 8, 836: 8, 865: 8, 869: 7, 870: 7, 871: 2, 877: 8, 881: 8, 882: 8, 885: 8, 889: 8, 891: 8, 896: 8, 898: 8, 900: 6, 902: 6, 905: 8, 918: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 976: 1, 987: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1063: 8, 1076: 8, 1077: 8, 1082: 8, 1084: 8, 1085: 8, 1086: 8, 1114: 8, 1132: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1172: 8, 1228: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1592: 8, 1594: 8, 1595: 8, 1649: 8, 1696: 8, 1745: 8, 1775: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8, 2015: 8, 2016: 8, 2024: 8
}],
- CAR.COROLLA_TSS2: [
- # hatch 2019+ and sedan 2020+
- {
- 36: 8, 37: 8, 114: 5, 170: 8, 180: 8, 186: 4, 401: 8, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 608: 8, 610: 8, 643: 7, 705: 8, 728: 8, 740: 5, 742: 8, 743: 8, 761: 8, 764: 8, 765: 8, 767: 4, 800: 8, 810: 2, 812: 8, 824: 8, 829: 2, 830: 7, 835: 8, 836: 8, 865: 8, 869: 7, 870: 7, 871: 2, 877: 8, 881: 8, 896: 8, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 976: 1, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1076: 8, 1077: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1172: 8, 1235: 8, 1237: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1592: 8, 1595: 8, 1649: 8, 1745: 8, 1775: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1808: 8, 1809: 8, 1816: 8, 1817: 8, 1840: 8, 1848: 8, 1904: 8, 1912: 8, 1940: 8, 1941: 8, 1948: 8, 1949: 8, 1952: 8, 1960: 8, 1981: 8, 1986: 8, 1990: 8, 1994: 8, 1998: 8, 2004: 8
- }],
CAR.COROLLAH_TSS2: [
# 2019 Taiwan Altis Hybrid
{
@@ -241,17 +206,6 @@ FINGERPRINTS = {
36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 401: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 643: 7, 713: 8, 728: 8, 740: 5, 742: 8, 743: 8, 761: 8, 765: 8, 767: 4, 800: 8, 810: 2, 812: 8, 829: 2, 830: 7, 835: 8, 836: 8, 865: 8, 869: 7, 870: 7, 871: 2, 877: 8, 881: 8, 885: 8, 896: 8, 898: 8, 921: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 5, 993: 8, 1002: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1071: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1172: 8, 1235: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1592: 8, 1594: 8, 1595: 8, 1600: 8, 1649: 8, 1745: 8, 1775: 8, 1779: 8
}
],
- CAR.LEXUS_ES_TSS2: [{
- 36: 8, 37: 8, 114: 5, 119: 6, 120: 4, 170: 8, 180: 8, 186: 4, 401: 8, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 608: 8, 610: 8, 643: 7, 658: 8, 705: 8, 728: 8, 740: 5, 761: 8, 764: 8, 765: 8, 767: 4, 800: 8, 810: 2, 812: 8, 814: 8, 818: 8, 824: 8, 830: 7, 835: 8, 836: 8, 865: 8, 869: 7, 870: 7, 871: 2, 877: 8, 881: 8, 882: 8, 885: 8, 889: 8, 896: 8, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 976: 1, 987: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1076: 8, 1077: 8, 1082: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1172: 8, 1228: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1592: 8, 1594: 8, 1595: 8, 1649: 8, 1696: 8, 1775: 8, 1777: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8,
- }],
- CAR.LEXUS_ESH_TSS2: [
- {
- 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 401: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 643: 7, 658: 8, 713: 8, 728: 8, 740: 5, 742: 8, 743: 8, 744: 8, 761: 8, 764: 8, 765: 8, 767: 4, 800: 8, 810: 2, 812: 8, 814: 8, 818: 8, 824: 8, 829: 2, 830: 7, 835: 8, 836: 8, 863: 8, 865: 8, 869: 7, 870: 7, 871: 2, 877: 8, 881: 8, 882: 8, 885: 8, 889: 8, 896: 8, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 5, 987: 8, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1056: 8, 1057: 8, 1059: 1, 1071: 8, 1076: 8, 1077: 8, 1082: 8, 1084: 8, 1085: 8, 1086: 8, 1114: 8, 1132: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1172: 8, 1228: 8, 1235: 8, 1264: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1592: 8, 1594: 8, 1595: 8, 1649: 8, 1696: 8, 1775: 8, 1777: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8
- }],
- CAR.LEXUS_ESH: [
- {
- 36: 8, 37: 8, 170: 8, 180: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 548: 8, 552: 4, 560: 7, 581: 5, 608: 8, 610: 5, 643: 7, 710: 8, 713: 8, 740: 5, 800: 8, 832: 8, 835: 8, 836: 8, 845: 7, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 897: 8, 900: 6, 902: 6, 905: 8, 911: 8, 913: 2, 916: 2, 918: 7, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 3, 955: 8, 956: 8, 979: 2, 998: 5, 999: 7, 1000: 8, 1001: 8, 1005: 2, 1014: 8, 1017: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1059: 1, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1184: 8, 1185: 8, 1186: 8, 1189: 8, 1190: 8, 1191: 8, 1192: 8, 1196: 8, 1197: 8, 1198: 8, 1199: 8, 1206: 8, 1208: 8, 1227: 8, 1232: 8, 1235: 8, 1237: 8, 1279: 8, 1408: 8, 1409: 8, 1410: 8, 1552: 8, 1553: 8, 1554: 8, 1555: 8, 1556: 8, 1557: 8, 1561: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1584: 8, 1589: 8, 1592: 8, 1593: 8, 1595: 8, 1664: 8, 1728: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8
- }],
CAR.SIENNA: [
{
36: 8, 37: 8, 114: 5, 119: 6, 120: 4, 170: 8, 180: 8, 186: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 545: 5, 548: 8, 550: 8, 552: 4, 562: 4, 608: 8, 610: 5, 643: 7, 705: 8, 725: 2, 740: 5, 764: 8, 767: 4, 800: 8, 824: 8, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 888: 8, 896: 8, 900: 6, 902: 6, 905: 8, 911: 8, 916: 1, 918: 7, 921: 8, 933: 8, 944: 6, 945: 8, 951: 8, 955: 8, 956: 8, 979: 2, 992: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1008: 2, 1014: 8, 1017: 8, 1041: 8, 1042: 8, 1043: 8, 1056: 8, 1059: 1, 1076: 8, 1077: 8, 1114: 8, 1160: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1182: 8, 1183: 8, 1191: 8, 1192: 8, 1196: 8, 1197: 8, 1198: 8, 1199: 8, 1200: 8, 1201: 8, 1202: 8, 1203: 8, 1212: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1279: 8, 1552: 8, 1553: 8, 1555: 8, 1556: 8, 1557: 8, 1561: 8, 1562: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1584: 8, 1589: 8, 1592: 8, 1593: 8, 1595: 8, 1656: 8, 1664: 8, 1666: 8, 1667: 8, 1728: 8, 1745: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8
@@ -269,75 +223,85 @@ FINGERPRINTS = {
{
36: 8, 37: 8, 170: 8, 180: 8, 295: 8, 296: 8, 400: 6, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 581: 5, 608: 8, 610: 5, 643: 7, 713: 8, 740: 5, 767: 4, 800: 8, 836: 8, 845: 5, 849: 4, 869: 7, 870: 7, 871: 2, 896: 8, 897: 8, 900: 6, 902: 6, 905: 8, 911: 8, 913: 8, 916: 3, 918: 7, 921: 7, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 3, 955: 8, 956: 8, 979: 2, 992: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1009: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1112: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1168: 1, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1184: 8, 1185: 8, 1186: 8, 1187: 8, 1189: 8, 1190: 8, 1191: 8, 1192: 8, 1196: 8, 1197: 8, 1198: 8, 1199: 8, 1206: 8, 1208: 8, 1212: 8, 1227: 8, 1232: 8, 1235: 8, 1279: 8, 1408: 8, 1409: 8, 1410: 8, 1552: 8, 1553: 8, 1554: 8, 1555: 8, 1556: 8, 1557: 8, 1561: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1584: 8, 1589: 8, 1592: 8, 1593: 8, 1595: 8, 1599: 8, 1728: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8
}],
- CAR.RAV4H_TSS2: [
- #Hybrid Limited
- {
- 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 401: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 643: 7, 658: 8, 713: 8, 728: 8, 740: 5, 742: 8, 743: 8, 761: 8, 764: 8, 765: 8, 767: 4, 800: 8, 810: 2, 812: 8, 814: 8, 818: 8, 822: 8, 824: 8, 829: 2, 830: 7, 835: 8, 836: 8, 863: 8, 865: 8, 869: 7, 870: 7, 871: 2, 877: 8, 881: 8, 882: 8, 885: 8, 889: 8, 891: 8, 896: 8, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 5, 987: 8, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1063: 8, 1071: 8, 1076: 8, 1077: 8, 1082: 8, 1084: 8, 1085: 8, 1086: 8, 1114: 8, 1132: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1172: 8, 1228: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1592: 8, 1594: 8, 1595: 8, 1649: 8, 1696: 8, 1745: 8, 1775: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1808: 8, 1810: 8, 1816: 8, 1818: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8
- },
- ],
CAR.LEXUS_CTH: [{
36: 8, 37: 8, 170: 8, 180: 8, 288: 8, 426: 6, 452: 8, 466: 8, 467: 8, 548: 8, 552: 4, 560: 7, 581: 5, 608: 8, 610: 5, 643: 7, 713: 8, 740: 5, 800: 8, 810: 2, 832: 8, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 897: 8, 900: 6, 902: 6, 905: 8, 911: 8, 916: 1, 921: 8, 933: 8, 944: 6, 945: 8, 950: 8, 951: 8, 953: 3, 955: 4, 956: 8, 979: 2, 992: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1017: 8, 1041: 8, 1042: 8, 1043: 8, 1056: 8, 1057: 8, 1059: 1, 1076: 8, 1077: 8, 1114: 8, 1116: 8, 1160: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1184: 8, 1185: 8, 1186: 8, 1190: 8, 1191: 8, 1192: 8, 1227: 8, 1235: 8, 1279: 8, 1552: 8, 1553: 8, 1554: 8, 1555: 8, 1556: 8, 1557: 8, 1558: 8, 1561: 8, 1562: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1584: 8, 1589: 8, 1592: 8, 1593: 8, 1595: 8, 1664: 8, 1728: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8
}],
- CAR.LEXUS_NXH: [{
- 36: 8, 37: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 5, 643: 7, 713: 8, 740: 5, 742: 8, 743: 8, 764: 8, 800: 8, 810: 2, 812: 3, 818: 8, 822: 8, 824: 8, 835: 8, 836: 8, 845: 5, 849: 4, 869: 7, 870: 7, 871: 2, 889: 8, 891: 8, 896: 8, 897: 8, 900: 6, 902: 6, 905: 8, 911: 8, 913: 8, 916: 3, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 3, 955: 8, 956: 8, 979: 2, 987: 8, 992: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1006: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1043: 8, 1056: 8, 1057: 8, 1059: 1, 1076: 8, 1077: 8, 1082: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1168: 1, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1184: 8, 1185: 8, 1186: 8, 1189: 8, 1190: 8, 1191: 8, 1192: 8, 1195: 8, 1196: 8, 1197: 8, 1198: 8, 1199: 8, 1206: 8, 1208: 8, 1212: 8, 1227: 8, 1228: 8, 1232: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1408: 8, 1409: 8, 1410: 8, 1552: 8, 1553: 8, 1554: 8, 1555: 8, 1556: 8, 1557: 8, 1561: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1584: 8, 1589: 8, 1592: 8, 1593: 8, 1595: 8, 1599: 8, 1656: 8, 1728: 8, 1745: 8, 1777: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8
- }],
- CAR.LEXUS_NX: [{
- 36: 8, 37: 8, 114: 5, 119: 6, 120: 4, 170: 8, 180: 8, 186: 4, 238: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 608: 8, 610: 5, 643: 7, 658: 8, 705: 8, 725: 2, 740: 5, 764: 8, 800: 8, 810: 2, 812: 3, 818: 8, 824: 8, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 888: 8, 889: 8, 896: 8, 897: 8, 900: 6, 902: 6, 905: 8, 911: 8, 916: 3, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 979: 2, 992: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1006: 8, 1008: 2, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1059: 1, 1076: 8, 1077: 8, 1082: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1168: 1, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1182: 8, 1183: 8, 1184: 8, 1185: 8, 1186: 8, 1189: 8, 1190: 8, 1191: 8, 1192: 8, 1195: 8, 1196: 8, 1197: 8, 1198: 8, 1199: 8, 1200: 8, 1201: 8, 1202: 8, 1203: 8, 1206: 8, 1208: 8, 1212: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1408: 8, 1409: 8, 1410: 8, 1552: 8, 1553: 8, 1554: 8, 1555: 8, 1556: 8, 1557: 8, 1561: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1584: 8, 1589: 8, 1592: 8, 1593: 8, 1595: 8, 1599: 8, 1656: 8, 1666: 8, 1667: 8, 1728: 8, 1745: 8, 1777: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8
- }],
- CAR.LEXUS_NX_TSS2: [{
- 36: 8, 37: 8, 114: 5, 119: 6, 120: 4, 170: 8, 180: 8, 186: 4, 238: 4, 401: 8, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 608: 8, 610: 8, 643: 7, 658: 8, 705: 8, 725: 2, 740: 5, 742: 8, 743: 8, 764: 8, 765: 8, 800: 8, 810: 2, 812: 3, 818: 8, 822: 8, 824: 8, 835: 8, 836: 8, 849: 4, 869: 7, 870: 7, 871: 2, 877: 8, 889: 8, 891: 8, 896: 8, 897: 8, 900: 6, 902: 6, 905: 8, 911: 8, 916: 3, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 979: 2, 987: 8, 992: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1006: 8, 1008: 2, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1043: 8, 1044: 8, 1056: 8, 1059: 1, 1076: 8, 1077: 8, 1082: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1168: 1, 1172: 8, 1176: 8, 1177: 8, 1178: 8, 1179: 8, 1180: 8, 1181: 8, 1182: 8, 1183: 8, 1184: 8, 1185: 8, 1186: 8, 1189: 8, 1190: 8, 1191: 8, 1192: 8, 1195: 8, 1196: 8, 1197: 8, 1198: 8, 1199: 8, 1200: 8, 1201: 8, 1202: 8, 1203: 8, 1206: 8, 1208: 8, 1212: 8, 1228: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1408: 8, 1409: 8, 1410: 8, 1552: 8, 1553: 8, 1554: 8, 1555: 8, 1556: 8, 1557: 8, 1561: 8, 1568: 8, 1569: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1584: 8, 1585: 8, 1589: 8, 1592: 8, 1593: 8, 1595: 8, 1599: 8, 1656: 8, 1666: 8, 1667: 8, 1728: 8, 1745: 8, 1775: 8, 1777: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8
- }],
- CAR.PRIUS_TSS2: [{
- 36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 401: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 614: 8, 643: 7, 658: 8, 713: 8, 740: 5, 742: 8, 743: 8, 764: 8, 765: 8, 800: 8, 810: 2, 814: 8, 824: 8, 829: 2, 830: 7, 835: 8, 836: 8, 863: 8, 865: 8, 869: 7, 870: 7, 871: 2, 877: 8, 881: 8, 882: 8, 896: 8, 898: 8, 900: 6, 902: 6, 905: 8, 918: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 5, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1071: 8, 1076: 8, 1077: 8, 1082: 8, 1083: 8, 1084: 8, 1085: 8, 1086: 8, 1114: 8, 1132: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1172: 8, 1175: 8, 1228: 8, 1235: 8, 1237: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1592: 8, 1593: 8, 1595: 8, 1649: 8, 1653: 8, 1654: 8, 1655: 8, 1775: 8, 1777: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8
- }],
- CAR.MIRAI: [{
- 15: 8, 36: 8, 37: 8, 164: 8, 166: 8, 170: 8, 180: 8, 203: 8, 295: 8, 401: 8, 426: 6, 466: 8, 467: 8, 494: 8, 495: 8, 550: 8, 552: 4, 560: 7, 562: 8, 581: 5, 608: 8, 610: 8, 643: 7, 664: 8, 665: 8, 666: 8, 728: 8, 740: 5, 742: 8, 743: 8, 761: 8, 764: 8, 765: 8, 789: 8, 791: 8, 800: 8, 810: 2, 812: 8, 818: 8, 822: 8, 824: 8, 829: 2, 830: 7, 835: 8, 836: 8, 845: 5, 863: 8, 865: 8, 870: 7, 871: 2, 877: 8, 881: 8, 889: 8, 891: 8, 892: 8, 893: 8, 894: 8, 896: 8, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 934: 8, 935: 8, 944: 8, 945: 8, 950: 8, 951: 8, 955: 8, 956: 8, 971: 7, 983: 8, 984: 8, 987: 8, 998: 5, 1002: 8, 1011: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1071: 8, 1076: 8, 1077: 8, 1081: 8, 1082: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1172: 8, 1228: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1593: 8, 1595: 8, 1649: 8, 1653: 8, 1654: 8, 1655: 8, 1677: 8, 1745: 8, 1769: 8, 1770: 8, 1775: 8, 1777: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1792: 8, 1872: 8, 1880: 8, 1937: 8, 1945: 8, 1953: 8, 1961: 8, 1968: 8, 1976: 8, 1988: 8, 1996: 8, 2000: 8, 2001: 8, 2008: 8, 2009: 8, 2015: 8, 2016: 8, 2017: 8
- }]
}
-# Don't use theses fingerprints for fingerprinting, they are still needed for ECU detection
-IGNORED_FINGERPRINTS = [CAR.RAV4H_TSS2, CAR.HIGHLANDERH_TSS2, CAR.LEXUS_RXH_TSS2, CAR.PRIUS_TSS2,
- CAR.LEXUS_NX, CAR.LEXUS_NX_TSS2, CAR.CAMRY_TSS2, CAR.CAMRYH_TSS2, CAR.LEXUS_ESH, CAR.MIRAI]
FW_VERSIONS = {
CAR.AVALON: {
(Ecu.esp, 0x7b0, None): [
b'F152607060\x00\x00\x00\x00\x00\x00',
- b'F152607110\x00\x00\x00\x00\x00\x00',
- b'F152607140\x00\x00\x00\x00\x00\x00',
- b'F152607171\x00\x00\x00\x00\x00\x00',
- b'F152607180\x00\x00\x00\x00\x00\x00',
],
(Ecu.dsu, 0x791, None): [
b'881510701300\x00\x00\x00\x00',
- b'881510703200\x00\x00\x00\x00',
b'881510705100\x00\x00\x00\x00',
b'881510705200\x00\x00\x00\x00',
],
(Ecu.eps, 0x7a1, None): [
b'8965B41051\x00\x00\x00\x00\x00\x00',
- b'8965B41080\x00\x00\x00\x00\x00\x00',
- b'8965B41090\x00\x00\x00\x00\x00\x00',
],
(Ecu.engine, 0x7e0, None): [
b'\x0230721100\x00\x00\x00\x00\x00\x00\x00\x00A0C01000\x00\x00\x00\x00\x00\x00\x00\x00',
b'\x0230721200\x00\x00\x00\x00\x00\x00\x00\x00A0C01000\x00\x00\x00\x00\x00\x00\x00\x00',
],
- (Ecu.engine, 0x700, None): [
- b'\x01896630735100\x00\x00\x00\x00',
- b'\x01896630738000\x00\x00\x00\x00',
- ],
(Ecu.fwdRadar, 0x750, 0xf): [
b'8821F4702000\x00\x00\x00\x00',
b'8821F4702100\x00\x00\x00\x00',
- b'8821F4702300\x00\x00\x00\x00',
],
(Ecu.fwdCamera, 0x750, 0x6d): [
b'8646F0701100\x00\x00\x00\x00',
- b'8646F0702100\x00\x00\x00\x00',
b'8646F0703000\x00\x00\x00\x00',
],
},
+ CAR.AVALON_2019: {
+ (Ecu.esp, 0x7b0, None): [
+ b'F152607140\x00\x00\x00\x00\x00\x00',
+ b'F152607171\x00\x00\x00\x00\x00\x00',
+ b'F152607110\x00\x00\x00\x00\x00\x00',
+ b'F152607180\x00\x00\x00\x00\x00\x00',
+ ],
+ (Ecu.dsu, 0x791, None): [
+ b'881510703200\x00\x00\x00\x00',
+ ],
+ (Ecu.eps, 0x7a1, None): [
+ b'8965B41080\x00\x00\x00\x00\x00\x00',
+ b'8965B07010\x00\x00\x00\x00\x00\x00',
+ b'8965B41090\x00\x00\x00\x00\x00\x00',
+ ],
+ (Ecu.engine, 0x700, None): [
+ b'\x01896630735100\x00\x00\x00\x00',
+ b'\x01896630725300\x00\x00\x00\x00',
+ b'\x01896630738000\x00\x00\x00\x00',
+ ],
+ (Ecu.fwdRadar, 0x750, 0xf): [
+ b'8821F4702300\x00\x00\x00\x00',
+ ],
+ (Ecu.fwdCamera, 0x750, 0x6d): [
+ b'8646F0702100\x00\x00\x00\x00',
+ ],
+ },
+ CAR.AVALONH_2019: {
+ (Ecu.esp, 0x7b0, None): [
+ b'F152641040\x00\x00\x00\x00\x00\x00',
+ ],
+ (Ecu.dsu, 0x791, None): [
+ b'881510704200\x00\x00\x00\x00',
+ ],
+ (Ecu.eps, 0x7a1, None): [
+ b'8965B07010\x00\x00\x00\x00\x00\x00',
+ ],
+ (Ecu.engine, 0x700, None): [
+ b'\x02896630724000\x00\x00\x00\x00897CF3302002\x00\x00\x00\x00',
+ ],
+ (Ecu.fwdRadar, 0x750, 0xf): [
+ b'8821F4702300\x00\x00\x00\x00',
+ ],
+ (Ecu.fwdCamera, 0x750, 0x6d): [
+ b'8646F0702100\x00\x00\x00\x00',
+ ],
+ },
CAR.CAMRY: {
(Ecu.engine, 0x700, None): [
b'\x018966306L3100\x00\x00\x00\x00',
@@ -361,12 +325,16 @@ FW_VERSIONS = {
b'\x018966333Q6300\x00\x00\x00\x00',
b'\x018966333W6000\x00\x00\x00\x00',
],
+ (Ecu.engine, 0x7e0, None): [
+ b'\x02333P1100\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00',
+ ],
(Ecu.dsu, 0x791, None): [
b'8821F0601200 ',
b'8821F0601300 ',
b'8821F0602000 ',
b'8821F0603300 ',
b'8821F0604100 ',
+ b'8821F0605200 ',
b'8821F0607200 ',
b'8821F0608000 ',
b'8821F0608200 ',
@@ -395,6 +363,7 @@ FW_VERSIONS = {
b'8821F0602000 ',
b'8821F0603300 ',
b'8821F0604100 ',
+ b'8821F0605200 ',
b'8821F0607200 ',
b'8821F0608000 ',
b'8821F0608200 ',
@@ -405,6 +374,7 @@ FW_VERSIONS = {
b'8646F0601300 ',
b'8646F0601400 ',
b'8646F0603400 ',
+ b'8646F0604100 ',
b'8646F0605000 ',
b'8646F0606000 ',
b'8646F0606100 ',
@@ -413,6 +383,7 @@ FW_VERSIONS = {
},
CAR.CAMRYH: {
(Ecu.engine, 0x700, None): [
+ b'\x018966306Q6000\x00\x00\x00\x00',
b'\x018966333N1100\x00\x00\x00\x00',
b'\x018966333N4300\x00\x00\x00\x00',
b'\x018966333X0000\x00\x00\x00\x00',
@@ -692,6 +663,7 @@ FW_VERSIONS = {
b'\x03312M3000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00',
b'\x03312N6000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203202\x00\x00\x00\x00',
b'\x03312N6000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00',
+ b'\x03312N6000\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00',
b'\x03312N6100\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203302\x00\x00\x00\x00',
b'\x03312N6100\x00\x00\x00\x00\x00\x00\x00\x00A0202000\x00\x00\x00\x00\x00\x00\x00\x00895231203402\x00\x00\x00\x00',
],
@@ -744,6 +716,7 @@ FW_VERSIONS = {
(Ecu.engine, 0x700, None): [
b'\x01896630ZJ1000\x00\x00\x00\x00',
b'\x01896630ZU8000\x00\x00\x00\x00',
+ b'\x01896637621000\x00\x00\x00\x00',
b'\x01896637624000\x00\x00\x00\x00',
b'\x01896637626000\x00\x00\x00\x00',
b'\x02896630ZN8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00',
@@ -794,6 +767,7 @@ FW_VERSIONS = {
b'\x028646F1202000\x00\x00\x00\x008646G2601200\x00\x00\x00\x00',
b'\x028646F1202100\x00\x00\x00\x008646G2601400\x00\x00\x00\x00',
b'\x028646F4203400\x00\x00\x00\x008646G2601200\x00\x00\x00\x00',
+ b'\x028646F76020C0\x00\x00\x00\x008646G26011A0\x00\x00\x00\x00',
b'\x028646F7603100\x00\x00\x00\x008646G2601200\x00\x00\x00\x00',
],
},
@@ -840,7 +814,7 @@ FW_VERSIONS = {
},
CAR.HIGHLANDERH: {
(Ecu.eps, 0x7a1, None): [
- b'8965B48160\x00\x00\x00\x00\x00\x00'
+ b'8965B48160\x00\x00\x00\x00\x00\x00',
],
(Ecu.esp, 0x7b0, None): [
b'F152648541\x00\x00\x00\x00\x00\x00',
@@ -1442,8 +1416,9 @@ FW_VERSIONS = {
b'881517804100\x00\x00\x00\x00',
],
(Ecu.eps, 0x7a1, None): [
- b'8965B78100\x00\x00\x00\x00\x00\x00',
b'8965B78060\x00\x00\x00\x00\x00\x00',
+ b'8965B78080\x00\x00\x00\x00\x00\x00',
+ b'8965B78100\x00\x00\x00\x00\x00\x00',
],
(Ecu.fwdRadar, 0x750, 0xf): [
b'8821F4702300\x00\x00\x00\x00',
@@ -1603,6 +1578,7 @@ FW_VERSIONS = {
b'\x028966347C8000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00',
b'\x038966347C1000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4710101\x00\x00\x00\x00',
b'\x038966347C5000\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4707101\x00\x00\x00\x00',
+ b'\x038966347C5100\x00\x00\x00\x008966A4703000\x00\x00\x00\x00897CF4707101\x00\x00\x00\x00',
],
(Ecu.esp, 0x7b0, None): [
b'F152647500\x00\x00\x00\x00\x00\x00',
@@ -1650,6 +1626,8 @@ DBC = {
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.AVALON_2019: dbc_dict('toyota_nodsu_pt_generated', 'toyota_adas'),
+ CAR.AVALONH_2019: dbc_dict('toyota_nodsu_hybrid_pt_generated', 'toyota_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'),
diff --git a/selfdrive/car/volkswagen/carcontroller.py b/selfdrive/car/volkswagen/carcontroller.py
index 1317ee769..503583f66 100644
--- a/selfdrive/car/volkswagen/carcontroller.py
+++ b/selfdrive/car/volkswagen/carcontroller.py
@@ -43,7 +43,7 @@ class CarController():
# FAULT AVOIDANCE: HCA must not be enabled at standstill. Also stop
# commanding HCA if there's a fault, so the steering rack recovers.
- if enabled and not (CS.out.standstill or CS.steeringFault):
+ if enabled and not (CS.out.standstill or CS.out.steerError or CS.out.steerWarning):
# FAULT AVOIDANCE: Requested HCA torque must not exceed 3.0 Nm. This
# is inherently handled by scaling to STEER_MAX. The rack doesn't seem
diff --git a/selfdrive/car/volkswagen/carstate.py b/selfdrive/car/volkswagen/carstate.py
index 3897588f6..833cae6f7 100644
--- a/selfdrive/car/volkswagen/carstate.py
+++ b/selfdrive/car/volkswagen/carstate.py
@@ -9,20 +9,21 @@ from selfdrive.car.volkswagen.values import DBC, CANBUS, TransmissionType, GearS
class CarState(CarStateBase):
def __init__(self, CP):
super().__init__(CP)
- can_define = CANDefine(DBC[CP.carFingerprint]['pt'])
+ can_define = CANDefine(DBC[CP.carFingerprint]["pt"])
if CP.transmissionType == TransmissionType.automatic:
- self.shifter_values = can_define.dv["Getriebe_11"]['GE_Fahrstufe']
+ self.shifter_values = can_define.dv["Getriebe_11"]["GE_Fahrstufe"]
elif CP.transmissionType == TransmissionType.direct:
- self.shifter_values = can_define.dv["EV_Gearshift"]['GearPosition']
+ self.shifter_values = can_define.dv["EV_Gearshift"]["GearPosition"]
+ self.hca_status_values = can_define.dv["LH_EPS_03"]["EPS_HCA_Status"]
self.buttonStates = BUTTON_STATES.copy()
def update(self, pt_cp, cam_cp, trans_type):
ret = car.CarState.new_message()
# Update vehicle speed and acceleration from ABS wheel speeds.
- ret.wheelSpeeds.fl = pt_cp.vl["ESP_19"]['ESP_VL_Radgeschw_02'] * CV.KPH_TO_MS
- ret.wheelSpeeds.fr = pt_cp.vl["ESP_19"]['ESP_VR_Radgeschw_02'] * CV.KPH_TO_MS
- ret.wheelSpeeds.rl = pt_cp.vl["ESP_19"]['ESP_HL_Radgeschw_02'] * CV.KPH_TO_MS
- ret.wheelSpeeds.rr = pt_cp.vl["ESP_19"]['ESP_HR_Radgeschw_02'] * CV.KPH_TO_MS
+ ret.wheelSpeeds.fl = pt_cp.vl["ESP_19"]["ESP_VL_Radgeschw_02"] * CV.KPH_TO_MS
+ ret.wheelSpeeds.fr = pt_cp.vl["ESP_19"]["ESP_VR_Radgeschw_02"] * CV.KPH_TO_MS
+ ret.wheelSpeeds.rl = pt_cp.vl["ESP_19"]["ESP_HL_Radgeschw_02"] * CV.KPH_TO_MS
+ ret.wheelSpeeds.rr = pt_cp.vl["ESP_19"]["ESP_HR_Radgeschw_02"] * CV.KPH_TO_MS
ret.vEgoRaw = float(np.mean([ret.wheelSpeeds.fl, ret.wheelSpeeds.fr, ret.wheelSpeeds.rl, ret.wheelSpeeds.rr]))
ret.vEgo, ret.aEgo = self.update_speed_kf(ret.vEgoRaw)
@@ -31,37 +32,41 @@ 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.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.steeringAngleDeg = pt_cp.vl["LH_EPS_03"]["EPS_Berechneter_LW"] * (1, -1)[int(pt_cp.vl["LH_EPS_03"]["EPS_VZ_BLW"])]
+ 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
- ret.yawRate = pt_cp.vl["ESP_02"]['ESP_Gierrate'] * (1, -1)[int(pt_cp.vl["ESP_02"]['ESP_VZ_Gierrate'])] * CV.DEG_TO_RAD
+ ret.yawRate = pt_cp.vl["ESP_02"]["ESP_Gierrate"] * (1, -1)[int(pt_cp.vl["ESP_02"]["ESP_VZ_Gierrate"])] * CV.DEG_TO_RAD
+
+ # 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"]
# Update gas, brakes, and gearshift.
- ret.gas = pt_cp.vl["Motor_20"]['MO_Fahrpedalrohwert_01'] / 100.0
+ ret.gas = pt_cp.vl["Motor_20"]["MO_Fahrpedalrohwert_01"] / 100.0
ret.gasPressed = ret.gas > 0
- ret.brake = pt_cp.vl["ESP_05"]['ESP_Bremsdruck'] / 250.0 # FIXME: this is pressure in Bar, not sure what OP expects
- ret.brakePressed = bool(pt_cp.vl["ESP_05"]['ESP_Fahrer_bremst'])
- ret.brakeLights = bool(pt_cp.vl["ESP_05"]['ESP_Status_Bremsdruck'])
+ ret.brake = pt_cp.vl["ESP_05"]["ESP_Bremsdruck"] / 250.0 # FIXME: this is pressure in Bar, not sure what OP expects
+ ret.brakePressed = bool(pt_cp.vl["ESP_05"]["ESP_Fahrer_bremst"])
# Update gear and/or clutch position data.
if trans_type == TransmissionType.automatic:
- ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(pt_cp.vl["Getriebe_11"]['GE_Fahrstufe'], None))
+ ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(pt_cp.vl["Getriebe_11"]["GE_Fahrstufe"], None))
elif trans_type == TransmissionType.direct:
- ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(pt_cp.vl["EV_Gearshift"]['GearPosition'], None))
+ ret.gearShifter = self.parse_gear_shifter(self.shifter_values.get(pt_cp.vl["EV_Gearshift"]["GearPosition"], None))
elif trans_type == TransmissionType.manual:
- ret.clutchPressed = not pt_cp.vl["Motor_14"]['MO_Kuppl_schalter']
- if bool(pt_cp.vl["Gateway_72"]['BCM1_Rueckfahrlicht_Schalter']):
+ ret.clutchPressed = not pt_cp.vl["Motor_14"]["MO_Kuppl_schalter"]
+ if bool(pt_cp.vl["Gateway_72"]["BCM1_Rueckfahrlicht_Schalter"]):
ret.gearShifter = GearShifter.reverse
else:
ret.gearShifter = GearShifter.drive
# Update door and trunk/hatch lid open status.
- ret.doorOpen = any([pt_cp.vl["Gateway_72"]['ZV_FT_offen'],
- pt_cp.vl["Gateway_72"]['ZV_BT_offen'],
- pt_cp.vl["Gateway_72"]['ZV_HFS_offen'],
- pt_cp.vl["Gateway_72"]['ZV_HBFS_offen'],
- pt_cp.vl["Gateway_72"]['ZV_HD_offen']])
+ ret.doorOpen = any([pt_cp.vl["Gateway_72"]["ZV_FT_offen"],
+ pt_cp.vl["Gateway_72"]["ZV_BT_offen"],
+ pt_cp.vl["Gateway_72"]["ZV_HFS_offen"],
+ pt_cp.vl["Gateway_72"]["ZV_HBFS_offen"],
+ pt_cp.vl["Gateway_72"]["ZV_HD_offen"]])
# Update seatbelt fastened status.
ret.seatbeltUnlatched = pt_cp.vl["Airbag_02"]["AB_Gurtschloss_FA"] != 3
@@ -101,7 +106,7 @@ class CarState(CarStateBase):
ret.stockAeb = bool(pt_cp.vl["ACC_10"]["ANB_Teilbremsung_Freigabe"]) or bool(pt_cp.vl["ACC_10"]["ANB_Zielbremsung_Freigabe"])
# Update ACC radar status.
- accStatus = pt_cp.vl["TSK_06"]['TSK_Status']
+ accStatus = pt_cp.vl["TSK_06"]["TSK_Status"]
if accStatus == 2:
# ACC okay and enabled, but not currently engaged
ret.cruiseState.available = True
@@ -117,38 +122,34 @@ class CarState(CarStateBase):
# Update ACC setpoint. When the setpoint is zero or there's an error, the
# radar sends a set-speed of ~90.69 m/s / 203mph.
- ret.cruiseState.speed = pt_cp.vl["ACC_02"]['ACC_Wunschgeschw'] * CV.KPH_TO_MS
+ ret.cruiseState.speed = pt_cp.vl["ACC_02"]["ACC_Wunschgeschw"] * CV.KPH_TO_MS
if ret.cruiseState.speed > 90:
ret.cruiseState.speed = 0
# Update control button states for turn signals and ACC controls.
- self.buttonStates["accelCruise"] = bool(pt_cp.vl["GRA_ACC_01"]['GRA_Tip_Hoch'])
- self.buttonStates["decelCruise"] = bool(pt_cp.vl["GRA_ACC_01"]['GRA_Tip_Runter'])
- self.buttonStates["cancel"] = bool(pt_cp.vl["GRA_ACC_01"]['GRA_Abbrechen'])
- self.buttonStates["setCruise"] = bool(pt_cp.vl["GRA_ACC_01"]['GRA_Tip_Setzen'])
- self.buttonStates["resumeCruise"] = bool(pt_cp.vl["GRA_ACC_01"]['GRA_Tip_Wiederaufnahme'])
- self.buttonStates["gapAdjustCruise"] = bool(pt_cp.vl["GRA_ACC_01"]['GRA_Verstellung_Zeitluecke'])
- ret.leftBlinker = bool(pt_cp.vl["Gateway_72"]['BH_Blinker_li'])
- ret.rightBlinker = bool(pt_cp.vl["Gateway_72"]['BH_Blinker_re'])
+ self.buttonStates["accelCruise"] = bool(pt_cp.vl["GRA_ACC_01"]["GRA_Tip_Hoch"])
+ self.buttonStates["decelCruise"] = bool(pt_cp.vl["GRA_ACC_01"]["GRA_Tip_Runter"])
+ self.buttonStates["cancel"] = bool(pt_cp.vl["GRA_ACC_01"]["GRA_Abbrechen"])
+ self.buttonStates["setCruise"] = bool(pt_cp.vl["GRA_ACC_01"]["GRA_Tip_Setzen"])
+ self.buttonStates["resumeCruise"] = bool(pt_cp.vl["GRA_ACC_01"]["GRA_Tip_Wiederaufnahme"])
+ self.buttonStates["gapAdjustCruise"] = bool(pt_cp.vl["GRA_ACC_01"]["GRA_Verstellung_Zeitluecke"])
+ ret.leftBlinker = bool(pt_cp.vl["Gateway_72"]["BH_Blinker_li"])
+ ret.rightBlinker = bool(pt_cp.vl["Gateway_72"]["BH_Blinker_re"])
# Read ACC hardware button type configuration info that has to pass thru
# to the radar. Ends up being different for steering wheel buttons vs
# third stalk type controls.
- self.graHauptschalter = pt_cp.vl["GRA_ACC_01"]['GRA_Hauptschalter']
- self.graTypHauptschalter = pt_cp.vl["GRA_ACC_01"]['GRA_Typ_Hauptschalter']
- self.graButtonTypeInfo = pt_cp.vl["GRA_ACC_01"]['GRA_ButtonTypeInfo']
- self.graTipStufe2 = pt_cp.vl["GRA_ACC_01"]['GRA_Tip_Stufe_2']
+ self.graHauptschalter = pt_cp.vl["GRA_ACC_01"]["GRA_Hauptschalter"]
+ self.graTypHauptschalter = pt_cp.vl["GRA_ACC_01"]["GRA_Typ_Hauptschalter"]
+ self.graButtonTypeInfo = pt_cp.vl["GRA_ACC_01"]["GRA_ButtonTypeInfo"]
+ self.graTipStufe2 = pt_cp.vl["GRA_ACC_01"]["GRA_Tip_Stufe_2"]
# Pick up the GRA_ACC_01 CAN message counter so we can sync to it for
# later cruise-control button spamming.
- self.graMsgBusCounter = pt_cp.vl["GRA_ACC_01"]['COUNTER']
-
- # Check to make sure the electric power steering rack is configured to
- # accept and respond to HCA_01 messages and has not encountered a fault.
- self.steeringFault = not pt_cp.vl["LH_EPS_03"]["EPS_HCA_Status"]
+ self.graMsgBusCounter = pt_cp.vl["GRA_ACC_01"]["COUNTER"]
# Additional safety checks performed in CarInterface.
- self.parkingBrakeSet = bool(pt_cp.vl["Kombi_01"]['KBI_Handbremse']) # FIXME: need to include an EPB check as well
- ret.espDisabled = pt_cp.vl["ESP_21"]['ESP_Tastung_passiv'] != 0
+ self.parkingBrakeSet = bool(pt_cp.vl["Kombi_01"]["KBI_Handbremse"]) # FIXME: need to include an EPB check as well
+ ret.espDisabled = pt_cp.vl["ESP_21"]["ESP_Tastung_passiv"] != 0
return ret
@@ -177,22 +178,16 @@ class CarState(CarStateBase):
("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_Status_Bremsdruck", "ESP_05", 0), # Brakes applied
("ESP_Bremsdruck", "ESP_05", 0), # Brake pressure applied
("MO_Fahrpedalrohwert_01", "Motor_20", 0), # Accelerator pedal value
("MO_Kuppl_schalter", "Motor_14", 0), # Clutch switch
("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", 0), # Steering rack HCA support configured
+ ("EPS_HCA_Status", "LH_EPS_03", 3), # EPS HCA control status
("ESP_Tastung_passiv", "ESP_21", 0), # Stability control disabled
("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
- ("TSK_Fahrzeugmasse_02", "Motor_16", 0), # Estimated vehicle mass from drivetrain coordinator
- ("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
("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
@@ -213,31 +208,17 @@ class CarState(CarStateBase):
("ESP_19", 100), # From J104 ABS/ESP controller
("ESP_05", 50), # From J104 ABS/ESP controller
("ESP_21", 50), # From J104 ABS/ESP controller
- ("ACC_10", 50), # From J428 ACC radar control module
("Motor_20", 50), # From J623 Engine control module
("TSK_06", 50), # From J623 Engine control module
- ("ESP_02", 50),
- ("GRA_ACC_01", 33), # From J??? steering wheel control buttons
- ("ACC_02", 17), # From J428 ACC radar control module
+ ("ESP_02", 50), # From J104 ABS/ESP controller
+ ("GRA_ACC_01", 33), # From J533 CAN gateway (via LIN from steering wheel controls)
("Gateway_72", 10), # From J533 CAN gateway (aggregated data)
("Motor_14", 10), # From J623 Engine control module
("Airbag_02", 5), # From J234 Airbag control module
("Kombi_01", 2), # From J285 Instrument cluster
- ("Motor_16", 2), # From J623 Engine control module
("Einheiten_01", 1), # From J??? not known if gateway, cluster, or BCM
]
- if CP.enableBsm:
- 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
- ]
- checks += [
- ("SWA_01", 20),
- ]
-
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
@@ -249,7 +230,15 @@ class CarState(CarStateBase):
("BCM1_Rueckfahrlicht_Schalter", "Gateway_72", 0)] # Reverse light from BCM
checks += [("Motor_14", 10)] # From J623 Engine control module
- return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, CANBUS.pt)
+ # TODO: Detect ACC radar bus location
+ signals += MqbExtraSignals.fwd_radar_signals
+ checks += MqbExtraSignals.fwd_radar_checks
+ # TODO: Detect BSM radar bus location
+ if CP.enableBsm:
+ signals += MqbExtraSignals.bsm_radar_signals
+ checks += MqbExtraSignals.bsm_radar_checks
+
+ return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, CANBUS.pt)
@staticmethod
def get_cam_can_parser(CP):
@@ -268,4 +257,26 @@ class CarState(CarStateBase):
("LDW_02", 10) # From R242 Driver assistance camera
]
- return CANParser(DBC[CP.carFingerprint]['pt'], signals, checks, CANBUS.cam)
+ return CANParser(DBC[CP.carFingerprint]["pt"], signals, checks, CANBUS.cam)
+
+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
+ ]
+ 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
+ ]
+ 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 787899359..55401af0f 100644
--- a/selfdrive/car/volkswagen/interface.py
+++ b/selfdrive/car/volkswagen/interface.py
@@ -87,16 +87,31 @@ class CarInterface(CarInterfaceBase):
ret.mass = 1335 + STD_CARGO_KG
ret.wheelbase = 2.61
+ elif candidate == CAR.AUDI_Q2_MK1:
+ # Averages of all GA Q2 variants
+ ret.mass = 1205 + STD_CARGO_KG
+ ret.wheelbase = 2.61
+
elif candidate == CAR.SEAT_ATECA_MK1:
# Averages of all 5F Ateca variants
ret.mass = 1900 + STD_CARGO_KG
ret.wheelbase = 2.64
+ elif candidate == CAR.SEAT_LEON_MK3:
+ # Averages of all 5F Leon variants
+ ret.mass = 1227 + STD_CARGO_KG
+ ret.wheelbase = 2.64
+
elif candidate == CAR.SKODA_KODIAQ_MK1:
# Averages of all 5N Kodiaq variants
ret.mass = 1569 + STD_CARGO_KG
ret.wheelbase = 2.79
+ elif candidate == CAR.SKODA_OCTAVIA_MK3:
+ # Averages of all 5E/NE Octavia variants
+ ret.mass = 1388 + STD_CARGO_KG
+ ret.wheelbase = 2.68
+
elif candidate == CAR.SKODA_SCALA_MK1:
# Averages of all NW Scala variants
ret.mass = 1192 + STD_CARGO_KG
@@ -152,13 +167,11 @@ class CarInterface(CarInterfaceBase):
be.pressed = self.CS.buttonStates[button]
buttonEvents.append(be)
- events = self.create_common_events(ret, extra_gears=[GearShifter.eco, GearShifter.sport])
+ events = self.create_common_events(ret, extra_gears=[GearShifter.eco, GearShifter.sport, GearShifter.manumatic])
# Vehicle health and operation safety checks
if self.CS.parkingBrakeSet:
events.add(EventName.parkBrake)
- if self.CS.steeringFault:
- events.add(EventName.steerTempUnavailable)
ret.events = events.to_msg()
ret.buttonEvents = buttonEvents
diff --git a/selfdrive/car/volkswagen/values.py b/selfdrive/car/volkswagen/values.py
index ec2d879fa..fcbf56ac1 100644
--- a/selfdrive/car/volkswagen/values.py
+++ b/selfdrive/car/volkswagen/values.py
@@ -53,6 +53,7 @@ MQB_LDW_MESSAGES = {
# Check the 7th and 8th characters of the VIN before adding a new CAR. If the
# chassis code is already listed below, don't add a new CAR, just add to the
# FW_VERSIONS for that existing CAR.
+# Exception: SEAT Leon and SEAT Ateca share a chassis code
class CAR:
ATLAS_MK1 = "VOLKSWAGEN ATLAS 1ST GEN" # Chassis CA, Mk1 VW Atlas and Atlas Cross Sport
@@ -61,64 +62,36 @@ class CAR:
PASSAT_MK8 = "VOLKSWAGEN PASSAT 8TH GEN" # Chassis 3G, Mk8 Passat and variants
TIGUAN_MK2 = "VOLKSWAGEN TIGUAN 2ND GEN" # Chassis AD/BW, Mk2 VW Tiguan and variants
AUDI_A3_MK3 = "AUDI A3 3RD GEN" # Chassis 8V/FF, Mk3 Audi A3 and variants
+ AUDI_Q2_MK1 = "AUDI Q2 1ST GEN" # Chassis GA, Mk1 Audi Q2 (RoW) and Q2L (China only)
SEAT_ATECA_MK1 = "SEAT ATECA 1ST GEN" # Chassis 5F, Mk1 SEAT Ateca and CUPRA Ateca
+ SEAT_LEON_MK3 = "SEAT LEON 3RD GEN" # Chassis 5F, Mk3 SEAT Leon and variants
SKODA_KODIAQ_MK1 = "SKODA KODIAQ 1ST GEN" # Chassis NS, Mk1 Skoda Kodiaq
SKODA_SCALA_MK1 = "SKODA SCALA 1ST GEN" # Chassis NW, Mk1 Skoda Scala and Skoda Kamiq
SKODA_SUPERB_MK3 = "SKODA SUPERB 3RD GEN" # Chassis 3V/NP, Mk3 Skoda Superb and variants
-
-FINGERPRINTS = {
- CAR.ATLAS_MK1: [{
- 64: 8, 134: 8, 159: 8, 173: 8, 178: 8, 253: 8, 257: 8, 260: 8, 262: 8, 278: 8, 279: 8, 283: 8, 286: 8, 288: 8, 289: 8, 290: 8, 294: 8, 299: 8, 302: 8, 346: 8, 418: 8, 427: 8, 679: 8, 681: 8, 695: 8, 779: 8, 780: 8, 783: 8, 792: 8, 795: 8, 804: 8, 806: 8, 807: 8, 808: 8, 809: 8, 870: 8, 896: 8, 897: 8, 898: 8, 901: 8, 917: 8, 919: 8, 927: 8, 949: 8, 958: 8, 960: 4, 981: 8, 987: 8, 988: 8, 991: 8, 997: 8, 1000: 8, 1019: 8, 1122: 8, 1123: 8, 1124: 8, 1153: 8, 1156: 8, 1157: 8, 1158: 8, 1162: 8, 1175: 8, 1312: 8, 1385: 8, 1413: 8, 1440: 5, 1471: 4, 1514: 8, 1515: 8, 1520: 8, 1600: 8, 1601: 8, 1603: 8, 1605: 8, 1624: 8, 1626: 8, 1629: 8, 1631: 8, 1635: 8, 1646: 8, 1648: 8, 1712: 6, 1714: 8, 1716: 8, 1717: 8, 1719: 8, 1720: 8, 1721: 8, 1792: 8, 1872: 8, 1879: 8, 1976: 8, 1977: 8, 1985: 8, 2015: 8
- }],
- CAR.GOLF_MK7: [{
- 64: 8, 134: 8, 159: 8, 173: 8, 178: 8, 253: 8, 257: 8, 260: 8, 262: 8, 264: 8, 278: 8, 279: 8, 283: 8, 286: 8, 288: 8, 289: 8, 290: 8, 294: 8, 299: 8, 302: 8, 346: 8, 385: 8, 418: 8, 427: 8, 668: 8, 679: 8, 681: 8, 695: 8, 779: 8, 780: 8, 783: 8, 792: 8, 795: 8, 804: 8, 806: 8, 807: 8, 808: 8, 809: 8, 870: 8, 896: 8, 897: 8, 898: 8, 901: 8, 917: 8, 919: 8, 927: 8, 949: 8, 958: 8, 960: 4, 981: 8, 987: 8, 988: 8, 991: 8, 997: 8, 1000: 8, 1019: 8, 1120: 8, 1122: 8, 1123: 8, 1124: 8, 1153: 8, 1162: 8, 1175: 8, 1312: 8, 1385: 8, 1413: 8, 1440: 5, 1514: 8, 1515: 8, 1520: 8, 1529: 8, 1600: 8, 1601: 8, 1603: 8, 1605: 8, 1624: 8, 1626: 8, 1629: 8, 1631: 8, 1646: 8, 1648: 8, 1712: 6, 1714: 8, 1716: 8, 1717: 8, 1719: 8, 1720: 8, 1721: 8
- }],
- CAR.JETTA_MK7: [{
- 64: 8, 134: 8, 159: 8, 173: 8, 178: 8, 253: 8, 257: 8, 260: 8, 262: 8, 264: 8, 278: 8, 279: 8, 283: 8, 286: 8, 288: 8, 289: 8, 290: 8, 294: 8, 299: 8, 302: 8, 346: 8, 376: 8, 418: 8, 427: 8, 679: 8, 681: 8, 695: 8, 779: 8, 780: 8, 783: 8, 792: 8, 795: 8, 804: 8, 806: 8, 807: 8, 808: 8, 809: 8, 828: 8, 870: 8, 879: 8, 884: 8, 888: 8, 891: 8, 901: 8, 913: 8, 919: 8, 949: 8, 958: 8, 960: 4, 981: 8, 987: 8, 988: 8, 991: 8, 997: 8, 1000: 8, 1019: 8, 1122: 8, 1123: 8, 1124: 8, 1153: 8, 1156: 8, 1157: 8, 1158: 8, 1162: 8, 1312: 8, 1343: 8, 1385: 8, 1413: 8, 1440: 5, 1471: 4, 1514: 8, 1515: 8, 1520: 8, 1600: 8, 1601: 8, 1603: 8, 1605: 8, 1624: 8, 1626: 8, 1629: 8, 1631: 8, 1635: 8, 1646: 8, 1648: 8, 1712: 6, 1714: 8, 1716: 8, 1717: 8, 1719: 8, 1720: 8
- }],
- CAR.PASSAT_MK8: [{
- 64: 8, 134: 8, 159: 8, 173: 8, 178: 8, 253: 8, 257: 8, 260: 8, 262: 8, 264: 8, 278: 8, 279: 8, 283: 8, 286: 8, 288: 8, 289: 8, 290: 8, 294: 8, 295: 8, 299: 8, 302: 8, 346: 8, 385: 8, 391: 8, 427: 8, 668: 8, 679: 8, 681: 8, 695: 8, 779: 8, 780: 8, 783: 8, 787: 8, 788: 8, 789: 8, 791: 8, 792: 8, 799: 8, 802: 8, 804: 8, 806: 8, 807: 8, 808: 8, 809: 8, 828: 8, 838: 8, 839: 8, 840: 8, 841: 8, 842: 8, 843: 8, 844: 8, 845: 8, 870: 8, 896: 8, 897: 8, 898: 8, 901: 8, 917: 8, 919: 8, 927: 8, 949: 8, 958: 8, 960: 4, 981: 8, 987: 8, 988: 8, 991: 8, 997: 8, 1000: 8, 1019: 8, 1120: 8, 1122: 8, 1123: 8, 1124: 8, 1153: 8, 1162: 8, 1175: 8, 1312: 8, 1385: 8, 1413: 8, 1438: 8, 1440: 5, 1461: 8, 1514: 8, 1515: 8, 1520: 8, 1529: 8, 1600: 8, 1601: 8, 1603: 8, 1624: 8, 1629: 8, 1631: 8, 1646: 8, 1648: 8, 1712: 6, 1714: 8, 1716: 8, 1717: 8, 1719: 8, 1720: 8, 1721: 8
- }],
- CAR.TIGUAN_MK2: [{
- 64: 8, 134: 8, 159: 8, 173: 8, 178: 8, 253: 8, 257: 8, 260: 8, 262: 8, 278: 8, 279: 8, 283: 8, 286: 8, 288: 8, 289: 8, 290: 8, 294: 8, 299: 8, 302: 8, 346: 8, 376: 8, 418: 8, 427: 8, 573: 8, 679: 8, 681: 8, 684: 8, 695: 8, 779: 8, 780: 8, 783: 8, 787: 8, 788: 8, 789: 8, 792: 8, 795: 8, 804: 8, 806: 8, 807: 8, 808: 8, 809: 8, 828: 8, 870: 8, 879: 8, 884: 8, 888: 8, 891: 8, 896: 8, 897: 8, 898: 8, 901: 8, 913: 8, 917: 8, 919: 8, 949: 8, 958: 8, 960: 4, 981: 8, 987: 8, 988: 8, 991: 8, 997: 8, 1000: 8, 1019: 8, 1122: 8, 1123: 8, 1124: 8, 1153: 8, 1156: 8, 1157: 8, 1158: 8, 1162: 8, 1175: 8, 1312: 8, 1343: 8, 1385: 8, 1413: 8, 1440: 5, 1471: 4, 1514: 8, 1515: 8, 1520: 8, 1600: 8, 1601: 8, 1603: 8, 1605: 8, 1624: 8, 1626: 8, 1629: 8, 1631: 8, 1635: 8, 1646: 8, 1648: 8, 1712: 6, 1714: 8, 1716: 8, 1717: 8, 1719: 8, 1720: 8, 1721: 8
- }],
- CAR.AUDI_A3_MK3: [{
- 64: 8, 134: 8, 159: 8, 173: 8, 178: 8, 253: 8, 257: 8, 260: 8, 262: 8, 278: 8, 279: 8, 283: 8, 285: 8, 286: 8, 288: 8, 289: 8, 290: 8, 294: 8, 295: 8, 299: 8, 302: 8, 346: 8, 418: 8, 427: 8, 506: 8, 679: 8, 681: 8, 695: 8, 779: 8, 780: 8, 783: 8, 787: 8, 788: 8, 789: 8, 792: 8, 802: 8, 804: 8, 806: 8, 807: 8, 808: 8, 809: 8, 846: 8, 847: 8, 870: 8, 896: 8, 897: 8, 898: 8, 901: 8, 917: 8, 919: 8, 949: 8, 958: 8, 960: 4, 981: 8, 987: 8, 988: 8, 991: 8, 997: 8, 1000: 8, 1019: 8, 1122: 8, 1123: 8, 1124: 8, 1153: 8, 1162: 8, 1175: 8, 1312: 8, 1385: 8, 1413: 8, 1440: 5, 1514: 8, 1515: 8, 1520: 8, 1600: 8, 1601: 8, 1603: 8, 1624: 8, 1629: 8, 1631: 8, 1646: 8, 1648: 8, 1712: 6, 1714: 8, 1716: 8, 1717: 8, 1719: 8, 1720: 8, 1721: 8, 1792: 8, 1872: 8, 1976: 8, 1977: 8, 1982: 8, 1985: 8
- }],
- CAR.SEAT_ATECA_MK1: [{
- 64: 8, 134: 8, 159: 8, 173: 8, 178: 8, 253: 8, 257: 8, 260: 8, 262: 8, 278: 8, 279: 8, 283: 8, 286: 8, 288: 8, 289: 8, 290: 8, 294: 8, 299: 8, 302: 8, 346: 8, 385: 8, 418: 8, 427: 8, 668: 8, 679: 8, 681: 8, 684: 8, 779: 8, 780: 8, 792: 8, 795: 8, 804: 8, 806: 8, 807: 8, 808: 8, 809: 8, 870: 8, 901: 8, 917: 8, 919: 8, 927: 8, 949: 8, 958: 8, 960: 4, 981: 8, 987: 8, 988: 8, 991: 8, 997: 8, 1000: 8, 1019: 8, 1120: 8, 1122: 8, 1123: 8, 1124: 8, 1153: 8, 1162: 8, 1175: 8, 1312: 8, 1385: 8, 1413: 8, 1440: 5, 1514: 8, 1515: 8, 1520: 8, 1600: 8, 1601: 8, 1603: 8, 1605: 8, 1624: 8, 1626: 8, 1629: 8, 1631: 8, 1646: 8, 1648: 8, 1712: 6, 1714: 8, 1716: 8, 1717: 8, 1719: 8, 1720: 8, 1721: 8
- }],
- CAR.SKODA_KODIAQ_MK1: [{
- 64: 8, 134: 8, 159: 8, 173: 8, 178: 8, 253: 8, 257: 8, 260: 8, 262: 8, 278: 8, 279: 8, 283: 8, 286: 8, 288: 8, 289: 8, 290: 8, 294: 8, 299: 8, 302: 8, 346: 8, 385: 8, 418: 8, 427: 8, 573: 8, 668: 8, 679: 8, 681: 8, 684: 8, 695: 8, 779: 8, 780: 8, 783: 8, 787: 8, 788: 8, 789: 8, 792: 8, 795: 8, 802: 8, 804: 8, 806: 8, 807: 8, 808: 8, 809: 8, 828: 8, 870: 8, 896: 8, 897: 8, 898: 8, 901: 8, 917: 8, 919: 8, 949: 8, 958: 8, 960: 4, 981: 8, 987: 8, 988: 8, 991: 8, 997: 8, 1000: 8, 1019: 8, 1120: 8, 1153: 8, 1162: 8, 1175: 8, 1312: 8, 1385: 8, 1413: 8, 1440: 5, 1514: 8, 1515: 8, 1520: 8, 1529: 8, 1600: 8, 1601: 8, 1603: 8, 1605: 8, 1624: 8, 1626: 8, 1629: 8, 1631: 8, 1646: 8, 1648: 8, 1712: 6, 1714: 8, 1716: 8, 1717: 8, 1719: 8, 1720: 8, 1721: 8, 1792: 8, 1871: 8, 1872: 8, 1879: 8, 1909: 8, 1976: 8, 1977: 8, 1985: 8
- }],
- CAR.SKODA_SCALA_MK1: [{
- 64: 8, 134: 8, 159: 8, 173: 8, 178: 8, 253: 8, 257: 8, 262: 8, 278: 8, 279: 8, 283: 8, 286: 8, 288: 8, 289: 8, 290: 8, 294: 8, 299: 8, 302: 8, 346: 8, 418: 8, 427: 8, 506: 8, 568: 8, 569: 8, 572: 8, 573: 8, 679: 8, 681: 8, 684: 8, 695: 8, 779: 8, 780: 8, 783: 8, 787: 8, 788: 8, 789: 8, 792: 8, 795: 8, 804: 8, 806: 8, 807: 8, 808: 8, 809: 8, 826: 8, 827: 8, 828: 8, 870: 8, 879: 8, 884: 8, 888: 8, 891: 8, 901: 8, 913: 8, 917: 8, 919: 8, 949: 8, 958: 8, 960: 4, 981: 8, 987: 8, 988: 8, 991: 8, 997: 8, 1000: 8, 1019: 8, 1122: 8, 1123: 8, 1124: 8, 1153: 8, 1156: 8, 1157: 8, 1158: 8, 1162: 8, 1175: 8, 1312: 8, 1343: 8, 1385: 8, 1413: 8, 1440: 5, 1514: 8, 1515: 8, 1520: 8, 1600: 8, 1601: 8, 1603: 8, 1605: 8, 1624: 8, 1626: 8, 1629: 8, 1631: 8, 1635: 8, 1646: 8, 1648: 8, 1712: 6, 1714: 8, 1716: 8, 1717: 8, 1719: 8, 1720: 8, 1721: 8, 1792: 8, 1872: 8, 1879: 8, 1976: 8, 1977: 8, 1982: 8, 1985: 8
- }],
- CAR.SKODA_SUPERB_MK3: [{
- 64: 8, 134: 8, 159: 8, 178: 8, 253: 8, 257: 8, 260: 8, 262: 8, 278: 8, 279: 8, 283: 8, 286: 8, 288: 8, 289: 8, 290: 8, 294: 8, 295: 8, 299: 8, 302: 8, 346: 8, 418: 8, 427: 8, 679: 8, 681: 8, 695: 8, 779: 8, 780: 8, 783: 8, 791: 8, 792: 8, 795: 8, 799: 8, 804: 8, 806: 8, 807: 8, 808: 8, 809: 8, 838: 8, 839: 8, 840: 8, 841: 8, 842: 8, 843: 8, 844: 8, 845: 8, 870: 8, 896: 8, 897: 8, 898: 8, 901: 8, 917: 8, 919: 8, 949: 8, 958: 8, 960: 4, 981: 8, 987: 8, 988: 8, 991: 8, 997: 8, 1000: 8, 1019: 8, 1153: 8, 1162: 8, 1175: 8, 1312: 8, 1385: 8, 1413: 8, 1440: 5, 1514: 8, 1515: 8, 1520: 8, 1600: 8, 1601: 8, 1603: 8, 1624: 8, 1626: 8, 1629: 8, 1631: 8, 1646: 8, 1648: 8, 1712: 6, 1714: 8, 1716: 8, 1717: 8, 1719: 8, 1720: 8, 1792: 8, 1872: 8, 1879: 8, 1976: 8, 1977: 8, 1985: 8, 2017: 8
- }],
-}
-
-# All VW should be here
-IGNORED_FINGERPRINTS = [CAR.ATLAS_MK1, CAR.GOLF_MK7, CAR.JETTA_MK7, CAR.PASSAT_MK8,
- CAR.TIGUAN_MK2, CAR.AUDI_A3_MK3, CAR.SEAT_ATECA_MK1,
- CAR.SKODA_KODIAQ_MK1, CAR.SKODA_SCALA_MK1, CAR.SKODA_SUPERB_MK3 ]
+ SKODA_OCTAVIA_MK3 = "SKODA OCTAVIA 3RD GEN" # Chassis NE, Mk3 Skoda Octavia and variants
FW_VERSIONS = {
CAR.ATLAS_MK1: {
(Ecu.engine, 0x7e0, None): [
b'\xf1\x8703H906026AA\xf1\x899970',
+ b'\xf1\x8703H906026F \xf1\x896696',
+ b'\xf1\x8703H906026F \xf1\x899970',
],
(Ecu.transmission, 0x7e1, None): [
+ b'\xf1\x8709G927158A \xf1\x893387',
b'\xf1\x8709G927158DR\xf1\x893536',
],
(Ecu.srs, 0x715, None): [
+ b'\xf1\x873Q0959655BC\xf1\x890503\xf1\x82\0161914151912001103111122031200',
b'\xf1\x873Q0959655BN\xf1\x890713\xf1\x82\0162214152212001105141122052900',
],
(Ecu.eps, 0x712, None): [
b'\xf1\x873QF909144B \xf1\x891582\xf1\x82\00571B60924A1',
+ b'\xf1\x875Q0909143P \xf1\x892051\xf1\x820528B6090105',
],
(Ecu.fwdRadar, 0x757, None): [
+ b'\xf1\x875Q0907572H \xf1\x890620',
+ b'\xf1\x875Q0907572J \xf1\x890654',
b'\xf1\x875Q0907572P \xf1\x890682',
],
},
@@ -128,7 +101,9 @@ FW_VERSIONS = {
b'\xf1\x8704E906016AD\xf1\x895758',
b'\xf1\x8704E906023AG\xf1\x891726',
b'\xf1\x8704E906023BN\xf1\x894518',
+ b'\xf1\x8704E906024K \xf1\x896811',
b'\xf1\x8704E906027GR\xf1\x892394',
+ b'\xf1\x8704E906027MA\xf1\x894958',
b'\xf1\x8704L906026NF\xf1\x899528',
b'\xf1\x8704L906056CR\xf1\x895813',
b'\xf1\x8704L906056HE\xf1\x893758',
@@ -142,6 +117,7 @@ FW_VERSIONS = {
b'\xf1\x875G0906259Q \xf1\x890002',
b'\xf1\x875G0906259Q \xf1\x892313',
b'\xf1\x878V0906259J \xf1\x890003',
+ b'\xf1\x878V0906259K \xf1\x890001',
b'\xf1\x878V0906259P \xf1\x890001',
b'\xf1\x878V0906259Q \xf1\x890002',
b'\xf1\x878V0906264F \xf1\x890003',
@@ -150,11 +126,14 @@ FW_VERSIONS = {
],
(Ecu.transmission, 0x7e1, None): [
b'\xf1\x8709G927749AP\xf1\x892943',
+ b'\xf1\x8709S927158A \xf1\x893585',
+ b'\xf1\x870CW300041H \xf1\x891010',
b'\xf1\x870CW300042F \xf1\x891604',
b'\xf1\x870CW300045 \xf1\x894531',
b'\xf1\x870CW300047D \xf1\x895261',
b'\xf1\x870CW300048J \xf1\x890611',
b'\xf1\x870D9300012 \xf1\x894913',
+ b'\xf1\x870D9300012 \xf1\x894937',
b'\xf1\x870D9300014M \xf1\x895004',
b'\xf1\x870D9300020S \xf1\x895201',
b'\xf1\x870D9300040S \xf1\x894311',
@@ -186,6 +165,7 @@ FW_VERSIONS = {
b'\xf1\x875Q0959655S \xf1\x890870\xf1\x82\02324230011211200621143171724112491132111',
b'\xf1\x875Q0959655S \xf1\x890870\xf1\x82\x1315120011211200061104171717101791132111',
b'\xf1\x875Q0959655T \xf1\x890830\xf1\x82\x13271100111312--071104171826102691131211',
+ b'\xf1\x875QD959655 \xf1\x890388\xf1\x82\x111413001113120006110417121D101D9112',
],
(Ecu.eps, 0x712, None): [
b'\xf1\x873Q0909144F \xf1\x895043\xf1\x82\00561A01612A0',
@@ -205,9 +185,11 @@ FW_VERSIONS = {
b'\xf1\x875Q0909144R \xf1\x891061\xf1\x82\00516A00604A1',
b'\xf1\x875Q0909144S \xf1\x891063\xf1\x82\00516A07A02A1',
b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\00521A20B03A1',
+ b'\xf1\x875QD909144B \xf1\x891072\xf1\x82\x0521A00507A1',
b'\xf1\x875QM909144A \xf1\x891072\xf1\x82\x0521A20B03A1',
b'\xf1\x875QN909144A \xf1\x895081\xf1\x82\00571A01A18A1',
b'\xf1\x875QN909144A \xf1\x895081\xf1\x82\x0571A01A17A1',
+ b'\xf1\x875QM909144B \xf1\x891081\xf1\x82\00521A00442A1',
],
(Ecu.fwdRadar, 0x757, None): [
b'\xf1\x875Q0907572A \xf1\x890141\xf1\x82\00101',
@@ -227,9 +209,11 @@ FW_VERSIONS = {
b'\xf1\x8704E906024AS\xf1\x899912',
b'\xf1\x8704E906024B \xf1\x895594',
b'\xf1\x8704E906024L \xf1\x895595',
+ b'\xf1\x8704E906027MS\xf1\x896223',
b'\xf1\x875G0906259T \xf1\x890003',
],
(Ecu.transmission, 0x7e1, None): [
+ b'\xf1\x8709G927158BQ\xf1\x893545',
b'\xf1\x8709S927158BS\xf1\x893642',
b'\xf1\x8709S927158R \xf1\x893552',
b'\xf1\x8709S927158R \xf1\x893587',
@@ -240,10 +224,12 @@ FW_VERSIONS = {
b'\xf1\x875Q0959655BM\xf1\x890403\xf1\x82\02314171231313500314643011650169333463100',
b'\xf1\x875Q0959655BM\xf1\x890403\xf1\x82\02314171231313500314642011650169333463100',
b'\xf1\x875Q0959655BR\xf1\x890403\xf1\x82\02311170031313300314240011150119333433100',
+ b'\xf1\x875Q0959655BR\xf1\x890403\xf1\x82\02319170031313300314240011550159333463100',
],
(Ecu.eps, 0x712, None): [
b'\xf1\x875QM909144B \xf1\x891081\xf1\x82\00521A10A01A1',
b'\xf1\x875QM909144B \xf1\x891081\xf1\x82\x0521B00404A1',
+ b'\xf1\x875QM909144C \xf1\x891082\xf1\x82\00521A00642A1',
b'\xf1\x875QM909144C \xf1\x891082\xf1\x82\00521A10A01A1',
b'\xf1\x875QN909144B \xf1\x895082\xf1\x82\00571A10A11A1',
],
@@ -256,20 +242,25 @@ FW_VERSIONS = {
(Ecu.engine, 0x7e0, None): [
b'\xf1\x8704E906023AH\xf1\x893379',
b'\xf1\x8704L906026GA\xf1\x892013',
+ b'\xf1\x873G0906264 \xf1\x890004',
],
(Ecu.transmission, 0x7e1, None): [
+ b'\xf1\x870CW300048R \xf1\x890610',
b'\xf1\x870D9300014L \xf1\x895002',
b'\xf1\x870DD300045T \xf1\x891601',
],
(Ecu.srs, 0x715, None): [
b'\xf1\x873Q0959655AN\xf1\x890306\xf1\x82\r58160058140013036914110311',
+ b'\xf1\x873Q0959655BB\xf1\x890195\xf1\x82\r56140056130012026612120211',
b'\xf1\x875Q0959655S \xf1\x890870\xf1\x82\02315120011111200631145171716121691132111',
],
(Ecu.eps, 0x712, None): [
b'\xf1\x875Q0909143M \xf1\x892041\xf1\x820522B0080803',
+ b'\xf1\x875Q0909144S \xf1\x891063\xf1\x82\00516B00501A1',
b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\00521B00703A1',
],
(Ecu.fwdRadar, 0x757, None): [
+ b'\xf1\x873Q0907572B \xf1\x890192',
b'\xf1\x873Q0907572C \xf1\x890195',
b'\xf1\x875Q0907572R \xf1\x890771',
],
@@ -296,26 +287,32 @@ FW_VERSIONS = {
b'\xf1\x8704E906023AN\xf1\x893695',
b'\xf1\x8704E906023AR\xf1\x893440',
b'\xf1\x8704E906023BL\xf1\x895190',
+ b'\xf1\x8704E906027CJ\xf1\x897798',
b'\xf1\x8704L997022N \xf1\x899459',
b'\xf1\x875G0906259L \xf1\x890002',
b'\xf1\x878V0906264B \xf1\x890003',
+ b'\xf1\x878V0907115B \xf1\x890007',
],
(Ecu.transmission, 0x7e1, None): [
+ b'\xf1\x870CW300044T \xf1\x895245',
b'\xf1\x870CW300048 \xf1\x895201',
b'\xf1\x870D9300013B \xf1\x894931',
b'\xf1\x870D9300041N \xf1\x894512',
b'\xf1\x870DD300046A \xf1\x891602',
b'\xf1\x870DD300046F \xf1\x891602',
b'\xf1\x870DD300046G \xf1\x891601',
+ b'\xf1\x870GC300042J \xf1\x891402',
],
(Ecu.srs, 0x715, None): [
b'\xf1\x875Q0959655AM\xf1\x890315\xf1\x82\x1311111111111111311411011231129321212100',
b'\xf1\x875Q0959655J \xf1\x890825\xf1\x82\023111112111111--171115141112221291163221',
b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\023121111111211--261117141112231291163221',
b'\xf1\x875Q0959655J \xf1\x890830\xf1\x82\x13121111111111--341117141212231291163221',
+ b'\xf1\x875Q0959655N \xf1\x890361\xf1\x82\0211212001112110004110411111421149114',
b'\xf1\x875Q0959655N \xf1\x890361\xf1\x82\0211212001112111104110411111521159114',
],
(Ecu.eps, 0x712, None): [
+ b'\xf1\x875Q0909144P \xf1\x891043\xf1\x82\00503G00303A0',
b'\xf1\x875Q0909144P \xf1\x891043\xf1\x82\00503G00803A0',
b'\xf1\x875Q0909144R \xf1\x891061\xf1\x82\00516G00804A1',
b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\00521G00807A1',
@@ -323,6 +320,24 @@ FW_VERSIONS = {
(Ecu.fwdRadar, 0x757, None): [
b'\xf1\x875Q0907572D \xf1\x890304\xf1\x82\00101',
b'\xf1\x875Q0907572G \xf1\x890571',
+ b'\xf1\x875Q0907572H \xf1\x890620',
+ ],
+ },
+ CAR.AUDI_Q2_MK1: {
+ (Ecu.engine, 0x7e0, None): [
+ b'\xf1\x8704E906027JT\xf1\x894145',
+ ],
+ (Ecu.transmission, 0x7e1, None): [
+ b'\xf1\x870CW300041F \xf1\x891006',
+ ],
+ (Ecu.srs, 0x715, None): [
+ b'\xf1\x875Q0959655BD\xf1\x890336\xf1\x82\x1311111111111100311211011231129321312111',
+ ],
+ (Ecu.eps, 0x712, None): [
+ b'\xf1\x873Q0909144K \xf1\x895072\xf1\x82\x0571F60511A1',
+ ],
+ (Ecu.fwdRadar, 0x757, None): [
+ b'\xf1\x872Q0907572M \xf1\x890233',
],
},
CAR.SEAT_ATECA_MK1: {
@@ -342,6 +357,32 @@ FW_VERSIONS = {
b'\xf1\x872Q0907572M \xf1\x890233',
],
},
+ CAR.SEAT_LEON_MK3: {
+ (Ecu.engine, 0x7e0, None): [
+ b'\xf1\x8704L906021EL\xf1\x897542',
+ b'\xf1\x8704L906026BP\xf1\x891198',
+ b'\xf1\x8705E906018AS\xf1\x899596',
+ ],
+ (Ecu.transmission, 0x7e1, None): [
+ b'\xf1\x870CW300050J \xf1\x891908',
+ b'\xf1\x870D9300042M \xf1\x895016',
+ ],
+ (Ecu.srs, 0x715, None): [
+ b'\xf1\x873Q0959655AC\xf1\x890189\xf1\x82\r11110011110011021511110200',
+ b'\xf1\x873Q0959655AS\xf1\x890200\xf1\x82\r12110012120012021612110200',
+ b'\xf1\x873Q0959655CM\xf1\x890720\xf1\x82\0161312001313001305171311052900',
+ ],
+ (Ecu.eps, 0x712, None): [
+ b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\00521N01342A1',
+ b'\xf1\x875Q0909144P \xf1\x891043\xf1\x82\00511N01805A0',
+ b'\xf1\x875Q0909144T \xf1\x891072\xf1\x82\00521N05808A1',
+ ],
+ (Ecu.fwdRadar, 0x757, None): [
+ b'\xf1\x875Q0907572B \xf1\x890200\xf1\x82\00101',
+ b'\xf1\x875Q0907572H \xf1\x890620',
+ b'\xf1\x875Q0907572P \xf1\x890682',
+ ],
+ },
CAR.SKODA_KODIAQ_MK1: {
(Ecu.engine, 0x7e0, None): [
b'\xf1\x8704E906027DD\xf1\x893123',
@@ -367,6 +408,28 @@ FW_VERSIONS = {
b'\xf1\x872Q0907572Q \xf1\x890342',
],
},
+ CAR.SKODA_OCTAVIA_MK3: {
+ (Ecu.engine, 0x7e0, None): [
+ b'\xf1\x8704E906027HD\xf1\x893742',
+ b'\xf1\x8704L906021DT\xf1\x898127',
+ ],
+ (Ecu.transmission, 0x7e1, None): [
+ b'\xf1\x870CW300043B \xf1\x891601',
+ b'\xf1\x870D9300041P \xf1\x894507',
+ ],
+ (Ecu.srs, 0x715, None): [
+ b'\xf1\x873Q0959655AC\xf1\x890200\xf1\x82\r11120011100010022212110200',
+ b'\xf1\x873Q0959655CN\xf1\x890720\xf1\x82\x0e3221003221002105755331052100',
+ ],
+ (Ecu.eps, 0x712, None): [
+ b'\xf1\x875Q0909144AB\xf1\x891082\xf1\x82\x0521T00403A1',
+ b'\xf1\x875Q0909144R \xf1\x891061\xf1\x82\x0516A00604A1',
+ ],
+ (Ecu.fwdRadar, 0x757, None): [
+ b'\xf1\x875Q0907572D \xf1\x890304\xf1\x82\x0101',
+ b'\xf1\x875Q0907572P \xf1\x890682',
+ ],
+ },
CAR.SKODA_SCALA_MK1: {
(Ecu.engine, 0x7e0, None): [
b'\xf1\x8704C906025AK\xf1\x897053',
@@ -419,8 +482,11 @@ DBC = {
CAR.PASSAT_MK8: dbc_dict('vw_mqb_2010', None),
CAR.TIGUAN_MK2: dbc_dict('vw_mqb_2010', None),
CAR.AUDI_A3_MK3: dbc_dict('vw_mqb_2010', None),
+ CAR.AUDI_Q2_MK1: dbc_dict('vw_mqb_2010', None),
CAR.SEAT_ATECA_MK1: dbc_dict('vw_mqb_2010', None),
+ CAR.SEAT_LEON_MK3: dbc_dict('vw_mqb_2010', None),
CAR.SKODA_KODIAQ_MK1: dbc_dict('vw_mqb_2010', None),
+ CAR.SKODA_OCTAVIA_MK3: dbc_dict('vw_mqb_2010', None),
CAR.SKODA_SCALA_MK1: dbc_dict('vw_mqb_2010', None),
CAR.SKODA_SUPERB_MK3: dbc_dict('vw_mqb_2010', None),
}
diff --git a/selfdrive/common/SConscript b/selfdrive/common/SConscript
index 5d5900500..8f6c1dc18 100644
--- a/selfdrive/common/SConscript
+++ b/selfdrive/common/SConscript
@@ -1,4 +1,4 @@
-Import('env', 'arch', 'SHARED', 'QCOM_REPLAY')
+Import('env', 'arch', 'SHARED')
if SHARED:
fxn = env.SharedLibrary
diff --git a/selfdrive/common/gpio.h b/selfdrive/common/gpio.h
index f50134269..e03001987 100644
--- a/selfdrive/common/gpio.h
+++ b/selfdrive/common/gpio.h
@@ -1,7 +1,5 @@
#pragma once
-#include
-
// Pin definitions
#ifdef QCOM2
#define GPIO_HUB_RST_N 30
diff --git a/selfdrive/common/modeldata.h b/selfdrive/common/modeldata.h
index b6282000e..83aff9705 100644
--- a/selfdrive/common/modeldata.h
+++ b/selfdrive/common/modeldata.h
@@ -3,14 +3,16 @@ const int TRAJECTORY_SIZE = 33;
const float MIN_DRAW_DISTANCE = 10.0;
const float MAX_DRAW_DISTANCE = 100.0;
-const double T_IDXS[TRAJECTORY_SIZE] = {0. , 0.00976562, 0.0390625 , 0.08789062, 0.15625 ,
+const double T_IDXS[TRAJECTORY_SIZE] = {
+ 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 double X_IDXS[TRAJECTORY_SIZE] = { 0. , 0.1875, 0.75 , 1.6875, 3. , 4.6875,
+const double X_IDXS[TRAJECTORY_SIZE] = {
+ 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,
diff --git a/selfdrive/common/params.cc b/selfdrive/common/params.cc
index 87d338ed7..45eac661b 100644
--- a/selfdrive/common/params.cc
+++ b/selfdrive/common/params.cc
@@ -148,11 +148,11 @@ std::unordered_map keys = {
{"AthenadPid", PERSISTENT},
{"CalibrationParams", PERSISTENT},
{"CarBatteryCapacity", PERSISTENT},
- {"CarParams", CLEAR_ON_MANAGER_START | CLEAR_ON_PANDA_DISCONNECT | CLEAR_ON_IGNITION},
+ {"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},
+ {"CarVin", CLEAR_ON_MANAGER_START | CLEAR_ON_PANDA_DISCONNECT | CLEAR_ON_IGNITION_ON},
{"CommunityFeaturesToggle", PERSISTENT},
- {"ControlsReady", CLEAR_ON_MANAGER_START | CLEAR_ON_PANDA_DISCONNECT | CLEAR_ON_IGNITION},
+ {"ControlsReady", CLEAR_ON_MANAGER_START | CLEAR_ON_PANDA_DISCONNECT | CLEAR_ON_IGNITION_ON},
{"EnableLteOnroad", PERSISTENT},
{"EndToEndToggle", PERSISTENT},
{"CompletedTrainingVersion", PERSISTENT},
@@ -174,15 +174,18 @@ std::unordered_map keys = {
{"IsLdwEnabled", PERSISTENT},
{"IsMetric", PERSISTENT},
{"IsOffroad", CLEAR_ON_MANAGER_START},
+ {"IsOnroad", PERSISTENT},
{"IsRHD", PERSISTENT},
{"IsTakingSnapshot", CLEAR_ON_MANAGER_START},
{"IsUpdateAvailable", CLEAR_ON_MANAGER_START},
- {"IsUploadRawEnabled", PERSISTENT},
+ {"UploadRaw", PERSISTENT},
{"LastAthenaPingTime", PERSISTENT},
{"LastGPSPosition", PERSISTENT},
{"LastUpdateException", PERSISTENT},
{"LastUpdateTime", PERSISTENT},
{"LiveParameters", PERSISTENT},
+ {"MapboxToken", PERSISTENT},
+ {"NavDestination", CLEAR_ON_MANAGER_START | CLEAR_ON_IGNITION_OFF},
{"OpenpilotEnabledToggle", PERSISTENT},
{"PandaFirmware", CLEAR_ON_MANAGER_START | CLEAR_ON_PANDA_DISCONNECT},
{"PandaFirmwareHex", CLEAR_ON_MANAGER_START | CLEAR_ON_PANDA_DISCONNECT},
@@ -212,6 +215,7 @@ std::unordered_map keys = {
{"Offroad_UpdateFailed", CLEAR_ON_MANAGER_START},
{"Offroad_HardwareUnsupported", CLEAR_ON_MANAGER_START},
{"Offroad_UnofficialHardware", CLEAR_ON_MANAGER_START},
+ {"Offroad_NvmeMissing", CLEAR_ON_MANAGER_START},
{"ForcePowerDown", CLEAR_ON_MANAGER_START},
};
diff --git a/selfdrive/common/params.h b/selfdrive/common/params.h
index 589775c3c..3d59f07b1 100644
--- a/selfdrive/common/params.h
+++ b/selfdrive/common/params.h
@@ -12,8 +12,9 @@ enum ParamKeyType {
PERSISTENT = 0x02,
CLEAR_ON_MANAGER_START = 0x04,
CLEAR_ON_PANDA_DISCONNECT = 0x08,
- CLEAR_ON_IGNITION = 0x10,
- ALL = 0x02 | 0x04 | 0x08 | 0x10
+ CLEAR_ON_IGNITION_ON = 0x10,
+ CLEAR_ON_IGNITION_OFF = 0x20,
+ ALL = 0x02 | 0x04 | 0x08 | 0x10 | 0x20
};
class Params {
@@ -43,6 +44,10 @@ public:
return get(key.c_str(), block);
}
+ inline std::string getParamsPath() {
+ return params_path;
+ }
+
template
std::optional get(const char *key, bool block = false) {
std::istringstream iss(get(key, block));
diff --git a/selfdrive/common/util.cc b/selfdrive/common/util.cc
index 4d366a039..c629550c8 100644
--- a/selfdrive/common/util.cc
+++ b/selfdrive/common/util.cc
@@ -2,7 +2,12 @@
#include
+#include
+#include
+#include
+#include
#include
+#include
#ifdef __linux__
#include
@@ -97,5 +102,74 @@ int write_file(const char* path, const void* data, size_t size, int flags, mode_
return (n >= 0 && (size_t)n == size) ? 0 : -1;
}
+std::string readlink(const std::string &path) {
+ char buff[4096];
+ ssize_t len = ::readlink(path.c_str(), buff, sizeof(buff)-1);
+ if (len != -1) {
+ buff[len] = '\0';
+ return std::string(buff);
+ }
+ return "";
+}
+
+bool file_exists(const std::string& fn) {
+ std::ifstream f(fn);
+ return f.good();
+}
+
+std::string getenv_default(const char* env_var, const char * suffix, const char* default_val) {
+ const char* env_val = getenv(env_var);
+ if (env_val != NULL){
+ return std::string(env_val) + std::string(suffix);
+ } else {
+ return std::string(default_val);
+ }
+}
+
+std::string tohex(const uint8_t *buf, size_t buf_size) {
+ std::unique_ptr hexbuf(new char[buf_size * 2 + 1]);
+ for (size_t i = 0; i < buf_size; i++) {
+ sprintf(&hexbuf[i * 2], "%02x", buf[i]);
+ }
+ hexbuf[buf_size * 2] = 0;
+ return std::string(hexbuf.get(), hexbuf.get() + buf_size * 2);
+}
+
+std::string hexdump(const std::string& in) {
+ std::stringstream ss;
+ ss << std::hex << std::setfill('0');
+ for (size_t i = 0; i < in.size(); i++) {
+ ss << std::setw(2) << static_cast(static_cast(in[i]));
+ }
+ return ss.str();
+}
+
+std::string base_name(std::string const &path) {
+ size_t pos = path.find_last_of("/");
+ if (pos == std::string::npos) return path;
+ return path.substr(pos + 1);
+}
+
+std::string dir_name(std::string const &path) {
+ size_t pos = path.find_last_of("/");
+ if (pos == std::string::npos) return "";
+ return path.substr(0, pos);
+}
+
+struct tm get_time(){
+ time_t rawtime;
+ time(&rawtime);
+
+ struct tm sys_time;
+ gmtime_r(&rawtime, &sys_time);
+
+ return sys_time;
+}
+
+bool time_valid(struct tm sys_time){
+ int year = 1900 + sys_time.tm_year;
+ int month = 1 + sys_time.tm_mon;
+ return (year > 2020) || (year == 2020 && month >= 10);
+}
} // namespace util
diff --git a/selfdrive/common/util.h b/selfdrive/common/util.h
index d4d27fb90..698ca819b 100644
--- a/selfdrive/common/util.h
+++ b/selfdrive/common/util.h
@@ -2,20 +2,16 @@
#include
#include
-#include
#include
#include
-#include
#include
#include
-#include
-#include
-#include
+#include
+#include