parent
58bdb272a7
commit
37192c1aba
|
@ -76,3 +76,5 @@ comma*.sh
|
|||
|
||||
selfdrive/modeld/thneed/compile
|
||||
models/*.thneed
|
||||
|
||||
*.bz2
|
||||
|
|
|
@ -77,6 +77,7 @@ Supported Cars
|
|||
| Honda | CR-V 2015-16 | Touring | openpilot | 25mph<sup>1</sup> | 12mph |
|
||||
| Honda | CR-V 2017-21 | Honda Sensing | Stock | 0mph | 12mph |
|
||||
| Honda | CR-V Hybrid 2017-2019 | Honda Sensing | Stock | 0mph | 12mph |
|
||||
| Honda | e 2020 | All | Stock | 0mph | 3mph |
|
||||
| Honda | Fit 2018-19 | Honda Sensing | openpilot | 25mph<sup>1</sup> | 12mph |
|
||||
| Honda | HR-V 2019-20 | Honda Sensing | openpilot | 25mph<sup>1</sup> | 12mph |
|
||||
| Honda | Insight 2019-21 | All | Stock | 0mph | 3mph |
|
||||
|
@ -138,7 +139,7 @@ Community Maintained Cars and Features
|
|||
|
||||
| Make | Model (US Market Reference) | Supported Package | ACC | No ACC accel below | No ALC below |
|
||||
| ----------| ------------------------------| ------------------| -----------------| -------------------| -------------|
|
||||
| Audi | A3 2014-18 | Prestige | Stock | 0mph | 0mph |
|
||||
| Audi | A3 2014-19 | 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 2018<sup>1</sup> | Adaptive Cruise | openpilot | 0mph | 7mph |
|
||||
|
@ -162,7 +163,7 @@ Community Maintained Cars and Features
|
|||
| Hyundai | Ioniq Electric 2020 | SCC + LKAS | Stock | 0mph | 0mph |
|
||||
| Hyundai | Ioniq PHEV 2020 | SCC + LKAS | Stock | 0mph | 0mph |
|
||||
| Hyundai | Kona 2020 | SCC + LKAS | Stock | 0mph | 0mph |
|
||||
| Hyundai | Kona EV 2019 | SCC + LKAS | Stock | 0mph | 0mph |
|
||||
| Hyundai | Kona EV 2018-19 | SCC + LKAS | Stock | 0mph | 0mph |
|
||||
| Hyundai | Kona Hybrid 2020 | SCC + LKAS | Stock | 0mph | 0mph |
|
||||
| Hyundai | Santa Fe 2019-20 | All | Stock | 0mph | 0mph |
|
||||
| Hyundai | Sonata 2018-2019 | SCC + LKAS | Stock | 0mph | 0mph |
|
||||
|
@ -170,8 +171,8 @@ Community Maintained Cars and Features
|
|||
| Hyundai | Veloster 2019-20 | SCC + LKAS | Stock | 5mph | 0mph |
|
||||
| Jeep | Grand Cherokee 2016-18 | Adaptive Cruise | Stock | 0mph | 9mph |
|
||||
| Jeep | Grand Cherokee 2019-20 | Adaptive Cruise | Stock | 0mph | 39mph |
|
||||
| Kia | Forte 2018-2021 | SCC + LKAS | Stock | 0mph | 0mph |
|
||||
| Kia | Niro EV 2020 | SCC + LKAS | Stock | 0mph | 0mph |
|
||||
| Kia | Forte 2018-21 | SCC + LKAS | Stock | 0mph | 0mph |
|
||||
| Kia | Niro EV 2019-21 | SCC + LKAS | Stock | 0mph | 0mph |
|
||||
| Kia | Niro Hybrid 2021 | SCC + LKAS | Stock | 0mph | 0mph |
|
||||
| Kia | Niro PHEV 2019 | SCC + LKAS | Stock | 10mph | 32mph |
|
||||
| Kia | Optima 2017 | SCC + LKAS | Stock | 0mph | 32mph |
|
||||
|
@ -187,7 +188,7 @@ Community Maintained Cars and Features
|
|||
| 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 | Kodiaq 2018-19 | Driver Assistance | Stock | 0mph | 0mph |
|
||||
| Škoda | Octavia 2015, 2018-19 | Driver Assistance | Stock | 0mph | 0mph |
|
||||
| Škoda | Octavia RS 2016 | Driver Assistance | Stock | 0mph | 0mph |
|
||||
| Škoda | Scala 2020 | Driver Assistance | Stock | 0mph | 0mph |
|
||||
|
@ -198,10 +199,10 @@ Community Maintained Cars and Features
|
|||
| Subaru | Impreza 2017-19 | EyeSight | Stock | 0mph | 0mph |
|
||||
| Volkswagen| Atlas 2018-19 | Driver Assistance | Stock | 0mph | 0mph |
|
||||
| Volkswagen| e-Golf 2014, 2019-20 | Driver Assistance | Stock | 0mph | 0mph |
|
||||
| Volkswagen| Golf 2015-19 | Driver Assistance | Stock | 0mph | 0mph |
|
||||
| Volkswagen| Golf 2015-20 | Driver Assistance | Stock | 0mph | 0mph |
|
||||
| Volkswagen| Golf Alltrack 2017-18 | Driver Assistance | Stock | 0mph | 0mph |
|
||||
| Volkswagen| Golf GTE 2016 | Driver Assistance | Stock | 0mph | 0mph |
|
||||
| Volkswagen| Golf GTI 2018-19 | Driver Assistance | Stock | 0mph | 0mph |
|
||||
| Volkswagen| Golf GTI 2018-20 | Driver Assistance | Stock | 0mph | 0mph |
|
||||
| Volkswagen| Golf R 2016-19 | Driver Assistance | Stock | 0mph | 0mph |
|
||||
| Volkswagen| Golf SportsVan 2016 | Driver Assistance | Stock | 0mph | 0mph |
|
||||
| Volkswagen| Golf SportWagen 2015 | Driver Assistance | Stock | 0mph | 0mph |
|
||||
|
|
|
@ -1,3 +1,9 @@
|
|||
Version 0.8.9 (2021-09-14)
|
||||
========================
|
||||
* Improved fan control on comma three
|
||||
* AGNOS 1.5: improved stability
|
||||
* Honda e 2020 support
|
||||
|
||||
Version 0.8.8 (2021-08-27)
|
||||
========================
|
||||
* New driving model with improved laneless performance
|
||||
|
@ -8,6 +14,7 @@ Version 0.8.8 (2021-08-27)
|
|||
* NEOS 18 for comma two: update packages
|
||||
* AGNOS 1.3 for comma three: fix display init at high temperatures
|
||||
* Improved auto-exposure on comma three
|
||||
* Improved longitudinal control on Honda Nidec cars
|
||||
* Hyundai Kona Hybrid 2020 support thanks to haram-KONA!
|
||||
* Hyundai Sonata Hybrid 2021 support thanks to Matt-Wash-Burn!
|
||||
* Kia Niro Hybrid 2021 support thanks to tetious!
|
||||
|
|
|
@ -299,12 +299,22 @@ struct CarControl {
|
|||
|
||||
struct Actuators {
|
||||
# range from 0.0 - 1.0
|
||||
gas @0: Float32;
|
||||
brake @1: Float32;
|
||||
gasDEPRECATED @0: Float32;
|
||||
brakeDEPRECATED @1: Float32;
|
||||
# range from -1.0 - 1.0
|
||||
steer @2: Float32;
|
||||
steeringAngleDeg @3: Float32;
|
||||
|
||||
accel @4: Float32; # m/s^2
|
||||
longControlState @5: LongControlState;
|
||||
|
||||
enum LongControlState @0xe40f3a917d908282{
|
||||
off @0;
|
||||
pid @1;
|
||||
stopping @2;
|
||||
starting @3;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
struct CruiseControl {
|
||||
|
@ -380,10 +390,10 @@ struct CarParams {
|
|||
|
||||
steerMaxBP @11 :List(Float32);
|
||||
steerMaxV @12 :List(Float32);
|
||||
gasMaxBP @13 :List(Float32);
|
||||
gasMaxV @14 :List(Float32);
|
||||
brakeMaxBP @15 :List(Float32);
|
||||
brakeMaxV @16 :List(Float32);
|
||||
gasMaxBPDEPRECATED @13 :List(Float32);
|
||||
gasMaxVDEPRECATED @14 :List(Float32);
|
||||
brakeMaxBPDEPRECATED @15 :List(Float32);
|
||||
brakeMaxVDEPRECATED @16 :List(Float32);
|
||||
|
||||
# things about the car in the manual
|
||||
mass @17 :Float32; # [kg] curb weight: all fluids no cargo
|
||||
|
@ -416,10 +426,11 @@ struct CarParams {
|
|||
steerControlType @34 :SteerControlType;
|
||||
radarOffCan @35 :Bool; # True when radar objects aren't visible on CAN
|
||||
minSpeedCan @51 :Float32; # Minimum vehicle speed from CAN (below this value drops to 0)
|
||||
stoppingBrakeRate @52 :Float32; # brake_travel/s while trying to stop
|
||||
startingBrakeRate @53 :Float32; # brake_travel/s while releasing on restart
|
||||
stoppingDecelRate @52 :Float32; # m/s^2/s while trying to stop
|
||||
startingAccelRate @53 :Float32; # m/s^2/s while trying to start
|
||||
|
||||
steerActuatorDelay @36 :Float32; # Steering wheel actuator delay in seconds
|
||||
longitudinalActuatorDelay @58 :Float32; # Gas/Brake actuator delay in seconds
|
||||
openpilotLongitudinalControl @37 :Bool; # is openpilot doing the longitudinal control?
|
||||
carVin @38 :Text; # VIN number queried during fingerprinting
|
||||
dashcamOnly @41: Bool;
|
||||
|
|
|
@ -310,9 +310,7 @@ struct DeviceState @0xa4d8b5af2aa492eb {
|
|||
|
||||
# power
|
||||
batteryPercent @8 :Int16;
|
||||
batteryStatus @9 :Text;
|
||||
batteryCurrent @15 :Int32;
|
||||
batteryVoltage @16 :Int32;
|
||||
chargingError @17 :Bool;
|
||||
chargingDisabled @18 :Bool;
|
||||
|
||||
|
@ -320,7 +318,6 @@ struct DeviceState @0xa4d8b5af2aa492eb {
|
|||
cpuTempC @26 :List(Float32);
|
||||
gpuTempC @27 :List(Float32);
|
||||
memoryTempC @28 :Float32;
|
||||
batteryTempC @29 :Float32;
|
||||
ambientTempC @30 :Float32;
|
||||
thermalStatus @14 :ThermalStatus;
|
||||
|
||||
|
@ -368,6 +365,9 @@ struct DeviceState @0xa4d8b5af2aa492eb {
|
|||
batDEPRECATED @6 :UInt32;
|
||||
pa0DEPRECATED @21 :UInt16;
|
||||
cpuUsagePercentDEPRECATED @20 :Int8;
|
||||
batteryStatusDEPRECATED @9 :Text;
|
||||
batteryVoltageDEPRECATED @16 :Int32;
|
||||
batteryTempCDEPRECATED @29 :Float32;
|
||||
}
|
||||
|
||||
struct PandaState @0xa7649e2575e4591e {
|
||||
|
@ -533,7 +533,7 @@ struct ControlsState @0x97ff69c53601abf1 {
|
|||
enabled @19 :Bool;
|
||||
active @36 :Bool;
|
||||
|
||||
longControlState @30 :LongControlState;
|
||||
longControlState @30 :Car.CarControl.Actuators.LongControlState;
|
||||
vPid @2 :Float32;
|
||||
vTargetLead @3 :Float32;
|
||||
vCruise @22 :Float32;
|
||||
|
@ -572,13 +572,6 @@ struct ControlsState @0x97ff69c53601abf1 {
|
|||
softDisabling @3;
|
||||
}
|
||||
|
||||
enum LongControlState {
|
||||
off @0;
|
||||
pid @1;
|
||||
stopping @2;
|
||||
starting @3;
|
||||
}
|
||||
|
||||
enum AlertStatus {
|
||||
normal @0; # low priority alert for user's convenience
|
||||
userPrompt @1; # mid priority alert that might require user intervention
|
||||
|
|
|
@ -91,7 +91,7 @@ int msgq_new_queue(msgq_queue_t * q, const char * path, size_t size){
|
|||
strcpy(full_path, prefix);
|
||||
strcat(full_path, path);
|
||||
|
||||
auto fd = open(full_path, O_RDWR | O_CREAT, 0777);
|
||||
auto fd = open(full_path, O_RDWR | O_CREAT, 0664);
|
||||
if (fd < 0) {
|
||||
std::cout << "Warning, could not open: " << full_path << std::endl;
|
||||
delete[] full_path;
|
||||
|
|
|
@ -20,7 +20,7 @@ static void *malloc_with_fd(size_t len, int *fd) {
|
|||
snprintf(full_path, sizeof(full_path)-1, "/dev/shm/visionbuf_%d_%d", getpid(), offset++);
|
||||
#endif
|
||||
|
||||
*fd = open(full_path, O_RDWR | O_CREAT, 0777);
|
||||
*fd = open(full_path, O_RDWR | O_CREAT, 0664);
|
||||
assert(*fd >= 0);
|
||||
|
||||
unlink(full_path);
|
||||
|
|
|
@ -13,6 +13,9 @@ cdef extern from "visionbuf.h":
|
|||
cdef cppclass VisionBuf:
|
||||
void * addr
|
||||
size_t len
|
||||
size_t width
|
||||
size_t height
|
||||
size_t stride
|
||||
|
||||
cdef extern from "visionipc.h":
|
||||
struct VisionIpcBufExtra:
|
||||
|
@ -27,3 +30,9 @@ cdef extern from "visionipc_server.h":
|
|||
VisionBuf * get_buffer(VisionStreamType)
|
||||
void send(VisionBuf *, VisionIpcBufExtra *, bool)
|
||||
void start_listener()
|
||||
|
||||
cdef extern from "visionipc_client.h":
|
||||
cdef cppclass VisionIpcClient:
|
||||
VisionIpcClient(string, VisionStreamType, bool, void*, void*)
|
||||
VisionBuf * recv(VisionIpcBufExtra *, int)
|
||||
bool connect(bool)
|
||||
|
|
|
@ -2,12 +2,16 @@
|
|||
# cython: c_string_encoding=ascii, language_level=3
|
||||
|
||||
import sys
|
||||
from libcpp.string cimport string
|
||||
from libcpp cimport bool
|
||||
import numpy as np
|
||||
cimport numpy as cnp
|
||||
from cython.view cimport array
|
||||
from libc.string cimport memcpy
|
||||
from libc.stdint cimport uint32_t, uint64_t
|
||||
from libcpp cimport bool
|
||||
from libcpp.string cimport string
|
||||
|
||||
from .visionipc cimport VisionIpcServer as cppVisionIpcServer
|
||||
from .visionipc cimport VisionIpcClient as cppVisionIpcClient
|
||||
from .visionipc cimport VisionBuf as cppVisionBuf
|
||||
from .visionipc cimport VisionIpcBufExtra
|
||||
|
||||
|
@ -19,6 +23,7 @@ cpdef enum VisionStreamType:
|
|||
VISION_STREAM_YUV_FRONT
|
||||
VISION_STREAM_YUV_WIDE
|
||||
|
||||
|
||||
cdef class VisionIpcServer:
|
||||
cdef cppVisionIpcServer * server
|
||||
|
||||
|
@ -47,3 +52,39 @@ cdef class VisionIpcServer:
|
|||
|
||||
def __dealloc__(self):
|
||||
del self.server
|
||||
|
||||
|
||||
cdef class VisionIpcClient:
|
||||
cdef cppVisionBuf * buf
|
||||
cdef cppVisionIpcClient * client
|
||||
|
||||
def __cinit__(self, string name, VisionStreamType stream, bool conflate):
|
||||
self.client = new cppVisionIpcClient(name, stream, conflate, NULL, NULL)
|
||||
self.buf = NULL
|
||||
|
||||
def __dealloc__(self):
|
||||
del self.client
|
||||
|
||||
@property
|
||||
def width(self):
|
||||
return None if not self.buf else self.buf.width
|
||||
|
||||
@property
|
||||
def height(self):
|
||||
return None if not self.buf else self.buf.height
|
||||
|
||||
@property
|
||||
def stride(self):
|
||||
return None if not self.buf else self.buf.stride
|
||||
|
||||
def recv(self, int timeout_ms=100):
|
||||
self.buf = self.client.recv(NULL, timeout_ms)
|
||||
if not self.buf:
|
||||
return None
|
||||
cdef cnp.ndarray dat = np.empty(self.buf.len, dtype=np.uint8)
|
||||
cdef char[:] dat_view = dat
|
||||
memcpy(&dat_view[0], self.buf.addr, self.buf.len)
|
||||
return dat
|
||||
|
||||
def connect(self, bool blocking):
|
||||
return self.client.connect(blocking)
|
||||
|
|
|
@ -39,28 +39,6 @@ def get_tmpdir_on_same_filesystem(path):
|
|||
return "/tmp"
|
||||
|
||||
|
||||
class AutoMoveTempdir():
|
||||
def __init__(self, target_path, temp_dir=None):
|
||||
self._target_path = target_path
|
||||
self._path = tempfile.mkdtemp(dir=temp_dir)
|
||||
|
||||
@property
|
||||
def name(self):
|
||||
return self._path
|
||||
|
||||
def close(self):
|
||||
os.rename(self._path, self._target_path)
|
||||
|
||||
def __enter__(self):
|
||||
return self
|
||||
|
||||
def __exit__(self, exc_type, exc_value, traceback):
|
||||
if exc_type is None:
|
||||
self.close()
|
||||
else:
|
||||
shutil.rmtree(self._path)
|
||||
|
||||
|
||||
class NamedTemporaryDir():
|
||||
def __init__(self, temp_dir=None):
|
||||
self._path = tempfile.mkdtemp(dir=temp_dir)
|
||||
|
@ -100,9 +78,7 @@ class CallbackReader:
|
|||
|
||||
def _get_fileobject_func(writer, temp_dir):
|
||||
def _get_fileobject():
|
||||
file_obj = writer.get_fileobject(dir=temp_dir)
|
||||
os.chmod(file_obj.name, 0o644)
|
||||
return file_obj
|
||||
return writer.get_fileobject(dir=temp_dir)
|
||||
return _get_fileobject
|
||||
|
||||
|
||||
|
@ -122,20 +98,3 @@ def atomic_write_in_dir(path, **kwargs):
|
|||
"""
|
||||
writer = AtomicWriter(path, **kwargs)
|
||||
return writer._open(_get_fileobject_func(writer, os.path.dirname(path)))
|
||||
|
||||
|
||||
def atomic_write_in_dir_neos(path, contents, mode=None):
|
||||
"""
|
||||
Atomically writes contents to path using a temporary file in the same directory
|
||||
as path. Useful on NEOS, where `os.link` (required by atomic_write_in_dir) is missing.
|
||||
"""
|
||||
|
||||
f = tempfile.NamedTemporaryFile(delete=False, prefix=".tmp", dir=os.path.dirname(path))
|
||||
f.write(contents)
|
||||
f.flush()
|
||||
if mode is not None:
|
||||
os.fchmod(f.fileno(), mode)
|
||||
os.fsync(f.fileno())
|
||||
f.close()
|
||||
|
||||
os.rename(f.name, path)
|
||||
|
|
|
@ -1,13 +1,18 @@
|
|||
class FirstOrderFilter:
|
||||
# first order filter
|
||||
def __init__(self, x0, rc, dt):
|
||||
def __init__(self, x0, rc, dt, initialized=True):
|
||||
self.x = x0
|
||||
self.dt = dt
|
||||
self.update_alpha(rc)
|
||||
self.initialized = initialized
|
||||
|
||||
def update_alpha(self, rc):
|
||||
self.alpha = self.dt / (rc + self.dt)
|
||||
|
||||
def update(self, x):
|
||||
self.x = (1. - self.alpha) * self.x + self.alpha * x
|
||||
if self.initialized:
|
||||
self.x = (1. - self.alpha) * self.x + self.alpha * x
|
||||
else:
|
||||
self.initialized = True
|
||||
self.x = x
|
||||
return self.x
|
||||
|
|
|
@ -111,10 +111,15 @@ function tici_init {
|
|||
sleep 3
|
||||
fi
|
||||
|
||||
# setup governors
|
||||
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'
|
||||
|
||||
# TODO: move this to agnos
|
||||
# network manager config
|
||||
nmcli connection modify --temporary lte gsm.auto-config yes
|
||||
nmcli connection modify --temporary lte gsm.home-only yes
|
||||
sudo rm -f /data/etc/NetworkManager/system-connections/*.nmmeta
|
||||
|
||||
# set success flag for current boot slot
|
||||
sudo abctl --set_success
|
||||
|
|
|
@ -11,7 +11,7 @@ if [ -z "$REQUIRED_NEOS_VERSION" ]; then
|
|||
fi
|
||||
|
||||
if [ -z "$AGNOS_VERSION" ]; then
|
||||
export AGNOS_VERSION="1.3"
|
||||
export AGNOS_VERSION="1.5"
|
||||
fi
|
||||
|
||||
if [ -z "$PASSIVE" ]; then
|
||||
|
|
|
@ -1,24 +1,6 @@
|
|||
CM_ "AUTOGENERATED FILE, DO NOT EDIT";
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
|
||||
CM_ "Imported file _honda_2017.dbc starts here";
|
||||
VERSION ""
|
||||
|
||||
|
@ -251,6 +233,24 @@ VAL_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped" ;
|
|||
VAL_ 780 HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car" ;
|
||||
VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ;
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
CM_ "acura_ilx_2016_can.dbc starts here";
|
||||
|
||||
|
||||
|
|
|
@ -1,24 +1,6 @@
|
|||
CM_ "AUTOGENERATED FILE, DO NOT EDIT";
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
|
||||
CM_ "Imported file _honda_2017.dbc starts here";
|
||||
VERSION ""
|
||||
|
||||
|
@ -251,6 +233,24 @@ VAL_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped" ;
|
|||
VAL_ 780 HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car" ;
|
||||
VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ;
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
CM_ "acura_rdx_2018_can.dbc starts here";
|
||||
|
||||
|
||||
|
|
|
@ -66,7 +66,7 @@ cdef extern from "common_dbc.h":
|
|||
double value
|
||||
|
||||
cdef struct SignalPackValue:
|
||||
const char * name
|
||||
string name
|
||||
double value
|
||||
|
||||
|
||||
|
|
|
@ -8,7 +8,7 @@
|
|||
#define ARRAYSIZE(x) (sizeof(x)/sizeof(x[0]))
|
||||
|
||||
struct SignalPackValue {
|
||||
const char* name;
|
||||
std::string name;
|
||||
double value;
|
||||
};
|
||||
|
||||
|
|
|
@ -51,12 +51,11 @@ CANPacker::CANPacker(const std::string& dbc_name) {
|
|||
uint64_t CANPacker::pack(uint32_t address, const std::vector<SignalPackValue> &signals, int counter) {
|
||||
uint64_t ret = 0;
|
||||
for (const auto& sigval : signals) {
|
||||
std::string name = std::string(sigval.name);
|
||||
double value = sigval.value;
|
||||
|
||||
auto sig_it = signal_lookup.find(std::make_pair(address, name));
|
||||
auto sig_it = signal_lookup.find(std::make_pair(address, sigval.name));
|
||||
if (sig_it == signal_lookup.end()) {
|
||||
WARN("undefined signal %s - %d\n", name.c_str(), address);
|
||||
WARN("undefined signal %s - %d\n", sigval.name.c_str(), address);
|
||||
continue;
|
||||
}
|
||||
const auto& sig = sig_it->second;
|
||||
|
|
|
@ -33,15 +33,11 @@ cdef class CANPacker:
|
|||
|
||||
cdef uint64_t pack(self, addr, values, counter):
|
||||
cdef vector[SignalPackValue] values_thing
|
||||
values_thing.reserve(len(values))
|
||||
cdef SignalPackValue spv
|
||||
|
||||
names = []
|
||||
|
||||
for name, value in values.iteritems():
|
||||
n = name.encode('utf8')
|
||||
names.append(n) # TODO: find better way to keep reference to temp string around
|
||||
|
||||
spv.name = n
|
||||
spv.name = name.encode('utf8')
|
||||
spv.value = value
|
||||
values_thing.push_back(spv)
|
||||
|
||||
|
|
|
@ -175,18 +175,15 @@ cdef class CANDefine():
|
|||
val = self.dbc[0].vals[i]
|
||||
|
||||
sgname = val.name.decode('utf8')
|
||||
address = val.address
|
||||
def_val = val.def_val.decode('utf8')
|
||||
address = val.address
|
||||
msgname = address_to_msg_name[address]
|
||||
|
||||
#separate definition/value pairs
|
||||
# separate definition/value pairs
|
||||
def_val = def_val.split()
|
||||
values = [int(v) for v in def_val[::2]]
|
||||
defs = def_val[1::2]
|
||||
|
||||
if address not in dv:
|
||||
dv[address] = {}
|
||||
msgname = address_to_msg_name[address]
|
||||
dv[msgname] = {}
|
||||
|
||||
# two ways to lookup: address or msg name
|
||||
dv[address][sgname] = dict(zip(values, defs))
|
||||
|
|
|
@ -163,7 +163,7 @@ BO_ 715 ASCMGasRegenCmd: 8 K124_ASCM
|
|||
BO_ 717 ASCM_2CD: 5 K124_ASCM
|
||||
|
||||
BO_ 810 TCICOnStarGPSPosition: 8 K73_TCIC
|
||||
SG_ GPSLongitude : 39|32@0+ (1,0) [0|0] "milliarcsecond" NEO
|
||||
SG_ GPSLongitude : 39|32@0+ (1,-2147483648) [0|0] "milliarcsecond" NEO
|
||||
SG_ GPSLatitude : 7|32@0+ (1,0) [0|0] "milliarcsecond" NEO
|
||||
|
||||
BO_ 840 EBCMWheelSpdFront: 4 K17_EBCM
|
||||
|
|
|
@ -1,24 +1,6 @@
|
|||
CM_ "AUTOGENERATED FILE, DO NOT EDIT";
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
|
||||
CM_ "Imported file _honda_2017.dbc starts here";
|
||||
VERSION ""
|
||||
|
||||
|
@ -251,6 +233,24 @@ VAL_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped" ;
|
|||
VAL_ 780 HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car" ;
|
||||
VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ;
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
CM_ "honda_civic_touring_2016_can.dbc starts here";
|
||||
|
||||
|
||||
|
|
|
@ -1,24 +1,6 @@
|
|||
CM_ "AUTOGENERATED FILE, DO NOT EDIT";
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
|
||||
CM_ "Imported file _honda_2017.dbc starts here";
|
||||
VERSION ""
|
||||
|
||||
|
@ -251,6 +233,24 @@ VAL_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped" ;
|
|||
VAL_ 780 HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car" ;
|
||||
VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ;
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
CM_ "honda_crv_executive_2016_can.dbc starts here";
|
||||
|
||||
|
||||
|
|
|
@ -1,24 +1,6 @@
|
|||
CM_ "AUTOGENERATED FILE, DO NOT EDIT";
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
|
||||
CM_ "Imported file _honda_2017.dbc starts here";
|
||||
VERSION ""
|
||||
|
||||
|
@ -251,6 +233,24 @@ VAL_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped" ;
|
|||
VAL_ 780 HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car" ;
|
||||
VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ;
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
CM_ "honda_crv_touring_2016_can.dbc starts here";
|
||||
|
||||
|
||||
|
|
|
@ -1,24 +1,6 @@
|
|||
CM_ "AUTOGENERATED FILE, DO NOT EDIT";
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
|
||||
CM_ "Imported file _honda_2017.dbc starts here";
|
||||
VERSION ""
|
||||
|
||||
|
@ -251,6 +233,24 @@ VAL_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped" ;
|
|||
VAL_ 780 HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car" ;
|
||||
VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ;
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
CM_ "honda_fit_ex_2018_can.dbc starts here";
|
||||
|
||||
|
||||
|
@ -273,6 +273,9 @@ BO_ 304 GAS_PEDAL_2: 8 PCM
|
|||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
|
||||
|
||||
BO_ 316 GAS_PEDAL: 8 PCM
|
||||
SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
BO_ 342 STEERING_SENSORS: 6 EPS
|
||||
SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON
|
||||
SG_ STEER_ANGLE_RATE : 23|16@0- (-1,0) [-3000|3000] "deg/s" EON
|
||||
|
@ -299,6 +302,7 @@ BO_ 422 SCM_BUTTONS: 8 SCM
|
|||
SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ DRIVERS_DOOR_OPEN : 63|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
|
||||
|
||||
|
|
|
@ -1,341 +0,0 @@
|
|||
CM_ "AUTOGENERATED FILE, DO NOT EDIT";
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
|
||||
CM_ "Imported file _honda_2017.dbc starts here";
|
||||
VERSION ""
|
||||
|
||||
|
||||
NS_ :
|
||||
NS_DESC_
|
||||
CM_
|
||||
BA_DEF_
|
||||
BA_
|
||||
VAL_
|
||||
CAT_DEF_
|
||||
CAT_
|
||||
FILTER
|
||||
BA_DEF_DEF_
|
||||
EV_DATA_
|
||||
ENVVAR_DATA_
|
||||
SGTYPE_
|
||||
SGTYPE_VAL_
|
||||
BA_DEF_SGTYPE_
|
||||
BA_SGTYPE_
|
||||
SIG_TYPE_REF_
|
||||
VAL_TABLE_
|
||||
SIG_GROUP_
|
||||
SIG_VALTYPE_
|
||||
SIGTYPE_VALTYPE_
|
||||
BO_TX_BU_
|
||||
BA_DEF_REL_
|
||||
BA_REL_
|
||||
BA_DEF_DEF_REL_
|
||||
BU_SG_REL_
|
||||
BU_EV_REL_
|
||||
BU_BO_REL_
|
||||
SG_MUL_VAL_
|
||||
|
||||
BU_: EBCM ADAS PCM EPS VSA SCM BDY XXX EPB EON
|
||||
|
||||
BO_ 344 ENGINE_DATA: 8 PCM
|
||||
SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" EON
|
||||
SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON
|
||||
SG_ XMISSION_SPEED2 : 39|16@0+ (0.01,0) [0|250] "kph" EON
|
||||
SG_ ODOMETER : 55|8@0+ (10,0) [0|2550] "m" XXX
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON
|
||||
|
||||
BO_ 380 POWERTRAIN_DATA: 8 PCM
|
||||
SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" EON
|
||||
SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON
|
||||
SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "rpm" EON
|
||||
SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "rpm" EON
|
||||
SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "rpm" EON
|
||||
SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "rpm" EON
|
||||
SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "rpm" EON
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
|
||||
|
||||
BO_ 420 VSA_STATUS: 8 VSA
|
||||
SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON
|
||||
SG_ COMPUTER_BRAKING : 23|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ BRAKE_HOLD_RELATED : 52|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ BRAKE_HOLD_ENABLED : 45|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON
|
||||
|
||||
BO_ 427 STEER_MOTOR_TORQUE: 3 EPS
|
||||
SG_ CONFIG_VALID : 7|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ MOTOR_TORQUE : 1|10@0+ (1,0) [0|256] "" EON
|
||||
SG_ OUTPUT_DISABLED : 22|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ COUNTER : 21|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 19|4@0+ (1,0) [0|15] "" EON
|
||||
|
||||
BO_ 432 STANDSTILL: 7 VSA
|
||||
SG_ CONTROLLED_STANDSTILL : 0|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON
|
||||
|
||||
BO_ 464 WHEEL_SPEEDS: 8 VSA
|
||||
SG_ WHEEL_SPEED_FL : 7|15@0+ (0.01,0) [0|250] "kph" EON
|
||||
SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON
|
||||
SG_ WHEEL_SPEED_RL : 25|15@0+ (0.01,0) [0|250] "kph" EON
|
||||
SG_ WHEEL_SPEED_RR : 42|15@0+ (0.01,0) [0|250] "kph" EON
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
|
||||
|
||||
BO_ 490 VEHICLE_DYNAMICS: 8 VSA
|
||||
SG_ LONG_ACCEL : 23|16@0- (0.0015384,0) [-20|20] "m/s2" EON
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
|
||||
|
||||
BO_ 506 BRAKE_COMMAND: 8 ADAS
|
||||
SG_ COMPUTER_BRAKE : 7|10@0+ (1,0) [0|1] "" EBCM
|
||||
SG_ SET_ME_X00 : 13|5@0+ (1,0) [0|1] "" EBCM
|
||||
SG_ BRAKE_PUMP_REQUEST : 8|1@0+ (1,0) [0|1] "" EBCM
|
||||
SG_ SET_ME_X00_2 : 23|3@0+ (1,0) [0|1] "" EBCM
|
||||
SG_ CRUISE_OVERRIDE : 20|1@0+ (1,0) [0|1] "" EBCM
|
||||
SG_ SET_ME_X00_3 : 19|1@0+ (1,0) [0|1] "" EBCM
|
||||
SG_ CRUISE_FAULT_CMD : 18|1@0+ (1,0) [0|1] "" EBCM
|
||||
SG_ CRUISE_CANCEL_CMD : 17|1@0+ (1,0) [0|1] "" EBCM
|
||||
SG_ COMPUTER_BRAKE_REQUEST : 16|1@0+ (1,0) [0|1] "" EBCM
|
||||
SG_ SET_ME_1 : 31|1@0+ (1,0) [0|1] "" EBCM
|
||||
SG_ AEB_REQ_1 : 29|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ AEB_REQ_2 : 26|3@0+ (1,0) [0|7] "" XXX
|
||||
SG_ BRAKE_LIGHTS : 39|1@0+ (1,0) [0|1] "" EBCM
|
||||
SG_ CRUISE_STATES : 38|7@0+ (1,0) [0|1] "" EBCM
|
||||
SG_ CHIME : 47|3@0+ (1,0) [0|7] "" EBCM
|
||||
SG_ SET_ME_X00_4 : 44|1@0+ (1,0) [0|1] "" EBCM
|
||||
SG_ FCW : 43|2@0+ (1,0) [0|3] "" EBCM
|
||||
SG_ AEB_STATUS : 41|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ SET_ME_X00_5 : 55|8@0+ (1,0) [0|0] "" EBCM
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EBCM
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EBCM
|
||||
|
||||
BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA
|
||||
SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" EON
|
||||
SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" EON
|
||||
SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" EON
|
||||
SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" EON
|
||||
SG_ SET_TO_X55 : 39|8@0+ (1,0) [0|255] "" EON
|
||||
SG_ SET_TO_X55_2 : 47|8@0+ (1,0) [0|255] "" EON
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON
|
||||
|
||||
BO_ 773 SEATBELT_STATUS: 7 BDY
|
||||
SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON
|
||||
|
||||
BO_ 777 LOCK_STATUS: 8 XXX
|
||||
SG_ DOORS_UNLOCKED : 54|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ DOORS_LOCKED : 55|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
|
||||
|
||||
BO_ 780 ACC_HUD: 8 ADAS
|
||||
SG_ PCM_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" BDY
|
||||
SG_ PCM_GAS : 23|8@0+ (1,0) [0|127] "" BDY
|
||||
SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY
|
||||
SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ FCM_OFF : 36|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ FCM_OFF_2 : 35|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ HUD_DISTANCE : 47|2@0+ (1,0) [0|3] "" BDY
|
||||
SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY
|
||||
SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY
|
||||
SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY
|
||||
SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY
|
||||
SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY
|
||||
SG_ SET_ME_X01_2 : 55|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ IMPERIAL_UNIT : 54|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ HUD_DISTANCE_3 : 52|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ CHIME : 51|3@0+ (1,0) [0|1] "" BDY
|
||||
SG_ SET_ME_X01 : 48|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ ICONS : 63|2@0+ (1,0) [0|1] "" BDY
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY
|
||||
|
||||
BO_ 804 CRUISE: 8 PCM
|
||||
SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" EON
|
||||
SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" EON
|
||||
SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON
|
||||
SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" EON
|
||||
SG_ BOH2 : 47|8@0- (1,0) [0|255] "" EON
|
||||
SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" EON
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
|
||||
|
||||
BO_ 829 LKAS_HUD: 5 ADAS
|
||||
SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY
|
||||
SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY
|
||||
SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY
|
||||
SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY
|
||||
SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY
|
||||
SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY
|
||||
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY
|
||||
SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY
|
||||
|
||||
BO_ 892 CRUISE_PARAMS: 8 PCM
|
||||
SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" EON
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
|
||||
|
||||
BO_ 1029 DOORS_STATUS: 8 BDY
|
||||
SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
|
||||
|
||||
CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping";
|
||||
CM_ SG_ 506 AEB_REQ_1 "set for duration of suspected AEB event";
|
||||
CM_ SG_ 773 PASS_AIRBAG_ON "Might just be indicator light";
|
||||
CM_ SG_ 773 PASS_AIRBAG_OFF "Might just be indicator light";
|
||||
CM_ SG_ 780 CRUISE_SPEED "255 = no speed";
|
||||
CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed";
|
||||
CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc...";
|
||||
|
||||
|
||||
VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw" ;
|
||||
VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime" ;
|
||||
VAL_ 506 AEB_STATUS 3 "aeb_prepare" 2 "aeb_ready" 1 "aeb_braking" 0 "no_aeb" ;
|
||||
VAL_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped" ;
|
||||
VAL_ 780 HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car" ;
|
||||
VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ;
|
||||
|
||||
CM_ "honda_hrv_touring_2019_can.dbc starts here";
|
||||
|
||||
|
||||
|
||||
BO_ 145 KINEMATICS: 8 XXX
|
||||
SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON
|
||||
|
||||
BO_ 228 STEERING_CONTROL: 5 ADAS
|
||||
SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS
|
||||
SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS
|
||||
SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS
|
||||
SG_ SET_ME_X00_2 : 31|8@0+ (1,0) [0|0] "" EPS
|
||||
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS
|
||||
SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" EPS
|
||||
|
||||
BO_ 316 GAS_PEDAL: 8 PCM
|
||||
SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
BO_ 342 STEERING_SENSORS: 6 EPS
|
||||
SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON
|
||||
SG_ STEER_ANGLE_RATE : 23|16@0- (-1,0) [-3000|3000] "deg/s" EON
|
||||
SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON
|
||||
|
||||
BO_ 399 STEER_STATUS: 7 EPS
|
||||
SG_ STEER_TORQUE_SENSOR : 7|16@0- (-1,0) [-31000|31000] "tbd" EON
|
||||
SG_ STEER_ANGLE_RATE : 23|16@0- (-0.1,0) [-31000|31000] "deg/s" EON
|
||||
SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ STEER_CONFIG_INDEX : 43|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON
|
||||
|
||||
BO_ 401 GEARBOX: 8 PCM
|
||||
SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" EON
|
||||
SG_ GEAR : 43|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
|
||||
|
||||
BO_ 422 SCM_BUTTONS: 8 SCM
|
||||
SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON
|
||||
SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ DRIVERS_DOOR_OPEN : 63|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
|
||||
|
||||
BO_ 487 BRAKE_PRESSURE: 4 VSA
|
||||
SG_ BRAKE_PRESSURE1 : 7|10@0+ (0.015625,-103) [0|1000] "" EON
|
||||
SG_ BRAKE_PRESSURE2 : 9|10@0+ (0.015625,-103) [0|1000] "" EON
|
||||
SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EON
|
||||
SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON
|
||||
|
||||
BO_ 660 SCM_FEEDBACK: 8 SCM
|
||||
SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON
|
||||
|
||||
BO_ 862 HIGHBEAM_CONTROL: 8 ADAS
|
||||
SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY
|
||||
SG_ ZEROS_BOH_2 : 48|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ AUTO_HIGHBEAMS_ACTIVE : 53|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_ 884 STALK_STATUS: 8 XXX
|
||||
SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
|
||||
|
||||
CM_ SG_ 401 GEAR "10 = reverse, 11 = transition";
|
||||
CM_ SG_ 420 BRAKE_HOLD_RELATED "On when Brake Hold engaged";
|
||||
|
||||
VAL_ 399 STEER_STATUS 6 "tmp_fault" 5 "fault_1" 4 "no_torque_alert_2" 3 "low_speed_lockout" 2 "no_torque_alert_1" 0 "normal" ;
|
||||
VAL_ 401 GEAR_SHIFTER 32 "L" 16 "S" 8 "D" 4 "N" 2 "R" 1 "P" ;
|
||||
VAL_ 401 GEAR 7 "L" 10 "S" 4 "D" 3 "N" 2 "R" 1 "P" ;
|
||||
VAL_ 422 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ;
|
||||
VAL_ 422 LIGHTS_SETTING 3 "high_beam" 2 "low_beam" 1 "position" 0 "no_lights" ;
|
||||
VAL_ 422 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ;
|
||||
|
||||
CM_ "CHFFR_METRIC 342 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";
|
|
@ -1,24 +1,6 @@
|
|||
CM_ "AUTOGENERATED FILE, DO NOT EDIT";
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
|
||||
CM_ "Imported file _honda_2017.dbc starts here";
|
||||
VERSION ""
|
||||
|
||||
|
@ -251,6 +233,24 @@ VAL_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped" ;
|
|||
VAL_ 780 HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car" ;
|
||||
VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ;
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
CM_ "honda_odyssey_exl_2018.dbc starts here";
|
||||
|
||||
|
||||
|
|
|
@ -1,24 +1,6 @@
|
|||
CM_ "AUTOGENERATED FILE, DO NOT EDIT";
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
|
||||
CM_ "Imported file _honda_2017.dbc starts here";
|
||||
VERSION ""
|
||||
|
||||
|
@ -251,6 +233,24 @@ VAL_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped" ;
|
|||
VAL_ 780 HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car" ;
|
||||
VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ;
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
CM_ "honda_odyssey_extreme_edition_2018_china_can.dbc starts here";
|
||||
|
||||
|
||||
|
|
|
@ -1,24 +1,6 @@
|
|||
CM_ "AUTOGENERATED FILE, DO NOT EDIT";
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
|
||||
CM_ "Imported file _honda_2017.dbc starts here";
|
||||
VERSION ""
|
||||
|
||||
|
@ -251,6 +233,24 @@ VAL_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped" ;
|
|||
VAL_ 780 HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car" ;
|
||||
VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ;
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
CM_ "honda_pilot_touring_2017_can.dbc starts here";
|
||||
|
||||
|
||||
|
|
|
@ -1,24 +1,6 @@
|
|||
CM_ "AUTOGENERATED FILE, DO NOT EDIT";
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
|
||||
CM_ "Imported file _honda_2017.dbc starts here";
|
||||
VERSION ""
|
||||
|
||||
|
@ -251,6 +233,24 @@ VAL_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped" ;
|
|||
VAL_ 780 HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car" ;
|
||||
VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ;
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
CM_ "honda_ridgeline_black_edition_2017_can.dbc starts here";
|
||||
|
||||
|
||||
|
|
|
@ -1489,6 +1489,7 @@ BO_ 1157 LFAHDA_MFC: 4 XXX
|
|||
BO_ 913 BCM_PO_11: 8 Vector__XXX
|
||||
SG_ BCM_Door_Dri_Status : 5|1@0+ (1,0) [0|1] "" PT_ESC_ABS
|
||||
SG_ BCM_Shift_R_MT_SW_Status : 39|2@0+ (1,0) [0|3] "" PT_ESC_ABS
|
||||
SG_ LFA_Pressed : 4|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 1426 LABEL11: 8 XXX
|
||||
SG_ CC_React : 34|1@1+ (1,0) [0|1] "" XXX
|
||||
|
@ -1637,14 +1638,20 @@ BO_ 1042 ICM_412h: 8 ICM
|
|||
SG_ PopupMessageOutput_7Level : 54|1@0+ (1,0) [0|1] "" Vector__XXX
|
||||
SG_ PopupMessageOutput_8Level : 55|1@0+ (1,0) [0|1] "" Vector__XXX
|
||||
|
||||
VAL_ 274 CUR_GR 1 "D" 2 "D" 3 "D" 4 "D" 5 "D" 6 "D" 7 "D" 8 "D" 14 "R" 0 "P";
|
||||
VAL_ 871 CF_Lvr_Gear 5 "D" 8 "S" 6 "N" 7 "R" 0 "P";
|
||||
VAL_ 882 Elect_Gear_Shifter 5 "D" 8 "S" 6 "N" 7 "R" 0 "P";
|
||||
VAL_ 1322 CF_Clu_Gear 1 "P" 2 "R" 4 "N" 8 "D";
|
||||
VAL_ 909 CF_VSM_Warn 2 "FCW" 3 "AEB";
|
||||
VAL_ 1157 LFA_Icon_State 0 "no_wheel" 1 "white_wheel" 2 "green_wheel" 3 "green_wheel_blink";
|
||||
VAL_ 1157 LFA_SysWarning 0 "no_message" 1 "switching_to_hda" 2 "switching_to_scc" 3 "lfa_error" 4 "check_hda" 5 "keep_hands_on_wheel_orange" 6 "keep_hands_on_wheel_red";
|
||||
VAL_ 1157 HDA_Icon_State 0 "no_hda" 1 "white_hda" 2 "green_hda";
|
||||
VAL_ 1157 HDA_SysWarning 0 "no_message" 1 "driving_convenience_systems_cancelled" 2 "highway_drive_assist_system_cancelled";
|
||||
BO_ 1348 Navi_HU: 8 XXX
|
||||
SG_ SpeedLim_Nav_Clu : 7|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
|
||||
|
||||
|
||||
VAL_ 871 CF_Lvr_Gear 5 "D" 8 "S" 6 "N" 7 "R" 0 "P" ;
|
||||
VAL_ 1322 CF_Clu_Gear 1 "P" 2 "R" 4 "N" 8 "D" ;
|
||||
VAL_ 274 CUR_GR 1 "D" 2 "D" 3 "D" 4 "D" 5 "D" 6 "D" 7 "D" 8 "D" 14 "R" 0 "P" ;
|
||||
VAL_ 909 CF_VSM_Warn 2 "FCW" 3 "AEB" ;
|
||||
VAL_ 1157 HDA_Icon_State 0 "no_hda" 1 "white_hda" 2 "green_hda" ;
|
||||
VAL_ 1157 LFA_SysWarning 0 "no_message" 1 "switching_to_hda" 2 "switching_to_scc" 3 "lfa_error" 4 "check_hda" 5 "keep_hands_on_wheel_orange" 6 "keep_hands_on_wheel_red" ;
|
||||
VAL_ 1157 LFA_Icon_State 0 "no_wheel" 1 "white_wheel" 2 "green_wheel" 3 "green_wheel_blink" ;
|
||||
VAL_ 1157 HDA_SysWarning 0 "no_message" 1 "driving_convenience_systems_cancelled" 2 "highway_drive_assist_system_cancelled" ;
|
||||
VAL_ 882 Elect_Gear_Shifter 5 "D" 8 "S" 6 "N" 7 "R" 0 "P" ;
|
||||
CM_ "BO_ E_EMS11: All (plug-in) hybrids use this gas signal: CR_Vcu_AccPedDep_Pos, and all EVs use the Accel_Pedal_Pos signal. See hyundai/values.py for a specific car list";
|
||||
CM_ SG_ 1348 SpeedLim_Nav_Clu "Speed limit displayed on Nav, Cluster and HUD";
|
|
@ -1,41 +1,6 @@
|
|||
CM_ "AUTOGENERATED FILE, DO NOT EDIT";
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 359 STEERING_IPAS_COMMA: 8 IPAS
|
||||
SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX
|
||||
SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant";
|
||||
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX
|
||||
SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX
|
||||
|
||||
CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss";
|
||||
|
||||
|
||||
CM_ "Imported file _toyota_2017.dbc starts here";
|
||||
VERSION ""
|
||||
|
||||
|
@ -265,6 +230,7 @@ BO_ 1556 STEERING_LEVERS: 8 XXX
|
|||
|
||||
BO_ 1568 SEATS_DOORS: 8 XXX
|
||||
SG_ METER_DIMMED : 38|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ PARKING_BRAKE : 60|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX
|
||||
|
@ -277,6 +243,7 @@ BO_ 1570 LIGHT_STALK: 8 SCM
|
|||
SG_ PARKING_LIGHT : 28|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ LOW_BEAM : 29|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ HIGH_BEAM : 30|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DAYTIME_RUNNING_LIGHT : 31|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 1161 RSA1: 8 FCM
|
||||
SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX
|
||||
|
@ -319,6 +286,11 @@ BO_ 1163 RSA3: 8 FCM
|
|||
SG_ OVSPVALM : 19|4@0+ (1,-5) [0|0] "" XXX
|
||||
SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX
|
||||
SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" XXX
|
||||
|
||||
BO_ 1571 CENTRAL_GATEWAY_UNIT: 8 CGW
|
||||
SG_ DOOR_LOCK_FEEDBACK_LIGHT : 15|1@0+ (1,0) [0|0] "" XXX
|
||||
SG_ KEYFOB_LOCKING_FEEDBACK_LIGHT : 61|1@0+ (1,0) [0|0] "" XXX
|
||||
SG_ KEYFOB_UNLOCKING_FEEDBACK_LIGHT : 62|1@0+ (1,0) [0|0] "" XXX
|
||||
|
||||
CM_ SG_ 36 ACCEL_Y "unit is tbd";
|
||||
CM_ SG_ 36 YAW_RATE "verify";
|
||||
|
@ -381,6 +353,41 @@ VAL_ 1162 SPLSGN3 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none";
|
|||
|
||||
CM_ "CHFFR_METRIC 37 STEER_ANGLE STEER_ANGLE 0.36 180";
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 359 STEERING_IPAS_COMMA: 8 IPAS
|
||||
SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX
|
||||
SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant";
|
||||
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX
|
||||
SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX
|
||||
|
||||
CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss";
|
||||
|
||||
CM_ "lexus_ct200h_2018_pt.dbc starts here";
|
||||
|
||||
|
||||
|
|
|
@ -1,41 +1,6 @@
|
|||
CM_ "AUTOGENERATED FILE, DO NOT EDIT";
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 359 STEERING_IPAS_COMMA: 8 IPAS
|
||||
SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX
|
||||
SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant";
|
||||
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX
|
||||
SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX
|
||||
|
||||
CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss";
|
||||
|
||||
|
||||
CM_ "Imported file _toyota_2017.dbc starts here";
|
||||
VERSION ""
|
||||
|
||||
|
@ -265,6 +230,7 @@ BO_ 1556 STEERING_LEVERS: 8 XXX
|
|||
|
||||
BO_ 1568 SEATS_DOORS: 8 XXX
|
||||
SG_ METER_DIMMED : 38|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ PARKING_BRAKE : 60|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX
|
||||
|
@ -277,6 +243,7 @@ BO_ 1570 LIGHT_STALK: 8 SCM
|
|||
SG_ PARKING_LIGHT : 28|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ LOW_BEAM : 29|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ HIGH_BEAM : 30|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DAYTIME_RUNNING_LIGHT : 31|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 1161 RSA1: 8 FCM
|
||||
SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX
|
||||
|
@ -319,6 +286,11 @@ BO_ 1163 RSA3: 8 FCM
|
|||
SG_ OVSPVALM : 19|4@0+ (1,-5) [0|0] "" XXX
|
||||
SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX
|
||||
SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" XXX
|
||||
|
||||
BO_ 1571 CENTRAL_GATEWAY_UNIT: 8 CGW
|
||||
SG_ DOOR_LOCK_FEEDBACK_LIGHT : 15|1@0+ (1,0) [0|0] "" XXX
|
||||
SG_ KEYFOB_LOCKING_FEEDBACK_LIGHT : 61|1@0+ (1,0) [0|0] "" XXX
|
||||
SG_ KEYFOB_UNLOCKING_FEEDBACK_LIGHT : 62|1@0+ (1,0) [0|0] "" XXX
|
||||
|
||||
CM_ SG_ 36 ACCEL_Y "unit is tbd";
|
||||
CM_ SG_ 36 YAW_RATE "verify";
|
||||
|
@ -381,6 +353,41 @@ VAL_ 1162 SPLSGN3 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none";
|
|||
|
||||
CM_ "CHFFR_METRIC 37 STEER_ANGLE STEER_ANGLE 0.36 180";
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 359 STEERING_IPAS_COMMA: 8 IPAS
|
||||
SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX
|
||||
SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant";
|
||||
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX
|
||||
SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX
|
||||
|
||||
CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss";
|
||||
|
||||
CM_ "lexus_is_2018_pt.dbc starts here";
|
||||
|
||||
|
||||
|
|
|
@ -1,41 +1,6 @@
|
|||
CM_ "AUTOGENERATED FILE, DO NOT EDIT";
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 359 STEERING_IPAS_COMMA: 8 IPAS
|
||||
SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX
|
||||
SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant";
|
||||
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX
|
||||
SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX
|
||||
|
||||
CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss";
|
||||
|
||||
|
||||
CM_ "Imported file _toyota_2017.dbc starts here";
|
||||
VERSION ""
|
||||
|
||||
|
@ -265,6 +230,7 @@ BO_ 1556 STEERING_LEVERS: 8 XXX
|
|||
|
||||
BO_ 1568 SEATS_DOORS: 8 XXX
|
||||
SG_ METER_DIMMED : 38|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ PARKING_BRAKE : 60|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX
|
||||
|
@ -277,6 +243,7 @@ BO_ 1570 LIGHT_STALK: 8 SCM
|
|||
SG_ PARKING_LIGHT : 28|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ LOW_BEAM : 29|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ HIGH_BEAM : 30|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DAYTIME_RUNNING_LIGHT : 31|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 1161 RSA1: 8 FCM
|
||||
SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX
|
||||
|
@ -319,6 +286,11 @@ BO_ 1163 RSA3: 8 FCM
|
|||
SG_ OVSPVALM : 19|4@0+ (1,-5) [0|0] "" XXX
|
||||
SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX
|
||||
SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" XXX
|
||||
|
||||
BO_ 1571 CENTRAL_GATEWAY_UNIT: 8 CGW
|
||||
SG_ DOOR_LOCK_FEEDBACK_LIGHT : 15|1@0+ (1,0) [0|0] "" XXX
|
||||
SG_ KEYFOB_LOCKING_FEEDBACK_LIGHT : 61|1@0+ (1,0) [0|0] "" XXX
|
||||
SG_ KEYFOB_UNLOCKING_FEEDBACK_LIGHT : 62|1@0+ (1,0) [0|0] "" XXX
|
||||
|
||||
CM_ SG_ 36 ACCEL_Y "unit is tbd";
|
||||
CM_ SG_ 36 YAW_RATE "verify";
|
||||
|
@ -381,6 +353,41 @@ VAL_ 1162 SPLSGN3 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none";
|
|||
|
||||
CM_ "CHFFR_METRIC 37 STEER_ANGLE STEER_ANGLE 0.36 180";
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 359 STEERING_IPAS_COMMA: 8 IPAS
|
||||
SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX
|
||||
SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant";
|
||||
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX
|
||||
SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX
|
||||
|
||||
CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss";
|
||||
|
||||
CM_ "lexus_nx300_2018_pt.dbc starts here";
|
||||
|
||||
|
||||
|
|
|
@ -1,41 +1,6 @@
|
|||
CM_ "AUTOGENERATED FILE, DO NOT EDIT";
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 359 STEERING_IPAS_COMMA: 8 IPAS
|
||||
SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX
|
||||
SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant";
|
||||
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX
|
||||
SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX
|
||||
|
||||
CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss";
|
||||
|
||||
|
||||
CM_ "Imported file _toyota_2017.dbc starts here";
|
||||
VERSION ""
|
||||
|
||||
|
@ -265,6 +230,7 @@ BO_ 1556 STEERING_LEVERS: 8 XXX
|
|||
|
||||
BO_ 1568 SEATS_DOORS: 8 XXX
|
||||
SG_ METER_DIMMED : 38|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ PARKING_BRAKE : 60|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX
|
||||
|
@ -277,6 +243,7 @@ BO_ 1570 LIGHT_STALK: 8 SCM
|
|||
SG_ PARKING_LIGHT : 28|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ LOW_BEAM : 29|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ HIGH_BEAM : 30|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DAYTIME_RUNNING_LIGHT : 31|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 1161 RSA1: 8 FCM
|
||||
SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX
|
||||
|
@ -319,6 +286,11 @@ BO_ 1163 RSA3: 8 FCM
|
|||
SG_ OVSPVALM : 19|4@0+ (1,-5) [0|0] "" XXX
|
||||
SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX
|
||||
SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" XXX
|
||||
|
||||
BO_ 1571 CENTRAL_GATEWAY_UNIT: 8 CGW
|
||||
SG_ DOOR_LOCK_FEEDBACK_LIGHT : 15|1@0+ (1,0) [0|0] "" XXX
|
||||
SG_ KEYFOB_LOCKING_FEEDBACK_LIGHT : 61|1@0+ (1,0) [0|0] "" XXX
|
||||
SG_ KEYFOB_UNLOCKING_FEEDBACK_LIGHT : 62|1@0+ (1,0) [0|0] "" XXX
|
||||
|
||||
CM_ SG_ 36 ACCEL_Y "unit is tbd";
|
||||
CM_ SG_ 36 YAW_RATE "verify";
|
||||
|
@ -381,6 +353,41 @@ VAL_ 1162 SPLSGN3 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none";
|
|||
|
||||
CM_ "CHFFR_METRIC 37 STEER_ANGLE STEER_ANGLE 0.36 180";
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 359 STEERING_IPAS_COMMA: 8 IPAS
|
||||
SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX
|
||||
SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant";
|
||||
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX
|
||||
SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX
|
||||
|
||||
CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss";
|
||||
|
||||
CM_ "lexus_nx300h_2018_pt.dbc starts here";
|
||||
|
||||
|
||||
|
|
|
@ -1,41 +1,6 @@
|
|||
CM_ "AUTOGENERATED FILE, DO NOT EDIT";
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 359 STEERING_IPAS_COMMA: 8 IPAS
|
||||
SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX
|
||||
SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant";
|
||||
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX
|
||||
SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX
|
||||
|
||||
CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss";
|
||||
|
||||
|
||||
CM_ "Imported file _toyota_2017.dbc starts here";
|
||||
VERSION ""
|
||||
|
||||
|
@ -265,6 +230,7 @@ BO_ 1556 STEERING_LEVERS: 8 XXX
|
|||
|
||||
BO_ 1568 SEATS_DOORS: 8 XXX
|
||||
SG_ METER_DIMMED : 38|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ PARKING_BRAKE : 60|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX
|
||||
|
@ -277,6 +243,7 @@ BO_ 1570 LIGHT_STALK: 8 SCM
|
|||
SG_ PARKING_LIGHT : 28|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ LOW_BEAM : 29|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ HIGH_BEAM : 30|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DAYTIME_RUNNING_LIGHT : 31|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 1161 RSA1: 8 FCM
|
||||
SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX
|
||||
|
@ -319,6 +286,11 @@ BO_ 1163 RSA3: 8 FCM
|
|||
SG_ OVSPVALM : 19|4@0+ (1,-5) [0|0] "" XXX
|
||||
SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX
|
||||
SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" XXX
|
||||
|
||||
BO_ 1571 CENTRAL_GATEWAY_UNIT: 8 CGW
|
||||
SG_ DOOR_LOCK_FEEDBACK_LIGHT : 15|1@0+ (1,0) [0|0] "" XXX
|
||||
SG_ KEYFOB_LOCKING_FEEDBACK_LIGHT : 61|1@0+ (1,0) [0|0] "" XXX
|
||||
SG_ KEYFOB_UNLOCKING_FEEDBACK_LIGHT : 62|1@0+ (1,0) [0|0] "" XXX
|
||||
|
||||
CM_ SG_ 36 ACCEL_Y "unit is tbd";
|
||||
CM_ SG_ 36 YAW_RATE "verify";
|
||||
|
@ -381,6 +353,41 @@ VAL_ 1162 SPLSGN3 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none";
|
|||
|
||||
CM_ "CHFFR_METRIC 37 STEER_ANGLE STEER_ANGLE 0.36 180";
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 359 STEERING_IPAS_COMMA: 8 IPAS
|
||||
SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX
|
||||
SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant";
|
||||
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX
|
||||
SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX
|
||||
|
||||
CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss";
|
||||
|
||||
CM_ "lexus_rx_350_2016_pt.dbc starts here";
|
||||
|
||||
|
||||
|
|
|
@ -1,41 +1,6 @@
|
|||
CM_ "AUTOGENERATED FILE, DO NOT EDIT";
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 359 STEERING_IPAS_COMMA: 8 IPAS
|
||||
SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX
|
||||
SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant";
|
||||
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX
|
||||
SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX
|
||||
|
||||
CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss";
|
||||
|
||||
|
||||
CM_ "Imported file _toyota_2017.dbc starts here";
|
||||
VERSION ""
|
||||
|
||||
|
@ -265,6 +230,7 @@ BO_ 1556 STEERING_LEVERS: 8 XXX
|
|||
|
||||
BO_ 1568 SEATS_DOORS: 8 XXX
|
||||
SG_ METER_DIMMED : 38|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ PARKING_BRAKE : 60|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX
|
||||
|
@ -277,6 +243,7 @@ BO_ 1570 LIGHT_STALK: 8 SCM
|
|||
SG_ PARKING_LIGHT : 28|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ LOW_BEAM : 29|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ HIGH_BEAM : 30|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DAYTIME_RUNNING_LIGHT : 31|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 1161 RSA1: 8 FCM
|
||||
SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX
|
||||
|
@ -319,6 +286,11 @@ BO_ 1163 RSA3: 8 FCM
|
|||
SG_ OVSPVALM : 19|4@0+ (1,-5) [0|0] "" XXX
|
||||
SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX
|
||||
SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" XXX
|
||||
|
||||
BO_ 1571 CENTRAL_GATEWAY_UNIT: 8 CGW
|
||||
SG_ DOOR_LOCK_FEEDBACK_LIGHT : 15|1@0+ (1,0) [0|0] "" XXX
|
||||
SG_ KEYFOB_LOCKING_FEEDBACK_LIGHT : 61|1@0+ (1,0) [0|0] "" XXX
|
||||
SG_ KEYFOB_UNLOCKING_FEEDBACK_LIGHT : 62|1@0+ (1,0) [0|0] "" XXX
|
||||
|
||||
CM_ SG_ 36 ACCEL_Y "unit is tbd";
|
||||
CM_ SG_ 36 YAW_RATE "verify";
|
||||
|
@ -381,6 +353,41 @@ VAL_ 1162 SPLSGN3 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none";
|
|||
|
||||
CM_ "CHFFR_METRIC 37 STEER_ANGLE STEER_ANGLE 0.36 180";
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 359 STEERING_IPAS_COMMA: 8 IPAS
|
||||
SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX
|
||||
SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant";
|
||||
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX
|
||||
SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX
|
||||
|
||||
CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss";
|
||||
|
||||
CM_ "lexus_rx_hybrid_2017_pt.dbc starts here";
|
||||
|
||||
|
||||
|
|
|
@ -218,7 +218,7 @@ 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
|
||||
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
|
||||
|
@ -243,9 +243,9 @@ CM_ SG_ 604 L_RCTA "Rear cross traffic alert, only when in R gear";
|
|||
CM_ SG_ 642 Counter "Affected by signals";
|
||||
CM_ SG_ 642 SEATBELT_FL "Driver seatbelt";
|
||||
CM_ SG_ 880 Steering_Voltage_Flat "receives later than 371";
|
||||
CM_ SG_ 977 UNITS "0 = Metric, 1 = Imperial";
|
||||
|
||||
VAL_ 328 Gear 0 "N" 1 "D" 2 "D" 3 "D" 4 "D" 5 "D" 6 "D" 14 "R" 15 "P";
|
||||
VAL_ 1745 Units 0 "Metric" 1 "Imperial";
|
||||
|
||||
CM_ "subaru_forester_2017.dbc starts here";
|
||||
|
||||
|
|
|
@ -156,6 +156,7 @@ BO_ 552 BSD_RCTA: 8 XXX
|
|||
BO_ 912 Dashlights: 8 XXX
|
||||
SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ Counter : 8|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ UNITS : 24|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ ICY_ROAD : 32|2@1+ (1,0) [0|3] "" XXX
|
||||
SG_ SEATBELT_FL : 48|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ LEFT_BLINKER : 50|1@1+ (1,0) [0|1] "" XXX
|
||||
|
@ -169,32 +170,36 @@ BO_ 940 BodyInfo: 8 XXX
|
|||
SG_ DOOR_OPEN_RL : 34|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ DOOR_OPEN_RR : 35|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ DOOR_OPEN_TRUNK : 36|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DASH_BTN_LIGHTS : 56|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ Lowbeam : 57|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ Highbeam : 58|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ FOG_LIGHTS2 : 60|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ WIPERS : 62|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ BRAKE : 54|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ DASH_BTN_LIGHTS : 56|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ LOWBEAM : 57|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ HIGHBEAM : 58|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ FOG_LIGHTS : 60|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ WIPERS : 62|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 801 ES_DashStatus: 8 XXX
|
||||
SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ Counter : 8|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ PCB_Off : 12|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ LDW_Off : 13|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ Signal1 : 14|10@1+ (1,0) [0|1023] "" XXX
|
||||
SG_ Signal1 : 14|2@1+ (1,0) [0|3] "" XXX
|
||||
SG_ Cruise_State_Msg : 16|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ LKAS_State_Msg : 20|3@1+ (1,0) [0|7] "" XXX
|
||||
SG_ Signal2 : 23|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ Cruise_Soft_Disable : 24|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ Signal2 : 25|3@1+ (1,0) [0|1] "" XXX
|
||||
SG_ Cruise_Status_Msg : 25|2@1+ (1,0) [0|3] "" XXX
|
||||
SG_ Signal3 : 27|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ Cruise_Distance : 28|3@1+ (1,0) [0|7] "" XXX
|
||||
SG_ Signal3 : 31|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ Signal4 : 31|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ Conventional_Cruise : 32|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ Signal4 : 33|2@1+ (1,0) [0|3] "" XXX
|
||||
SG_ Signal5 : 33|2@1+ (1,0) [0|3] "" XXX
|
||||
SG_ Cruise_Disengaged : 35|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ Cruise_Activated : 36|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ Signal5 : 37|3@1+ (1,0) [0|1] "" XXX
|
||||
SG_ Signal6 : 37|3@1+ (1,0) [0|1] "" XXX
|
||||
SG_ Cruise_Set_Speed : 40|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ Cruise_Fault : 48|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ Cruise_On : 49|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ Signal6 : 50|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ Display_Own_Car : 50|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ Brake_Lights : 51|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ Car_Follow : 52|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ Signal7 : 53|3@1+ (1,0) [0|1] "" XXX
|
||||
|
@ -204,22 +209,20 @@ BO_ 801 ES_DashStatus: 8 XXX
|
|||
BO_ 802 ES_LKAS_State: 8 XXX
|
||||
SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ Counter : 8|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ Keep_Hands_On_Wheel : 12|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ Empty_Box : 13|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ Signal1 : 14|3@1+ (1,0) [0|7] "" XXX
|
||||
SG_ LKAS_Alert_Msg : 12|3@1+ (1,0) [0|7] "" XXX
|
||||
SG_ Signal1 : 15|2@1+ (1,0) [0|3] "" XXX
|
||||
SG_ LKAS_ACTIVE : 17|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ Signal2 : 18|5@1+ (1,0) [0|31] "" XXX
|
||||
SG_ LKAS_Dash_State : 18|2@1+ (1,0) [0|2] "" XXX
|
||||
SG_ Signal2 : 20|3@1+ (1,0) [0|7] "" XXX
|
||||
SG_ Backward_Speed_Limit_Menu : 23|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ LKAS_ENABLE_3 : 24|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ LKAS_Left_Line_Enable : 24|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ LKAS_Left_Line_Light_Blink : 25|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ LKAS_ENABLE_2 : 26|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ LKAS_Right_Line_Enable : 26|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ LKAS_Right_Line_Light_Blink : 27|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ LKAS_Left_Line_Visible : 28|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ LKAS_Left_Line_Green : 29|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ LKAS_Right_Line_Visible : 30|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ LKAS_Right_Line_Green : 31|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ LKAS_Alert : 32|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ Signal3 : 36|28@1+ (1,0) [0|1] "" XXX
|
||||
SG_ LKAS_Left_Line_Visible : 28|2@1+ (1,0) [0|3] "" XXX
|
||||
SG_ LKAS_Right_Line_Visible : 30|2@1+ (1,0) [0|3] "" XXX
|
||||
SG_ LKAS_Alert : 32|5@1+ (1,0) [0|31] "" XXX
|
||||
SG_ Signal3 : 37|27@1+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 722 AC_State: 8 XXX
|
||||
SG_ CHECKSUM : 0|8@1+ (1,0) [0|255] "" XXX
|
||||
|
@ -239,12 +242,18 @@ CM_ SG_ 801 PCB_Off "Pre-Collision Braking off";
|
|||
CM_ SG_ 801 Brake_Lights "Driver or Cruise brake on";
|
||||
CM_ SG_ 801 Cruise_State "0 = Normal, 1 = Hold+User Brake, 2 = Ready, 3 = Hold";
|
||||
CM_ SG_ 801 Far_Distance "1=0-5m, 2=5-10m, 3=10-15m, 4=15-20m, 5=20-25m, 6=25-30m, 7=30-35m, 8=35-40m, 9=40-45m, 10=45-50m, 11=50-55m, 12=55-60m, 13=60-65m, 14=65-70m, 15=75m+";
|
||||
CM_ SG_ 801 LKAS_State_Msg "1 = LKAS_Off_Sharp_Curve, 2 = Keep_Hands_On_Steering_wheel_disabled, 3 = LKAS_Off, 4 = LKAS_Off_Too_Slow, 5 = LKAS_Off_Too_Fast";
|
||||
CM_ SG_ 801 Cruise_State_Msg "1 = Cruise_Off_Steep_Slope, 2 = Cruise_lvl1_eco, 3 = Cruise_lvl2_comfort, 4 = Cruise_off_empty_reason, 5 = Cruise_off, 6 = Cruise_Unable_to_set, 7 = Cruise_Unable_to_set_brakes_applied, 8 = Eyesight_not_ready, 9 = Cruise_lvl3_standard, 10 = Cruise_lvl4_dynamic, 11 = Cruise_Unable_to_set_steep_slope";
|
||||
CM_ SG_ 801 Cruise_Soft_Disable "Eyesight soft disable (eg direct sunlight)";
|
||||
CM_ SG_ 802 LKAS_Alert "1 = FCW_Cont_Beep, 2 = FCW_Repeated_Beep, 3 = Throttle_Management_Activated_Warning, 4 = Throttle_Management_Activated_Alert, 8 = Traffic_Light_Ahead, 9 = Apply_Brake_to_Hold Position, 11 = LDW_Right, 12 = LDW_Left, 13 = Stay_Alert, 14 = Lead_Vehicle_Start_Alert";
|
||||
CM_ SG_ 801 Cruise_Status_Msg "1 = Disabled_Bad_Visibility, 2 = Disabled_Check_Manual";
|
||||
CM_ SG_ 802 LKAS_ACTIVE "Turns on the full LKAS dash display";
|
||||
CM_ SG_ 802 LKAS_Alert_Msg "1 = Keep_Hands_On_Wheel, 6 = Pre_Collision_Braking, 7 = Keep_Hands_On_Wheel_Off";
|
||||
CM_ SG_ 802 LKAS_Alert "1 = FCW_Cont_Beep, 2 = FCW_Repeated_Beep, 3 = Throttle_Management_Activated_Warning, 4 = Throttle_Management_Activated_Alert, 5 = Pre_Collision_Activated_Alert, 8 = Traffic_Light_Ahead, 9 = Apply_Brake_to_Hold Position, 11 = LDW_Right, 12 = LDW_Left, 13 = Stay_Alert, 14 = Lead_Vehicle_Start_Alert, 18 = Keep_Hands_On_Steering_Alert, 24 = Audio_Beep, 25 = Audio_Lead_Car_Change, 26 = Audio_ACC_Disengaged, 27 = Audio_LKAS_disabled, 28 = Audio_Ding_Ding, 30 = Audio_Repeated_Beep";
|
||||
CM_ SG_ 802 LKAS_Left_Line_Visible "0 = Off, 1 = White, 2 = Green, 3 = Orange";
|
||||
CM_ SG_ 802 LKAS_Dash_State "0 = Off, 1 = Ready, 2 = Active";
|
||||
CM_ SG_ 802 LKAS_Right_Line_Visible "0 = Off, 1 = White, 2 = Green, 3 = Orange";
|
||||
CM_ SG_ 912 UNITS "0 = Metric, 1 = Imperial";
|
||||
CM_ SG_ 912 ICY_ROAD "1 = DASHLIGHT ON, 2 = WARNING, 3 = OFF";
|
||||
CM_ SG_ 940 Highbeam "01 = low beam, 11 = high beam";
|
||||
CM_ SG_ 940 FOG_LIGHTS2 "yellow fog light in the dash";
|
||||
CM_ SG_ 1677 Units "AU/EU: 1 = imperial, 3 = metric US: 3 = imperial, 4 = metric";
|
||||
|
||||
CM_ "subaru_global_2017.dbc starts here";
|
||||
|
||||
|
|
|
@ -218,7 +218,7 @@ 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
|
||||
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
|
||||
|
@ -243,9 +243,9 @@ CM_ SG_ 604 L_RCTA "Rear cross traffic alert, only when in R gear";
|
|||
CM_ SG_ 642 Counter "Affected by signals";
|
||||
CM_ SG_ 642 SEATBELT_FL "Driver seatbelt";
|
||||
CM_ SG_ 880 Steering_Voltage_Flat "receives later than 371";
|
||||
CM_ SG_ 977 UNITS "0 = Metric, 1 = Imperial";
|
||||
|
||||
VAL_ 328 Gear 0 "N" 1 "D" 2 "D" 3 "D" 4 "D" 5 "D" 6 "D" 14 "R" 15 "P";
|
||||
VAL_ 1745 Units 0 "Metric" 1 "Imperial";
|
||||
|
||||
CM_ "subaru_outback_2015.dbc starts here";
|
||||
|
||||
|
|
|
@ -218,7 +218,7 @@ 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
|
||||
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
|
||||
|
@ -243,9 +243,9 @@ CM_ SG_ 604 L_RCTA "Rear cross traffic alert, only when in R gear";
|
|||
CM_ SG_ 642 Counter "Affected by signals";
|
||||
CM_ SG_ 642 SEATBELT_FL "Driver seatbelt";
|
||||
CM_ SG_ 880 Steering_Voltage_Flat "receives later than 371";
|
||||
CM_ SG_ 977 UNITS "0 = Metric, 1 = Imperial";
|
||||
|
||||
VAL_ 328 Gear 0 "N" 1 "D" 2 "D" 3 "D" 4 "D" 5 "D" 6 "D" 14 "R" 15 "P";
|
||||
VAL_ 1745 Units 0 "Metric" 1 "Imperial";
|
||||
|
||||
CM_ "subaru_outback_2019.dbc starts here";
|
||||
|
||||
|
|
File diff suppressed because it is too large
Load Diff
|
@ -1,41 +1,6 @@
|
|||
CM_ "AUTOGENERATED FILE, DO NOT EDIT";
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 359 STEERING_IPAS_COMMA: 8 IPAS
|
||||
SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX
|
||||
SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant";
|
||||
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX
|
||||
SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX
|
||||
|
||||
CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss";
|
||||
|
||||
|
||||
CM_ "Imported file _toyota_2017.dbc starts here";
|
||||
VERSION ""
|
||||
|
||||
|
@ -265,6 +230,7 @@ BO_ 1556 STEERING_LEVERS: 8 XXX
|
|||
|
||||
BO_ 1568 SEATS_DOORS: 8 XXX
|
||||
SG_ METER_DIMMED : 38|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ PARKING_BRAKE : 60|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX
|
||||
|
@ -277,6 +243,7 @@ BO_ 1570 LIGHT_STALK: 8 SCM
|
|||
SG_ PARKING_LIGHT : 28|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ LOW_BEAM : 29|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ HIGH_BEAM : 30|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DAYTIME_RUNNING_LIGHT : 31|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 1161 RSA1: 8 FCM
|
||||
SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX
|
||||
|
@ -319,6 +286,11 @@ BO_ 1163 RSA3: 8 FCM
|
|||
SG_ OVSPVALM : 19|4@0+ (1,-5) [0|0] "" XXX
|
||||
SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX
|
||||
SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" XXX
|
||||
|
||||
BO_ 1571 CENTRAL_GATEWAY_UNIT: 8 CGW
|
||||
SG_ DOOR_LOCK_FEEDBACK_LIGHT : 15|1@0+ (1,0) [0|0] "" XXX
|
||||
SG_ KEYFOB_LOCKING_FEEDBACK_LIGHT : 61|1@0+ (1,0) [0|0] "" XXX
|
||||
SG_ KEYFOB_UNLOCKING_FEEDBACK_LIGHT : 62|1@0+ (1,0) [0|0] "" XXX
|
||||
|
||||
CM_ SG_ 36 ACCEL_Y "unit is tbd";
|
||||
CM_ SG_ 36 YAW_RATE "verify";
|
||||
|
@ -381,6 +353,41 @@ VAL_ 1162 SPLSGN3 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none";
|
|||
|
||||
CM_ "CHFFR_METRIC 37 STEER_ANGLE STEER_ANGLE 0.36 180";
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 359 STEERING_IPAS_COMMA: 8 IPAS
|
||||
SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX
|
||||
SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant";
|
||||
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX
|
||||
SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX
|
||||
|
||||
CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss";
|
||||
|
||||
CM_ "toyota_avalon_2017_pt.dbc starts here";
|
||||
|
||||
|
||||
|
|
|
@ -1,41 +1,6 @@
|
|||
CM_ "AUTOGENERATED FILE, DO NOT EDIT";
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 359 STEERING_IPAS_COMMA: 8 IPAS
|
||||
SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX
|
||||
SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant";
|
||||
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX
|
||||
SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX
|
||||
|
||||
CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss";
|
||||
|
||||
|
||||
CM_ "Imported file _toyota_2017.dbc starts here";
|
||||
VERSION ""
|
||||
|
||||
|
@ -265,6 +230,7 @@ BO_ 1556 STEERING_LEVERS: 8 XXX
|
|||
|
||||
BO_ 1568 SEATS_DOORS: 8 XXX
|
||||
SG_ METER_DIMMED : 38|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ PARKING_BRAKE : 60|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX
|
||||
|
@ -277,6 +243,7 @@ BO_ 1570 LIGHT_STALK: 8 SCM
|
|||
SG_ PARKING_LIGHT : 28|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ LOW_BEAM : 29|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ HIGH_BEAM : 30|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DAYTIME_RUNNING_LIGHT : 31|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 1161 RSA1: 8 FCM
|
||||
SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX
|
||||
|
@ -319,6 +286,11 @@ BO_ 1163 RSA3: 8 FCM
|
|||
SG_ OVSPVALM : 19|4@0+ (1,-5) [0|0] "" XXX
|
||||
SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX
|
||||
SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" XXX
|
||||
|
||||
BO_ 1571 CENTRAL_GATEWAY_UNIT: 8 CGW
|
||||
SG_ DOOR_LOCK_FEEDBACK_LIGHT : 15|1@0+ (1,0) [0|0] "" XXX
|
||||
SG_ KEYFOB_LOCKING_FEEDBACK_LIGHT : 61|1@0+ (1,0) [0|0] "" XXX
|
||||
SG_ KEYFOB_UNLOCKING_FEEDBACK_LIGHT : 62|1@0+ (1,0) [0|0] "" XXX
|
||||
|
||||
CM_ SG_ 36 ACCEL_Y "unit is tbd";
|
||||
CM_ SG_ 36 YAW_RATE "verify";
|
||||
|
@ -381,6 +353,41 @@ VAL_ 1162 SPLSGN3 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none";
|
|||
|
||||
CM_ "CHFFR_METRIC 37 STEER_ANGLE STEER_ANGLE 0.36 180";
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 359 STEERING_IPAS_COMMA: 8 IPAS
|
||||
SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX
|
||||
SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant";
|
||||
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX
|
||||
SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX
|
||||
|
||||
CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss";
|
||||
|
||||
CM_ "toyota_camry_hybrid_2018_pt.dbc starts here";
|
||||
|
||||
|
||||
|
|
|
@ -1,41 +1,6 @@
|
|||
CM_ "AUTOGENERATED FILE, DO NOT EDIT";
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 359 STEERING_IPAS_COMMA: 8 IPAS
|
||||
SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX
|
||||
SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant";
|
||||
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX
|
||||
SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX
|
||||
|
||||
CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss";
|
||||
|
||||
|
||||
CM_ "Imported file _toyota_2017.dbc starts here";
|
||||
VERSION ""
|
||||
|
||||
|
@ -265,6 +230,7 @@ BO_ 1556 STEERING_LEVERS: 8 XXX
|
|||
|
||||
BO_ 1568 SEATS_DOORS: 8 XXX
|
||||
SG_ METER_DIMMED : 38|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ PARKING_BRAKE : 60|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX
|
||||
|
@ -277,6 +243,7 @@ BO_ 1570 LIGHT_STALK: 8 SCM
|
|||
SG_ PARKING_LIGHT : 28|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ LOW_BEAM : 29|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ HIGH_BEAM : 30|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DAYTIME_RUNNING_LIGHT : 31|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 1161 RSA1: 8 FCM
|
||||
SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX
|
||||
|
@ -319,6 +286,11 @@ BO_ 1163 RSA3: 8 FCM
|
|||
SG_ OVSPVALM : 19|4@0+ (1,-5) [0|0] "" XXX
|
||||
SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX
|
||||
SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" XXX
|
||||
|
||||
BO_ 1571 CENTRAL_GATEWAY_UNIT: 8 CGW
|
||||
SG_ DOOR_LOCK_FEEDBACK_LIGHT : 15|1@0+ (1,0) [0|0] "" XXX
|
||||
SG_ KEYFOB_LOCKING_FEEDBACK_LIGHT : 61|1@0+ (1,0) [0|0] "" XXX
|
||||
SG_ KEYFOB_UNLOCKING_FEEDBACK_LIGHT : 62|1@0+ (1,0) [0|0] "" XXX
|
||||
|
||||
CM_ SG_ 36 ACCEL_Y "unit is tbd";
|
||||
CM_ SG_ 36 YAW_RATE "verify";
|
||||
|
@ -381,6 +353,41 @@ VAL_ 1162 SPLSGN3 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none";
|
|||
|
||||
CM_ "CHFFR_METRIC 37 STEER_ANGLE STEER_ANGLE 0.36 180";
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 359 STEERING_IPAS_COMMA: 8 IPAS
|
||||
SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX
|
||||
SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant";
|
||||
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX
|
||||
SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX
|
||||
|
||||
CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss";
|
||||
|
||||
CM_ "toyota_corolla_2017_pt.dbc starts here";
|
||||
|
||||
|
||||
|
|
|
@ -1,41 +1,6 @@
|
|||
CM_ "AUTOGENERATED FILE, DO NOT EDIT";
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 359 STEERING_IPAS_COMMA: 8 IPAS
|
||||
SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX
|
||||
SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant";
|
||||
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX
|
||||
SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX
|
||||
|
||||
CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss";
|
||||
|
||||
|
||||
CM_ "Imported file _toyota_2017.dbc starts here";
|
||||
VERSION ""
|
||||
|
||||
|
@ -265,6 +230,7 @@ BO_ 1556 STEERING_LEVERS: 8 XXX
|
|||
|
||||
BO_ 1568 SEATS_DOORS: 8 XXX
|
||||
SG_ METER_DIMMED : 38|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ PARKING_BRAKE : 60|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX
|
||||
|
@ -277,6 +243,7 @@ BO_ 1570 LIGHT_STALK: 8 SCM
|
|||
SG_ PARKING_LIGHT : 28|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ LOW_BEAM : 29|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ HIGH_BEAM : 30|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DAYTIME_RUNNING_LIGHT : 31|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 1161 RSA1: 8 FCM
|
||||
SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX
|
||||
|
@ -319,6 +286,11 @@ BO_ 1163 RSA3: 8 FCM
|
|||
SG_ OVSPVALM : 19|4@0+ (1,-5) [0|0] "" XXX
|
||||
SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX
|
||||
SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" XXX
|
||||
|
||||
BO_ 1571 CENTRAL_GATEWAY_UNIT: 8 CGW
|
||||
SG_ DOOR_LOCK_FEEDBACK_LIGHT : 15|1@0+ (1,0) [0|0] "" XXX
|
||||
SG_ KEYFOB_LOCKING_FEEDBACK_LIGHT : 61|1@0+ (1,0) [0|0] "" XXX
|
||||
SG_ KEYFOB_UNLOCKING_FEEDBACK_LIGHT : 62|1@0+ (1,0) [0|0] "" XXX
|
||||
|
||||
CM_ SG_ 36 ACCEL_Y "unit is tbd";
|
||||
CM_ SG_ 36 YAW_RATE "verify";
|
||||
|
@ -381,6 +353,41 @@ VAL_ 1162 SPLSGN3 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none";
|
|||
|
||||
CM_ "CHFFR_METRIC 37 STEER_ANGLE STEER_ANGLE 0.36 180";
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 359 STEERING_IPAS_COMMA: 8 IPAS
|
||||
SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX
|
||||
SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant";
|
||||
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX
|
||||
SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX
|
||||
|
||||
CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss";
|
||||
|
||||
CM_ "toyota_highlander_2017_pt.dbc starts here";
|
||||
|
||||
|
||||
|
|
|
@ -1,41 +1,6 @@
|
|||
CM_ "AUTOGENERATED FILE, DO NOT EDIT";
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 359 STEERING_IPAS_COMMA: 8 IPAS
|
||||
SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX
|
||||
SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant";
|
||||
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX
|
||||
SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX
|
||||
|
||||
CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss";
|
||||
|
||||
|
||||
CM_ "Imported file _toyota_2017.dbc starts here";
|
||||
VERSION ""
|
||||
|
||||
|
@ -265,6 +230,7 @@ BO_ 1556 STEERING_LEVERS: 8 XXX
|
|||
|
||||
BO_ 1568 SEATS_DOORS: 8 XXX
|
||||
SG_ METER_DIMMED : 38|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ PARKING_BRAKE : 60|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX
|
||||
|
@ -277,6 +243,7 @@ BO_ 1570 LIGHT_STALK: 8 SCM
|
|||
SG_ PARKING_LIGHT : 28|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ LOW_BEAM : 29|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ HIGH_BEAM : 30|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DAYTIME_RUNNING_LIGHT : 31|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 1161 RSA1: 8 FCM
|
||||
SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX
|
||||
|
@ -319,6 +286,11 @@ BO_ 1163 RSA3: 8 FCM
|
|||
SG_ OVSPVALM : 19|4@0+ (1,-5) [0|0] "" XXX
|
||||
SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX
|
||||
SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" XXX
|
||||
|
||||
BO_ 1571 CENTRAL_GATEWAY_UNIT: 8 CGW
|
||||
SG_ DOOR_LOCK_FEEDBACK_LIGHT : 15|1@0+ (1,0) [0|0] "" XXX
|
||||
SG_ KEYFOB_LOCKING_FEEDBACK_LIGHT : 61|1@0+ (1,0) [0|0] "" XXX
|
||||
SG_ KEYFOB_UNLOCKING_FEEDBACK_LIGHT : 62|1@0+ (1,0) [0|0] "" XXX
|
||||
|
||||
CM_ SG_ 36 ACCEL_Y "unit is tbd";
|
||||
CM_ SG_ 36 YAW_RATE "verify";
|
||||
|
@ -381,6 +353,41 @@ VAL_ 1162 SPLSGN3 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none";
|
|||
|
||||
CM_ "CHFFR_METRIC 37 STEER_ANGLE STEER_ANGLE 0.36 180";
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 359 STEERING_IPAS_COMMA: 8 IPAS
|
||||
SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX
|
||||
SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant";
|
||||
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX
|
||||
SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX
|
||||
|
||||
CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss";
|
||||
|
||||
CM_ "toyota_highlander_hybrid_2018_pt.dbc starts here";
|
||||
|
||||
|
||||
|
|
|
@ -1,71 +1,6 @@
|
|||
CM_ "AUTOGENERATED FILE, DO NOT EDIT";
|
||||
|
||||
|
||||
CM_ "Imported file _toyota_nodsu_common.dbc starts here";
|
||||
BO_ 401 STEERING_LTA: 8 XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SETME_X3 : 29|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ PERCENTAGE : 39|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SETME_X64 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ ANGLE : 55|8@0- (0.5,0) [0|255] "" XXX
|
||||
SG_ STEER_ANGLE_CMD : 15|16@0- (0.0573,0) [-540|540] "" XXX
|
||||
SG_ STEER_REQUEST : 25|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ BIT : 30|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ COUNTER : 6|6@0+ (1,0) [0|255] "" XXX
|
||||
SG_ STEER_REQUEST_2 : 0|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ SETME_X1 : 7|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 1014 BSM: 8 XXX
|
||||
SG_ L_ADJACENT : 0|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ L_APPROACHING : 8|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ R_ADJACENT : 1|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ R_APPROACHING : 10|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ ADJACENT_ENABLED : 7|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ APPROACHING_ENABLED : 15|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
CM_ SG_ 1014 L_ADJACENT "vehicle adjacent left side of car. enabled above 10mph, regardless of ADJACENT_ENABLED or APPROACHING_ENABLED";
|
||||
CM_ SG_ 1014 L_APPROACHING "vehicle approaching from left side of car. enabled above 10mph, regardless of ADJACENT_ENABLED or APPROACHING_ENABLED";
|
||||
CM_ SG_ 1014 R_ADJACENT "vehicle adjacent right side of car. enabled above 10mph, regardless of ADJACENT_ENABLED or APPROACHING_ENABLED";
|
||||
CM_ SG_ 1014 R_APPROACHING "vehicle approaching from right side of car. enabled above 10mph, regardless of ADJACENT_ENABLED or APPROACHING_ENABLED";
|
||||
CM_ SG_ 1014 ADJACENT_ENABLED "when BSM is enabled in settings, this is on along with APPROACHING_ENABLED. this controls bsm alert visibility";
|
||||
CM_ SG_ 1014 APPROACHING_ENABLED "when BSM is enabled in settings, this is on along with ADJACENT_ENABLED. this controls bsm alert visibility";
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 359 STEERING_IPAS_COMMA: 8 IPAS
|
||||
SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX
|
||||
SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant";
|
||||
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX
|
||||
SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX
|
||||
|
||||
CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss";
|
||||
|
||||
|
||||
CM_ "Imported file _toyota_2017.dbc starts here";
|
||||
VERSION ""
|
||||
|
||||
|
@ -295,6 +230,7 @@ BO_ 1556 STEERING_LEVERS: 8 XXX
|
|||
|
||||
BO_ 1568 SEATS_DOORS: 8 XXX
|
||||
SG_ METER_DIMMED : 38|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ PARKING_BRAKE : 60|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX
|
||||
|
@ -307,6 +243,7 @@ BO_ 1570 LIGHT_STALK: 8 SCM
|
|||
SG_ PARKING_LIGHT : 28|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ LOW_BEAM : 29|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ HIGH_BEAM : 30|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DAYTIME_RUNNING_LIGHT : 31|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 1161 RSA1: 8 FCM
|
||||
SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX
|
||||
|
@ -349,6 +286,11 @@ BO_ 1163 RSA3: 8 FCM
|
|||
SG_ OVSPVALM : 19|4@0+ (1,-5) [0|0] "" XXX
|
||||
SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX
|
||||
SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" XXX
|
||||
|
||||
BO_ 1571 CENTRAL_GATEWAY_UNIT: 8 CGW
|
||||
SG_ DOOR_LOCK_FEEDBACK_LIGHT : 15|1@0+ (1,0) [0|0] "" XXX
|
||||
SG_ KEYFOB_LOCKING_FEEDBACK_LIGHT : 61|1@0+ (1,0) [0|0] "" XXX
|
||||
SG_ KEYFOB_UNLOCKING_FEEDBACK_LIGHT : 62|1@0+ (1,0) [0|0] "" XXX
|
||||
|
||||
CM_ SG_ 36 ACCEL_Y "unit is tbd";
|
||||
CM_ SG_ 36 YAW_RATE "verify";
|
||||
|
@ -411,6 +353,71 @@ VAL_ 1162 SPLSGN3 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none";
|
|||
|
||||
CM_ "CHFFR_METRIC 37 STEER_ANGLE STEER_ANGLE 0.36 180";
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 359 STEERING_IPAS_COMMA: 8 IPAS
|
||||
SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX
|
||||
SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant";
|
||||
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX
|
||||
SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX
|
||||
|
||||
CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss";
|
||||
|
||||
|
||||
CM_ "Imported file _toyota_nodsu_common.dbc starts here";
|
||||
BO_ 401 STEERING_LTA: 8 XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SETME_X3 : 29|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ PERCENTAGE : 39|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SETME_X64 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ ANGLE : 55|8@0- (0.5,0) [0|255] "" XXX
|
||||
SG_ STEER_ANGLE_CMD : 15|16@0- (0.0573,0) [-540|540] "" XXX
|
||||
SG_ STEER_REQUEST : 25|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ BIT : 30|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ COUNTER : 6|6@0+ (1,0) [0|255] "" XXX
|
||||
SG_ STEER_REQUEST_2 : 0|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ SETME_X1 : 7|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 1014 BSM: 8 XXX
|
||||
SG_ L_ADJACENT : 0|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ L_APPROACHING : 8|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ R_ADJACENT : 1|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ R_APPROACHING : 10|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ ADJACENT_ENABLED : 7|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ APPROACHING_ENABLED : 15|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
CM_ SG_ 1014 L_ADJACENT "vehicle adjacent left side of car. enabled above 10mph, regardless of ADJACENT_ENABLED or APPROACHING_ENABLED";
|
||||
CM_ SG_ 1014 L_APPROACHING "vehicle approaching from left side of car. enabled above 10mph, regardless of ADJACENT_ENABLED or APPROACHING_ENABLED";
|
||||
CM_ SG_ 1014 R_ADJACENT "vehicle adjacent right side of car. enabled above 10mph, regardless of ADJACENT_ENABLED or APPROACHING_ENABLED";
|
||||
CM_ SG_ 1014 R_APPROACHING "vehicle approaching from right side of car. enabled above 10mph, regardless of ADJACENT_ENABLED or APPROACHING_ENABLED";
|
||||
CM_ SG_ 1014 ADJACENT_ENABLED "when BSM is enabled in settings, this is on along with APPROACHING_ENABLED. this controls bsm alert visibility";
|
||||
CM_ SG_ 1014 APPROACHING_ENABLED "when BSM is enabled in settings, this is on along with ADJACENT_ENABLED. this controls bsm alert visibility";
|
||||
|
||||
CM_ "toyota_nodsu_hybrid_pt.dbc starts here";
|
||||
|
||||
|
||||
|
|
|
@ -1,71 +1,6 @@
|
|||
CM_ "AUTOGENERATED FILE, DO NOT EDIT";
|
||||
|
||||
|
||||
CM_ "Imported file _toyota_nodsu_common.dbc starts here";
|
||||
BO_ 401 STEERING_LTA: 8 XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SETME_X3 : 29|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ PERCENTAGE : 39|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SETME_X64 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ ANGLE : 55|8@0- (0.5,0) [0|255] "" XXX
|
||||
SG_ STEER_ANGLE_CMD : 15|16@0- (0.0573,0) [-540|540] "" XXX
|
||||
SG_ STEER_REQUEST : 25|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ BIT : 30|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ COUNTER : 6|6@0+ (1,0) [0|255] "" XXX
|
||||
SG_ STEER_REQUEST_2 : 0|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ SETME_X1 : 7|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 1014 BSM: 8 XXX
|
||||
SG_ L_ADJACENT : 0|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ L_APPROACHING : 8|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ R_ADJACENT : 1|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ R_APPROACHING : 10|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ ADJACENT_ENABLED : 7|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ APPROACHING_ENABLED : 15|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
CM_ SG_ 1014 L_ADJACENT "vehicle adjacent left side of car. enabled above 10mph, regardless of ADJACENT_ENABLED or APPROACHING_ENABLED";
|
||||
CM_ SG_ 1014 L_APPROACHING "vehicle approaching from left side of car. enabled above 10mph, regardless of ADJACENT_ENABLED or APPROACHING_ENABLED";
|
||||
CM_ SG_ 1014 R_ADJACENT "vehicle adjacent right side of car. enabled above 10mph, regardless of ADJACENT_ENABLED or APPROACHING_ENABLED";
|
||||
CM_ SG_ 1014 R_APPROACHING "vehicle approaching from right side of car. enabled above 10mph, regardless of ADJACENT_ENABLED or APPROACHING_ENABLED";
|
||||
CM_ SG_ 1014 ADJACENT_ENABLED "when BSM is enabled in settings, this is on along with APPROACHING_ENABLED. this controls bsm alert visibility";
|
||||
CM_ SG_ 1014 APPROACHING_ENABLED "when BSM is enabled in settings, this is on along with ADJACENT_ENABLED. this controls bsm alert visibility";
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 359 STEERING_IPAS_COMMA: 8 IPAS
|
||||
SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX
|
||||
SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant";
|
||||
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX
|
||||
SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX
|
||||
|
||||
CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss";
|
||||
|
||||
|
||||
CM_ "Imported file _toyota_2017.dbc starts here";
|
||||
VERSION ""
|
||||
|
||||
|
@ -295,6 +230,7 @@ BO_ 1556 STEERING_LEVERS: 8 XXX
|
|||
|
||||
BO_ 1568 SEATS_DOORS: 8 XXX
|
||||
SG_ METER_DIMMED : 38|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ PARKING_BRAKE : 60|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX
|
||||
|
@ -307,6 +243,7 @@ BO_ 1570 LIGHT_STALK: 8 SCM
|
|||
SG_ PARKING_LIGHT : 28|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ LOW_BEAM : 29|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ HIGH_BEAM : 30|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DAYTIME_RUNNING_LIGHT : 31|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 1161 RSA1: 8 FCM
|
||||
SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX
|
||||
|
@ -349,6 +286,11 @@ BO_ 1163 RSA3: 8 FCM
|
|||
SG_ OVSPVALM : 19|4@0+ (1,-5) [0|0] "" XXX
|
||||
SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX
|
||||
SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" XXX
|
||||
|
||||
BO_ 1571 CENTRAL_GATEWAY_UNIT: 8 CGW
|
||||
SG_ DOOR_LOCK_FEEDBACK_LIGHT : 15|1@0+ (1,0) [0|0] "" XXX
|
||||
SG_ KEYFOB_LOCKING_FEEDBACK_LIGHT : 61|1@0+ (1,0) [0|0] "" XXX
|
||||
SG_ KEYFOB_UNLOCKING_FEEDBACK_LIGHT : 62|1@0+ (1,0) [0|0] "" XXX
|
||||
|
||||
CM_ SG_ 36 ACCEL_Y "unit is tbd";
|
||||
CM_ SG_ 36 YAW_RATE "verify";
|
||||
|
@ -411,6 +353,71 @@ VAL_ 1162 SPLSGN3 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none";
|
|||
|
||||
CM_ "CHFFR_METRIC 37 STEER_ANGLE STEER_ANGLE 0.36 180";
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 359 STEERING_IPAS_COMMA: 8 IPAS
|
||||
SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX
|
||||
SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant";
|
||||
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX
|
||||
SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX
|
||||
|
||||
CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss";
|
||||
|
||||
|
||||
CM_ "Imported file _toyota_nodsu_common.dbc starts here";
|
||||
BO_ 401 STEERING_LTA: 8 XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SETME_X3 : 29|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ PERCENTAGE : 39|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SETME_X64 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ ANGLE : 55|8@0- (0.5,0) [0|255] "" XXX
|
||||
SG_ STEER_ANGLE_CMD : 15|16@0- (0.0573,0) [-540|540] "" XXX
|
||||
SG_ STEER_REQUEST : 25|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ BIT : 30|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ COUNTER : 6|6@0+ (1,0) [0|255] "" XXX
|
||||
SG_ STEER_REQUEST_2 : 0|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ SETME_X1 : 7|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 1014 BSM: 8 XXX
|
||||
SG_ L_ADJACENT : 0|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ L_APPROACHING : 8|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ R_ADJACENT : 1|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ R_APPROACHING : 10|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ ADJACENT_ENABLED : 7|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ APPROACHING_ENABLED : 15|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
CM_ SG_ 1014 L_ADJACENT "vehicle adjacent left side of car. enabled above 10mph, regardless of ADJACENT_ENABLED or APPROACHING_ENABLED";
|
||||
CM_ SG_ 1014 L_APPROACHING "vehicle approaching from left side of car. enabled above 10mph, regardless of ADJACENT_ENABLED or APPROACHING_ENABLED";
|
||||
CM_ SG_ 1014 R_ADJACENT "vehicle adjacent right side of car. enabled above 10mph, regardless of ADJACENT_ENABLED or APPROACHING_ENABLED";
|
||||
CM_ SG_ 1014 R_APPROACHING "vehicle approaching from right side of car. enabled above 10mph, regardless of ADJACENT_ENABLED or APPROACHING_ENABLED";
|
||||
CM_ SG_ 1014 ADJACENT_ENABLED "when BSM is enabled in settings, this is on along with APPROACHING_ENABLED. this controls bsm alert visibility";
|
||||
CM_ SG_ 1014 APPROACHING_ENABLED "when BSM is enabled in settings, this is on along with ADJACENT_ENABLED. this controls bsm alert visibility";
|
||||
|
||||
CM_ "toyota_nodsu_pt.dbc starts here";
|
||||
|
||||
|
||||
|
|
|
@ -1,41 +1,6 @@
|
|||
CM_ "AUTOGENERATED FILE, DO NOT EDIT";
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 359 STEERING_IPAS_COMMA: 8 IPAS
|
||||
SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX
|
||||
SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant";
|
||||
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX
|
||||
SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX
|
||||
|
||||
CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss";
|
||||
|
||||
|
||||
CM_ "Imported file _toyota_2017.dbc starts here";
|
||||
VERSION ""
|
||||
|
||||
|
@ -265,6 +230,7 @@ BO_ 1556 STEERING_LEVERS: 8 XXX
|
|||
|
||||
BO_ 1568 SEATS_DOORS: 8 XXX
|
||||
SG_ METER_DIMMED : 38|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ PARKING_BRAKE : 60|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX
|
||||
|
@ -277,6 +243,7 @@ BO_ 1570 LIGHT_STALK: 8 SCM
|
|||
SG_ PARKING_LIGHT : 28|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ LOW_BEAM : 29|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ HIGH_BEAM : 30|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DAYTIME_RUNNING_LIGHT : 31|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 1161 RSA1: 8 FCM
|
||||
SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX
|
||||
|
@ -319,6 +286,11 @@ BO_ 1163 RSA3: 8 FCM
|
|||
SG_ OVSPVALM : 19|4@0+ (1,-5) [0|0] "" XXX
|
||||
SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX
|
||||
SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" XXX
|
||||
|
||||
BO_ 1571 CENTRAL_GATEWAY_UNIT: 8 CGW
|
||||
SG_ DOOR_LOCK_FEEDBACK_LIGHT : 15|1@0+ (1,0) [0|0] "" XXX
|
||||
SG_ KEYFOB_LOCKING_FEEDBACK_LIGHT : 61|1@0+ (1,0) [0|0] "" XXX
|
||||
SG_ KEYFOB_UNLOCKING_FEEDBACK_LIGHT : 62|1@0+ (1,0) [0|0] "" XXX
|
||||
|
||||
CM_ SG_ 36 ACCEL_Y "unit is tbd";
|
||||
CM_ SG_ 36 YAW_RATE "verify";
|
||||
|
@ -381,6 +353,41 @@ VAL_ 1162 SPLSGN3 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none";
|
|||
|
||||
CM_ "CHFFR_METRIC 37 STEER_ANGLE STEER_ANGLE 0.36 180";
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 359 STEERING_IPAS_COMMA: 8 IPAS
|
||||
SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX
|
||||
SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant";
|
||||
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX
|
||||
SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX
|
||||
|
||||
CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss";
|
||||
|
||||
CM_ "toyota_prius_2017_pt.dbc starts here";
|
||||
|
||||
|
||||
|
|
|
@ -1,41 +1,6 @@
|
|||
CM_ "AUTOGENERATED FILE, DO NOT EDIT";
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 359 STEERING_IPAS_COMMA: 8 IPAS
|
||||
SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX
|
||||
SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant";
|
||||
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX
|
||||
SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX
|
||||
|
||||
CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss";
|
||||
|
||||
|
||||
CM_ "Imported file _toyota_2017.dbc starts here";
|
||||
VERSION ""
|
||||
|
||||
|
@ -265,6 +230,7 @@ BO_ 1556 STEERING_LEVERS: 8 XXX
|
|||
|
||||
BO_ 1568 SEATS_DOORS: 8 XXX
|
||||
SG_ METER_DIMMED : 38|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ PARKING_BRAKE : 60|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX
|
||||
|
@ -277,6 +243,7 @@ BO_ 1570 LIGHT_STALK: 8 SCM
|
|||
SG_ PARKING_LIGHT : 28|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ LOW_BEAM : 29|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ HIGH_BEAM : 30|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DAYTIME_RUNNING_LIGHT : 31|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 1161 RSA1: 8 FCM
|
||||
SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX
|
||||
|
@ -319,6 +286,11 @@ BO_ 1163 RSA3: 8 FCM
|
|||
SG_ OVSPVALM : 19|4@0+ (1,-5) [0|0] "" XXX
|
||||
SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX
|
||||
SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" XXX
|
||||
|
||||
BO_ 1571 CENTRAL_GATEWAY_UNIT: 8 CGW
|
||||
SG_ DOOR_LOCK_FEEDBACK_LIGHT : 15|1@0+ (1,0) [0|0] "" XXX
|
||||
SG_ KEYFOB_LOCKING_FEEDBACK_LIGHT : 61|1@0+ (1,0) [0|0] "" XXX
|
||||
SG_ KEYFOB_UNLOCKING_FEEDBACK_LIGHT : 62|1@0+ (1,0) [0|0] "" XXX
|
||||
|
||||
CM_ SG_ 36 ACCEL_Y "unit is tbd";
|
||||
CM_ SG_ 36 YAW_RATE "verify";
|
||||
|
@ -381,6 +353,41 @@ VAL_ 1162 SPLSGN3 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none";
|
|||
|
||||
CM_ "CHFFR_METRIC 37 STEER_ANGLE STEER_ANGLE 0.36 180";
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 359 STEERING_IPAS_COMMA: 8 IPAS
|
||||
SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX
|
||||
SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant";
|
||||
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX
|
||||
SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX
|
||||
|
||||
CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss";
|
||||
|
||||
CM_ "toyota_rav4_2017_pt.dbc starts here";
|
||||
|
||||
|
||||
|
|
|
@ -1,41 +1,6 @@
|
|||
CM_ "AUTOGENERATED FILE, DO NOT EDIT";
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 359 STEERING_IPAS_COMMA: 8 IPAS
|
||||
SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX
|
||||
SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant";
|
||||
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX
|
||||
SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX
|
||||
|
||||
CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss";
|
||||
|
||||
|
||||
CM_ "Imported file _toyota_2017.dbc starts here";
|
||||
VERSION ""
|
||||
|
||||
|
@ -265,6 +230,7 @@ BO_ 1556 STEERING_LEVERS: 8 XXX
|
|||
|
||||
BO_ 1568 SEATS_DOORS: 8 XXX
|
||||
SG_ METER_DIMMED : 38|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ PARKING_BRAKE : 60|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX
|
||||
|
@ -277,6 +243,7 @@ BO_ 1570 LIGHT_STALK: 8 SCM
|
|||
SG_ PARKING_LIGHT : 28|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ LOW_BEAM : 29|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ HIGH_BEAM : 30|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DAYTIME_RUNNING_LIGHT : 31|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 1161 RSA1: 8 FCM
|
||||
SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX
|
||||
|
@ -319,6 +286,11 @@ BO_ 1163 RSA3: 8 FCM
|
|||
SG_ OVSPVALM : 19|4@0+ (1,-5) [0|0] "" XXX
|
||||
SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX
|
||||
SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" XXX
|
||||
|
||||
BO_ 1571 CENTRAL_GATEWAY_UNIT: 8 CGW
|
||||
SG_ DOOR_LOCK_FEEDBACK_LIGHT : 15|1@0+ (1,0) [0|0] "" XXX
|
||||
SG_ KEYFOB_LOCKING_FEEDBACK_LIGHT : 61|1@0+ (1,0) [0|0] "" XXX
|
||||
SG_ KEYFOB_UNLOCKING_FEEDBACK_LIGHT : 62|1@0+ (1,0) [0|0] "" XXX
|
||||
|
||||
CM_ SG_ 36 ACCEL_Y "unit is tbd";
|
||||
CM_ SG_ 36 YAW_RATE "verify";
|
||||
|
@ -381,6 +353,41 @@ VAL_ 1162 SPLSGN3 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none";
|
|||
|
||||
CM_ "CHFFR_METRIC 37 STEER_ANGLE STEER_ANGLE 0.36 180";
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 359 STEERING_IPAS_COMMA: 8 IPAS
|
||||
SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX
|
||||
SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant";
|
||||
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX
|
||||
SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX
|
||||
|
||||
CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss";
|
||||
|
||||
CM_ "toyota_rav4_hybrid_2017_pt.dbc starts here";
|
||||
|
||||
|
||||
|
|
|
@ -1,41 +1,6 @@
|
|||
CM_ "AUTOGENERATED FILE, DO NOT EDIT";
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 359 STEERING_IPAS_COMMA: 8 IPAS
|
||||
SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX
|
||||
SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant";
|
||||
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX
|
||||
SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX
|
||||
|
||||
CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss";
|
||||
|
||||
|
||||
CM_ "Imported file _toyota_2017.dbc starts here";
|
||||
VERSION ""
|
||||
|
||||
|
@ -265,6 +230,7 @@ BO_ 1556 STEERING_LEVERS: 8 XXX
|
|||
|
||||
BO_ 1568 SEATS_DOORS: 8 XXX
|
||||
SG_ METER_DIMMED : 38|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ PARKING_BRAKE : 60|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX
|
||||
|
@ -277,6 +243,7 @@ BO_ 1570 LIGHT_STALK: 8 SCM
|
|||
SG_ PARKING_LIGHT : 28|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ LOW_BEAM : 29|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ HIGH_BEAM : 30|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DAYTIME_RUNNING_LIGHT : 31|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 1161 RSA1: 8 FCM
|
||||
SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX
|
||||
|
@ -319,6 +286,11 @@ BO_ 1163 RSA3: 8 FCM
|
|||
SG_ OVSPVALM : 19|4@0+ (1,-5) [0|0] "" XXX
|
||||
SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX
|
||||
SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" XXX
|
||||
|
||||
BO_ 1571 CENTRAL_GATEWAY_UNIT: 8 CGW
|
||||
SG_ DOOR_LOCK_FEEDBACK_LIGHT : 15|1@0+ (1,0) [0|0] "" XXX
|
||||
SG_ KEYFOB_LOCKING_FEEDBACK_LIGHT : 61|1@0+ (1,0) [0|0] "" XXX
|
||||
SG_ KEYFOB_UNLOCKING_FEEDBACK_LIGHT : 62|1@0+ (1,0) [0|0] "" XXX
|
||||
|
||||
CM_ SG_ 36 ACCEL_Y "unit is tbd";
|
||||
CM_ SG_ 36 YAW_RATE "verify";
|
||||
|
@ -381,6 +353,41 @@ VAL_ 1162 SPLSGN3 15 "conditional blank" 4 "wet road" 5 "rain" 0 "none";
|
|||
|
||||
CM_ "CHFFR_METRIC 37 STEER_ANGLE STEER_ANGLE 0.36 180";
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here";
|
||||
BO_ 359 STEERING_IPAS_COMMA: 8 IPAS
|
||||
SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX
|
||||
SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00_1 : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
CM_ "BO_ STEERING_IPAS_COMMA: Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant";
|
||||
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.159375,-75.555) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.159375,-151.111) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" INTERCEPTOR
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.159375,-75.555) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.159375,-151.111) [0|1] "" EON
|
||||
SG_ STATE : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER_PEDAL : 35|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ CHECKSUM_PEDAL : 47|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
BO_ 35 SECONDARY_STEER_ANGLE: 8 XXX
|
||||
SG_ ZORRO_STEER : 7|24@0- (0.004901594652,0) [-500|500] "" XXX
|
||||
|
||||
CM_ "BO_ SECONDARY_STEER_ANGLE: ZSS is a high-precision steering angle sensor that can replace the lower resolution sensor in most TSS1 Toyotas. Learn more: https://github.com/commaai/openpilot/wiki/Toyota-Lexus#zorro-steering-sensor-zss";
|
||||
|
||||
CM_ "toyota_sienna_xle_2018_pt.dbc starts here";
|
||||
|
||||
|
||||
|
|
|
@ -703,6 +703,14 @@ void tick_handler(void) {
|
|||
siren_countdown -= 1U;
|
||||
}
|
||||
|
||||
if (controls_allowed) {
|
||||
controls_allowed_countdown = 30U;
|
||||
} else if (controls_allowed_countdown > 0U) {
|
||||
controls_allowed_countdown -= 1U;
|
||||
} else {
|
||||
|
||||
}
|
||||
|
||||
if (!heartbeat_disabled) {
|
||||
// if the heartbeat has been gone for a while, go to SILENT safety mode and enter power save
|
||||
if (heartbeat_counter >= (check_started() ? HEARTBEAT_IGNITION_CNT_ON : HEARTBEAT_IGNITION_CNT_OFF)) {
|
||||
|
@ -710,8 +718,9 @@ void tick_handler(void) {
|
|||
puth(heartbeat_counter);
|
||||
puts(" seconds. Safety is set to SILENT mode.\n");
|
||||
|
||||
if (controls_allowed) {
|
||||
if (controls_allowed_countdown > 0U) {
|
||||
siren_countdown = 5U;
|
||||
controls_allowed_countdown = 0U;
|
||||
}
|
||||
|
||||
// set flag to indicate the heartbeat was lost
|
||||
|
@ -757,7 +766,7 @@ void tick_handler(void) {
|
|||
ignition_can_cnt += 1U;
|
||||
|
||||
// synchronous safety check
|
||||
safety_tick(current_hooks);
|
||||
safety_tick(current_rx_checks);
|
||||
}
|
||||
|
||||
loop_counter++;
|
||||
|
|
|
@ -12,10 +12,16 @@ void pwm_set(TIM_TypeDef *TIM, uint8_t channel, uint8_t percentage);
|
|||
uint8_t hw_type = 0;
|
||||
const board *current_board;
|
||||
bool is_enumerated = 0;
|
||||
uint32_t heartbeat_counter = 0;
|
||||
uint32_t uptime_cnt = 0;
|
||||
bool heartbeat_lost = false;
|
||||
bool heartbeat_disabled = false;
|
||||
bool siren_enabled = false;
|
||||
uint32_t siren_countdown = 0;
|
||||
bool green_led_enabled = false;
|
||||
|
||||
// heartbeat state
|
||||
uint32_t heartbeat_counter = 0;
|
||||
bool heartbeat_lost = false;
|
||||
bool heartbeat_disabled = false; // set over USB
|
||||
|
||||
// siren state
|
||||
bool siren_enabled = false;
|
||||
uint32_t siren_countdown = 0; // siren plays while countdown > 0
|
||||
uint32_t controls_allowed_countdown = 0;
|
||||
|
||||
|
|
|
@ -43,8 +43,9 @@
|
|||
uint16_t current_safety_mode = SAFETY_SILENT;
|
||||
int16_t current_safety_param = 0;
|
||||
const safety_hooks *current_hooks = &nooutput_hooks;
|
||||
const addr_checks *current_rx_checks = &default_rx_checks;
|
||||
|
||||
int safety_rx_hook(CAN_FIFOMailBox_TypeDef *to_push){
|
||||
int safety_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
|
||||
return current_hooks->rx(to_push);
|
||||
}
|
||||
|
||||
|
@ -52,7 +53,7 @@ int safety_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) {
|
|||
return current_hooks->tx(to_send);
|
||||
}
|
||||
|
||||
int safety_tx_lin_hook(int lin_num, uint8_t *data, int len){
|
||||
int safety_tx_lin_hook(int lin_num, uint8_t *data, int len) {
|
||||
return current_hooks->tx_lin(lin_num, data, len);
|
||||
}
|
||||
|
||||
|
@ -126,16 +127,16 @@ int get_addr_check_index(CAN_FIFOMailBox_TypeDef *to_push, AddrCheckStruct addr_
|
|||
}
|
||||
|
||||
// 1Hz safety function called by main. Now just a check for lagging safety messages
|
||||
void safety_tick(const safety_hooks *hooks) {
|
||||
void safety_tick(const addr_checks *rx_checks) {
|
||||
uint32_t ts = microsecond_timer_get();
|
||||
if (hooks->addr_check != NULL) {
|
||||
for (int i=0; i < hooks->addr_check_len; i++) {
|
||||
uint32_t elapsed_time = get_ts_elapsed(ts, hooks->addr_check[i].last_timestamp);
|
||||
if (rx_checks != NULL) {
|
||||
for (int i=0; i < rx_checks->len; i++) {
|
||||
uint32_t elapsed_time = get_ts_elapsed(ts, rx_checks->check[i].last_timestamp);
|
||||
// lag threshold is max of: 1s and MAX_MISSED_MSGS * expected timestep.
|
||||
// Quite conservative to not risk false triggers.
|
||||
// 2s of lag is worse case, since the function is called at 1Hz
|
||||
bool lagging = elapsed_time > MAX(hooks->addr_check[i].msg[hooks->addr_check[i].index].expected_timestep * MAX_MISSED_MSGS, 1e6);
|
||||
hooks->addr_check[i].lagging = lagging;
|
||||
bool lagging = elapsed_time > MAX(rx_checks->check[i].msg[rx_checks->check[i].index].expected_timestep * MAX_MISSED_MSGS, 1e6);
|
||||
rx_checks->check[i].lagging = lagging;
|
||||
if (lagging) {
|
||||
controls_allowed = 0;
|
||||
}
|
||||
|
@ -171,34 +172,33 @@ void update_addr_timestamp(AddrCheckStruct addr_list[], int index) {
|
|||
}
|
||||
|
||||
bool addr_safety_check(CAN_FIFOMailBox_TypeDef *to_push,
|
||||
AddrCheckStruct *rx_checks,
|
||||
const int rx_checks_len,
|
||||
const addr_checks *rx_checks,
|
||||
uint8_t (*get_checksum)(CAN_FIFOMailBox_TypeDef *to_push),
|
||||
uint8_t (*compute_checksum)(CAN_FIFOMailBox_TypeDef *to_push),
|
||||
uint8_t (*get_counter)(CAN_FIFOMailBox_TypeDef *to_push)) {
|
||||
|
||||
int index = get_addr_check_index(to_push, rx_checks, rx_checks_len);
|
||||
update_addr_timestamp(rx_checks, index);
|
||||
int index = get_addr_check_index(to_push, rx_checks->check, rx_checks->len);
|
||||
update_addr_timestamp(rx_checks->check, index);
|
||||
|
||||
if (index != -1) {
|
||||
// checksum check
|
||||
if ((get_checksum != NULL) && (compute_checksum != NULL) && rx_checks[index].msg[rx_checks[index].index].check_checksum) {
|
||||
if ((get_checksum != NULL) && (compute_checksum != NULL) && rx_checks->check[index].msg[rx_checks->check[index].index].check_checksum) {
|
||||
uint8_t checksum = get_checksum(to_push);
|
||||
uint8_t checksum_comp = compute_checksum(to_push);
|
||||
rx_checks[index].valid_checksum = checksum_comp == checksum;
|
||||
rx_checks->check[index].valid_checksum = checksum_comp == checksum;
|
||||
} else {
|
||||
rx_checks[index].valid_checksum = true;
|
||||
rx_checks->check[index].valid_checksum = true;
|
||||
}
|
||||
|
||||
// counter check (max_counter == 0 means skip check)
|
||||
if ((get_counter != NULL) && (rx_checks[index].msg[rx_checks[index].index].max_counter > 0U)) {
|
||||
if ((get_counter != NULL) && (rx_checks->check[index].msg[rx_checks->check[index].index].max_counter > 0U)) {
|
||||
uint8_t counter = get_counter(to_push);
|
||||
update_counter(rx_checks, index, counter);
|
||||
update_counter(rx_checks->check, index, counter);
|
||||
} else {
|
||||
rx_checks[index].wrong_counters = 0U;
|
||||
rx_checks->check[index].wrong_counters = 0U;
|
||||
}
|
||||
}
|
||||
return is_msg_valid(rx_checks, index);
|
||||
return is_msg_valid(rx_checks->check, index);
|
||||
}
|
||||
|
||||
void generic_rx_checks(bool stock_ecu_detected) {
|
||||
|
@ -296,15 +296,14 @@ int set_safety_hooks(uint16_t mode, int16_t param) {
|
|||
current_safety_param = param;
|
||||
set_status = 0; // set
|
||||
}
|
||||
|
||||
// reset message index and seen flags in addr struct
|
||||
for (int j = 0; j < safety_hook_registry[i].hooks->addr_check_len; j++) {
|
||||
safety_hook_registry[i].hooks->addr_check[j].index = 0;
|
||||
safety_hook_registry[i].hooks->addr_check[j].msg_seen = false;
|
||||
}
|
||||
}
|
||||
if ((set_status == 0) && (current_hooks->init != NULL)) {
|
||||
current_hooks->init(param);
|
||||
current_rx_checks = current_hooks->init(param);
|
||||
// reset message index and seen flags in addr struct
|
||||
for (int j = 0; j < current_rx_checks->len; j++) {
|
||||
current_rx_checks->check[j].index = 0;
|
||||
current_rx_checks->check[j].msg_seen = false;
|
||||
}
|
||||
}
|
||||
return set_status;
|
||||
}
|
||||
|
|
|
@ -8,14 +8,15 @@ const int CHRYSLER_GAS_THRSLD = 30; // 7% more than 2m/s
|
|||
const int CHRYSLER_STANDSTILL_THRSLD = 10; // about 1m/s
|
||||
const CanMsg CHRYSLER_TX_MSGS[] = {{571, 0, 3}, {658, 0, 6}, {678, 0, 8}};
|
||||
|
||||
AddrCheckStruct chrysler_rx_checks[] = {
|
||||
AddrCheckStruct chrysler_addr_checks[] = {
|
||||
{.msg = {{544, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 10000U}, { 0 }, { 0 }}},
|
||||
{.msg = {{514, 0, 8, .check_checksum = false, .max_counter = 0U, .expected_timestep = 10000U}, { 0 }, { 0 }}},
|
||||
{.msg = {{500, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}, { 0 }, { 0 }}},
|
||||
{.msg = {{308, 0, 8, .check_checksum = false, .max_counter = 15U, .expected_timestep = 20000U}, { 0 }, { 0 }}},
|
||||
{.msg = {{320, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}, { 0 }, { 0 }}},
|
||||
};
|
||||
const int CHRYSLER_RX_CHECK_LEN = sizeof(chrysler_rx_checks) / sizeof(chrysler_rx_checks[0]);
|
||||
#define CHRYSLER_ADDR_CHECK_LEN (sizeof(chrysler_addr_checks) / sizeof(chrysler_addr_checks[0]))
|
||||
addr_checks chrysler_rx_checks = {chrysler_addr_checks, CHRYSLER_ADDR_CHECK_LEN};
|
||||
|
||||
static uint8_t chrysler_get_checksum(CAN_FIFOMailBox_TypeDef *to_push) {
|
||||
int checksum_byte = GET_LEN(to_push) - 1;
|
||||
|
@ -62,7 +63,7 @@ static uint8_t chrysler_get_counter(CAN_FIFOMailBox_TypeDef *to_push) {
|
|||
|
||||
static int chrysler_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
|
||||
|
||||
bool valid = addr_safety_check(to_push, chrysler_rx_checks, CHRYSLER_RX_CHECK_LEN,
|
||||
bool valid = addr_safety_check(to_push, &chrysler_rx_checks,
|
||||
chrysler_get_checksum, chrysler_compute_checksum,
|
||||
chrysler_get_counter);
|
||||
|
||||
|
@ -203,13 +204,17 @@ static int chrysler_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) {
|
|||
return bus_fwd;
|
||||
}
|
||||
|
||||
static const addr_checks* chrysler_init(int16_t param) {
|
||||
UNUSED(param);
|
||||
controls_allowed = false;
|
||||
relay_malfunction_reset();
|
||||
return &chrysler_rx_checks;
|
||||
}
|
||||
|
||||
const safety_hooks chrysler_hooks = {
|
||||
.init = nooutput_init,
|
||||
.init = chrysler_init,
|
||||
.rx = chrysler_rx_hook,
|
||||
.tx = chrysler_tx_hook,
|
||||
.tx_lin = nooutput_tx_lin_hook,
|
||||
.fwd = chrysler_fwd_hook,
|
||||
.addr_check = chrysler_rx_checks,
|
||||
.addr_check_len = sizeof(chrysler_rx_checks) / sizeof(chrysler_rx_checks[0]),
|
||||
};
|
||||
|
|
|
@ -1,3 +1,8 @@
|
|||
const addr_checks default_rx_checks = {
|
||||
.check = NULL,
|
||||
.len = 0,
|
||||
};
|
||||
|
||||
int default_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
|
||||
UNUSED(to_push);
|
||||
return true;
|
||||
|
@ -5,10 +10,11 @@ int default_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
|
|||
|
||||
// *** no output safety mode ***
|
||||
|
||||
static void nooutput_init(int16_t param) {
|
||||
static const addr_checks* nooutput_init(int16_t param) {
|
||||
UNUSED(param);
|
||||
controls_allowed = false;
|
||||
relay_malfunction_reset();
|
||||
return &default_rx_checks;
|
||||
}
|
||||
|
||||
static int nooutput_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) {
|
||||
|
@ -39,10 +45,11 @@ const safety_hooks nooutput_hooks = {
|
|||
|
||||
// *** all output safety mode ***
|
||||
|
||||
static void alloutput_init(int16_t param) {
|
||||
static const addr_checks* alloutput_init(int16_t param) {
|
||||
UNUSED(param);
|
||||
controls_allowed = true;
|
||||
relay_malfunction_reset();
|
||||
return &default_rx_checks;
|
||||
}
|
||||
|
||||
static int alloutput_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) {
|
||||
|
|
|
@ -24,20 +24,19 @@ const CanMsg GM_TX_MSGS[] = {{384, 0, 4}, {1033, 0, 7}, {1034, 0, 7}, {715, 0, 8
|
|||
{0x104c006c, 3, 3}, {0x10400060, 3, 5}}; // gmlan
|
||||
|
||||
// TODO: do checksum and counter checks. Add correct timestep, 0.1s for now.
|
||||
|
||||
AddrCheckStruct gm_rx_checks[] = {
|
||||
AddrCheckStruct gm_addr_checks[] = {
|
||||
{.msg = {{388, 0, 8, .expected_timestep = 100000U}, { 0 }, { 0 }}},
|
||||
{.msg = {{842, 0, 5, .expected_timestep = 100000U}, { 0 }, { 0 }}},
|
||||
{.msg = {{481, 0, 7, .expected_timestep = 100000U}, { 0 }, { 0 }}},
|
||||
{.msg = {{241, 0, 6, .expected_timestep = 100000U}, { 0 }, { 0 }}},
|
||||
{.msg = {{417, 0, 7, .expected_timestep = 100000U}, { 0 }, { 0 }}},
|
||||
};
|
||||
const int GM_RX_CHECK_LEN = sizeof(gm_rx_checks) / sizeof(gm_rx_checks[0]);
|
||||
#define GM_RX_CHECK_LEN (sizeof(gm_addr_checks) / sizeof(gm_addr_checks[0]))
|
||||
addr_checks gm_rx_checks = {gm_addr_checks, GM_RX_CHECK_LEN};
|
||||
|
||||
static int gm_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
|
||||
|
||||
bool valid = addr_safety_check(to_push, gm_rx_checks, GM_RX_CHECK_LEN,
|
||||
NULL, NULL, NULL);
|
||||
bool valid = addr_safety_check(to_push, &gm_rx_checks, NULL, NULL, NULL);
|
||||
|
||||
if (valid && (GET_BUS(to_push) == 0)) {
|
||||
int addr = GET_ADDR(to_push);
|
||||
|
@ -209,13 +208,17 @@ static int gm_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) {
|
|||
return tx;
|
||||
}
|
||||
|
||||
static const addr_checks* gm_init(int16_t param) {
|
||||
UNUSED(param);
|
||||
controls_allowed = false;
|
||||
relay_malfunction_reset();
|
||||
return &gm_rx_checks;
|
||||
}
|
||||
|
||||
const safety_hooks gm_hooks = {
|
||||
.init = nooutput_init,
|
||||
.init = gm_init,
|
||||
.rx = gm_rx_hook,
|
||||
.tx = gm_tx_hook,
|
||||
.tx_lin = nooutput_tx_lin_hook,
|
||||
.fwd = default_fwd_hook,
|
||||
.addr_check = gm_rx_checks,
|
||||
.addr_check_len = sizeof(gm_rx_checks) / sizeof(gm_rx_checks[0]),
|
||||
};
|
||||
|
|
|
@ -25,22 +25,22 @@ const int HONDA_BOSCH_GAS_MAX = 2000;
|
|||
const int HONDA_BOSCH_ACCEL_MIN = -350; // max braking == -3.5m/s2
|
||||
|
||||
// Nidec and Bosch giraffe have pt on bus 0
|
||||
AddrCheckStruct honda_rx_checks[] = {
|
||||
AddrCheckStruct honda_addr_checks[] = {
|
||||
{.msg = {{0x1A6, 0, 8, .check_checksum = true, .max_counter = 3U, .expected_timestep = 40000U},
|
||||
{0x296, 0, 4, .check_checksum = true, .max_counter = 3U, .expected_timestep = 40000U},{ 0 }}},
|
||||
{.msg = {{0x158, 0, 8, .check_checksum = true, .max_counter = 3U, .expected_timestep = 10000U}, { 0 }, { 0 }}},
|
||||
{.msg = {{0x17C, 0, 8, .check_checksum = true, .max_counter = 3U, .expected_timestep = 10000U}, { 0 }, { 0 }}},
|
||||
};
|
||||
const int HONDA_RX_CHECKS_LEN = sizeof(honda_rx_checks) / sizeof(honda_rx_checks[0]);
|
||||
#define HONDA_ADDR_CHECKS_LEN (sizeof(honda_addr_checks) / sizeof(honda_addr_checks[0]))
|
||||
|
||||
// Bosch harness has pt on bus 1
|
||||
AddrCheckStruct honda_bh_rx_checks[] = {
|
||||
AddrCheckStruct honda_bh_addr_checks[] = {
|
||||
{.msg = {{0x296, 1, 4, .check_checksum = true, .max_counter = 3U, .expected_timestep = 40000U}, { 0 }, { 0 }}},
|
||||
{.msg = {{0x158, 1, 8, .check_checksum = true, .max_counter = 3U, .expected_timestep = 10000U}, { 0 }, { 0 }}},
|
||||
{.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}, { 0 }}},
|
||||
};
|
||||
const int HONDA_BH_RX_CHECKS_LEN = sizeof(honda_bh_rx_checks) / sizeof(honda_bh_rx_checks[0]);
|
||||
#define HONDA_BH_ADDR_CHECKS_LEN (sizeof(honda_bh_addr_checks) / sizeof(honda_bh_addr_checks[0]))
|
||||
|
||||
const uint16_t HONDA_PARAM_ALT_BRAKE = 1;
|
||||
const uint16_t HONDA_PARAM_BOSCH_LONG = 2;
|
||||
|
@ -50,6 +50,7 @@ bool honda_alt_brake_msg = false;
|
|||
bool honda_fwd_brake = false;
|
||||
bool honda_bosch_long = false;
|
||||
enum {HONDA_N_HW, HONDA_BG_HW, HONDA_BH_HW} honda_hw = HONDA_N_HW;
|
||||
addr_checks honda_rx_checks = {honda_addr_checks, HONDA_ADDR_CHECKS_LEN};
|
||||
|
||||
|
||||
static uint8_t honda_get_checksum(CAN_FIFOMailBox_TypeDef *to_push) {
|
||||
|
@ -81,14 +82,8 @@ static uint8_t honda_get_counter(CAN_FIFOMailBox_TypeDef *to_push) {
|
|||
|
||||
static int honda_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
|
||||
|
||||
bool valid;
|
||||
if (honda_hw == HONDA_BH_HW) {
|
||||
valid = addr_safety_check(to_push, honda_bh_rx_checks, HONDA_BH_RX_CHECKS_LEN,
|
||||
honda_get_checksum, honda_compute_checksum, honda_get_counter);
|
||||
} else {
|
||||
valid = addr_safety_check(to_push, honda_rx_checks, HONDA_RX_CHECKS_LEN,
|
||||
honda_get_checksum, honda_compute_checksum, honda_get_counter);
|
||||
}
|
||||
bool valid = addr_safety_check(to_push, &honda_rx_checks,
|
||||
honda_get_checksum, honda_compute_checksum, honda_get_counter);
|
||||
|
||||
if (valid) {
|
||||
int addr = GET_ADDR(to_push);
|
||||
|
@ -310,7 +305,7 @@ static int honda_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) {
|
|||
return tx;
|
||||
}
|
||||
|
||||
static void honda_nidec_init(int16_t param) {
|
||||
static const addr_checks* honda_nidec_init(int16_t param) {
|
||||
UNUSED(param);
|
||||
controls_allowed = false;
|
||||
relay_malfunction_reset();
|
||||
|
@ -318,9 +313,11 @@ static void honda_nidec_init(int16_t param) {
|
|||
honda_hw = HONDA_N_HW;
|
||||
honda_alt_brake_msg = false;
|
||||
honda_bosch_long = false;
|
||||
honda_rx_checks = (addr_checks){honda_addr_checks, HONDA_ADDR_CHECKS_LEN};
|
||||
return &honda_rx_checks;
|
||||
}
|
||||
|
||||
static void honda_bosch_giraffe_init(int16_t param) {
|
||||
static const addr_checks* honda_bosch_giraffe_init(int16_t param) {
|
||||
controls_allowed = false;
|
||||
relay_malfunction_reset();
|
||||
honda_hw = HONDA_BG_HW;
|
||||
|
@ -328,9 +325,11 @@ static void honda_bosch_giraffe_init(int16_t param) {
|
|||
honda_alt_brake_msg = GET_FLAG(param, HONDA_PARAM_ALT_BRAKE);
|
||||
// radar disabled so allow gas/brakes
|
||||
honda_bosch_long = GET_FLAG(param, HONDA_PARAM_BOSCH_LONG);
|
||||
honda_rx_checks = (addr_checks){honda_addr_checks, HONDA_ADDR_CHECKS_LEN};
|
||||
return &honda_rx_checks;
|
||||
}
|
||||
|
||||
static void honda_bosch_harness_init(int16_t param) {
|
||||
static const addr_checks* honda_bosch_harness_init(int16_t param) {
|
||||
controls_allowed = false;
|
||||
relay_malfunction_reset();
|
||||
honda_hw = HONDA_BH_HW;
|
||||
|
@ -338,6 +337,8 @@ static void honda_bosch_harness_init(int16_t param) {
|
|||
honda_alt_brake_msg = GET_FLAG(param, HONDA_PARAM_ALT_BRAKE);
|
||||
// radar disabled so allow gas/brakes
|
||||
honda_bosch_long = GET_FLAG(param, HONDA_PARAM_BOSCH_LONG);
|
||||
honda_rx_checks = (addr_checks){honda_bh_addr_checks, HONDA_BH_ADDR_CHECKS_LEN};
|
||||
return &honda_rx_checks;
|
||||
}
|
||||
|
||||
static int honda_nidec_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) {
|
||||
|
@ -391,8 +392,6 @@ const safety_hooks honda_nidec_hooks = {
|
|||
.tx = honda_tx_hook,
|
||||
.tx_lin = nooutput_tx_lin_hook,
|
||||
.fwd = honda_nidec_fwd_hook,
|
||||
.addr_check = honda_rx_checks,
|
||||
.addr_check_len = sizeof(honda_rx_checks) / sizeof(honda_rx_checks[0]),
|
||||
};
|
||||
|
||||
const safety_hooks honda_bosch_giraffe_hooks = {
|
||||
|
@ -401,8 +400,6 @@ const safety_hooks honda_bosch_giraffe_hooks = {
|
|||
.tx = honda_tx_hook,
|
||||
.tx_lin = nooutput_tx_lin_hook,
|
||||
.fwd = honda_bosch_fwd_hook,
|
||||
.addr_check = honda_rx_checks,
|
||||
.addr_check_len = sizeof(honda_rx_checks) / sizeof(honda_rx_checks[0]),
|
||||
};
|
||||
|
||||
const safety_hooks honda_bosch_harness_hooks = {
|
||||
|
@ -411,6 +408,4 @@ const safety_hooks honda_bosch_harness_hooks = {
|
|||
.tx = honda_tx_hook,
|
||||
.tx_lin = nooutput_tx_lin_hook,
|
||||
.fwd = honda_bosch_fwd_hook,
|
||||
.addr_check = honda_bh_rx_checks,
|
||||
.addr_check_len = sizeof(honda_bh_rx_checks) / sizeof(honda_bh_rx_checks[0]),
|
||||
};
|
||||
|
|
|
@ -17,24 +17,24 @@ const CanMsg HYUNDAI_TX_MSGS[] = {
|
|||
// {1186, 0, 8} // 4a2SCC, Bus 0
|
||||
};
|
||||
|
||||
AddrCheckStruct hyundai_rx_checks[] = {
|
||||
AddrCheckStruct hyundai_addr_checks[] = {
|
||||
{.msg = {{608, 0, 8, .check_checksum = true, .max_counter = 3U, .expected_timestep = 10000U},
|
||||
{881, 0, 8, .expected_timestep = 10000U}, { 0 }}},
|
||||
{.msg = {{902, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 10000U}, { 0 }, { 0 }}},
|
||||
{.msg = {{916, 0, 8, .check_checksum = true, .max_counter = 7U, .expected_timestep = 10000U}, { 0 }, { 0 }}},
|
||||
{.msg = {{1057, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}, { 0 }, { 0 }}},
|
||||
};
|
||||
const int HYUNDAI_RX_CHECK_LEN = sizeof(hyundai_rx_checks) / sizeof(hyundai_rx_checks[0]);
|
||||
#define HYUNDAI_ADDR_CHECK_LEN (sizeof(hyundai_addr_checks) / sizeof(hyundai_addr_checks[0]))
|
||||
|
||||
// older hyundai models have less checks due to missing counters and checksums
|
||||
AddrCheckStruct hyundai_legacy_rx_checks[] = {
|
||||
AddrCheckStruct hyundai_legacy_addr_checks[] = {
|
||||
{.msg = {{608, 0, 8, .check_checksum = true, .max_counter = 3U, .expected_timestep = 10000U},
|
||||
{881, 0, 8, .expected_timestep = 10000U}, { 0 }}},
|
||||
{.msg = {{902, 0, 8, .expected_timestep = 10000U}, { 0 }, { 0 }}},
|
||||
{.msg = {{916, 0, 8, .expected_timestep = 10000U}, { 0 }, { 0 }}},
|
||||
{.msg = {{1057, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}, { 0 }, { 0 }}},
|
||||
};
|
||||
const int HYUNDAI_LEGACY_RX_CHECK_LEN = sizeof(hyundai_legacy_rx_checks) / sizeof(hyundai_legacy_rx_checks[0]);
|
||||
#define HYUNDAI_LEGACY_ADDR_CHECK_LEN (sizeof(hyundai_legacy_addr_checks) / sizeof(hyundai_legacy_addr_checks[0]))
|
||||
|
||||
const int HYUNDAI_PARAM_EV_GAS = 1;
|
||||
const int HYUNDAI_PARAM_HYBRID_GAS = 2;
|
||||
|
@ -43,6 +43,8 @@ bool hyundai_legacy = false;
|
|||
bool hyundai_ev_gas_signal = false;
|
||||
bool hyundai_hybrid_gas_signal = false;
|
||||
|
||||
addr_checks hyundai_rx_checks = {hyundai_addr_checks, HYUNDAI_ADDR_CHECK_LEN};
|
||||
|
||||
static uint8_t hyundai_get_counter(CAN_FIFOMailBox_TypeDef *to_push) {
|
||||
int addr = GET_ADDR(to_push);
|
||||
|
||||
|
@ -117,17 +119,9 @@ static uint8_t hyundai_compute_checksum(CAN_FIFOMailBox_TypeDef *to_push) {
|
|||
|
||||
static int hyundai_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
|
||||
|
||||
bool valid;
|
||||
if (hyundai_legacy) {
|
||||
valid = addr_safety_check(to_push, hyundai_legacy_rx_checks, HYUNDAI_LEGACY_RX_CHECK_LEN,
|
||||
hyundai_get_checksum, hyundai_compute_checksum,
|
||||
hyundai_get_counter);
|
||||
|
||||
} else {
|
||||
valid = addr_safety_check(to_push, hyundai_rx_checks, HYUNDAI_RX_CHECK_LEN,
|
||||
hyundai_get_checksum, hyundai_compute_checksum,
|
||||
hyundai_get_counter);
|
||||
}
|
||||
bool valid = addr_safety_check(to_push, &hyundai_rx_checks,
|
||||
hyundai_get_checksum, hyundai_compute_checksum,
|
||||
hyundai_get_counter);
|
||||
|
||||
if (valid && (GET_BUS(to_push) == 0)) {
|
||||
int addr = GET_ADDR(to_push);
|
||||
|
@ -267,22 +261,26 @@ static int hyundai_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) {
|
|||
return bus_fwd;
|
||||
}
|
||||
|
||||
static void hyundai_init(int16_t param) {
|
||||
static const addr_checks* hyundai_init(int16_t param) {
|
||||
controls_allowed = false;
|
||||
relay_malfunction_reset();
|
||||
|
||||
hyundai_legacy = false;
|
||||
hyundai_ev_gas_signal = GET_FLAG(param, HYUNDAI_PARAM_EV_GAS);
|
||||
hyundai_hybrid_gas_signal = !hyundai_ev_gas_signal && GET_FLAG(param, HYUNDAI_PARAM_HYBRID_GAS);
|
||||
hyundai_rx_checks = (addr_checks){hyundai_addr_checks, HYUNDAI_ADDR_CHECK_LEN};
|
||||
return &hyundai_rx_checks;
|
||||
}
|
||||
|
||||
static void hyundai_legacy_init(int16_t param) {
|
||||
static const addr_checks* hyundai_legacy_init(int16_t param) {
|
||||
controls_allowed = false;
|
||||
relay_malfunction_reset();
|
||||
|
||||
hyundai_legacy = true;
|
||||
hyundai_ev_gas_signal = GET_FLAG(param, HYUNDAI_PARAM_EV_GAS);
|
||||
hyundai_hybrid_gas_signal = !hyundai_ev_gas_signal && GET_FLAG(param, HYUNDAI_PARAM_HYBRID_GAS);
|
||||
hyundai_rx_checks = (addr_checks){hyundai_legacy_addr_checks, HYUNDAI_LEGACY_ADDR_CHECK_LEN};
|
||||
return &hyundai_rx_checks;
|
||||
}
|
||||
|
||||
const safety_hooks hyundai_hooks = {
|
||||
|
@ -291,8 +289,6 @@ const safety_hooks hyundai_hooks = {
|
|||
.tx = hyundai_tx_hook,
|
||||
.tx_lin = nooutput_tx_lin_hook,
|
||||
.fwd = hyundai_fwd_hook,
|
||||
.addr_check = hyundai_rx_checks,
|
||||
.addr_check_len = sizeof(hyundai_rx_checks) / sizeof(hyundai_rx_checks[0]),
|
||||
};
|
||||
|
||||
const safety_hooks hyundai_legacy_hooks = {
|
||||
|
@ -301,6 +297,4 @@ const safety_hooks hyundai_legacy_hooks = {
|
|||
.tx = hyundai_tx_hook,
|
||||
.tx_lin = nooutput_tx_lin_hook,
|
||||
.fwd = hyundai_fwd_hook,
|
||||
.addr_check = hyundai_legacy_rx_checks,
|
||||
.addr_check_len = sizeof(hyundai_legacy_rx_checks) / sizeof(hyundai_legacy_rx_checks[0]),
|
||||
};
|
||||
|
|
|
@ -30,19 +30,19 @@
|
|||
const CanMsg MAZDA_TX_MSGS[] = {{MAZDA_LKAS, 0, 8}, {MAZDA_CRZ_BTNS, 0, 8}};
|
||||
bool mazda_lkas_allowed = false;
|
||||
|
||||
AddrCheckStruct mazda_rx_checks[] = {
|
||||
AddrCheckStruct mazda_addr_checks[] = {
|
||||
{.msg = {{MAZDA_CRZ_CTRL, 0, 8, .expected_timestep = 20000U}, { 0 }, { 0 }}},
|
||||
{.msg = {{MAZDA_CRZ_BTNS, 0, 8, .expected_timestep = 100000U}, { 0 }, { 0 }}},
|
||||
{.msg = {{MAZDA_STEER_TORQUE, 0, 8, .expected_timestep = 12000U}, { 0 }, { 0 }}},
|
||||
{.msg = {{MAZDA_ENGINE_DATA, 0, 8, .expected_timestep = 10000U}, { 0 }, { 0 }}},
|
||||
{.msg = {{MAZDA_PEDALS, 0, 8, .expected_timestep = 20000U}, { 0 }, { 0 }}},
|
||||
};
|
||||
const int MAZDA_RX_CHECKS_LEN = sizeof(mazda_rx_checks) / sizeof(mazda_rx_checks[0]);
|
||||
#define MAZDA_ADDR_CHECKS_LEN (sizeof(mazda_addr_checks) / sizeof(mazda_addr_checks[0]))
|
||||
addr_checks mazda_rx_checks = {mazda_addr_checks, MAZDA_ADDR_CHECKS_LEN};
|
||||
|
||||
// track msgs coming from OP so that we know what CAM msgs to drop and what to forward
|
||||
static int mazda_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
|
||||
bool valid = addr_safety_check(to_push, mazda_rx_checks, MAZDA_RX_CHECKS_LEN,
|
||||
NULL, NULL, NULL);
|
||||
bool valid = addr_safety_check(to_push, &mazda_rx_checks, NULL, NULL, NULL);
|
||||
if (valid && (GET_BUS(to_push) == MAZDA_MAIN)) {
|
||||
int addr = GET_ADDR(to_push);
|
||||
|
||||
|
@ -183,11 +183,12 @@ static int mazda_fwd_hook(int bus, CAN_FIFOMailBox_TypeDef *to_fwd) {
|
|||
return bus_fwd;
|
||||
}
|
||||
|
||||
static void mazda_init(int16_t param) {
|
||||
static const addr_checks* mazda_init(int16_t param) {
|
||||
UNUSED(param);
|
||||
controls_allowed = false;
|
||||
relay_malfunction_reset();
|
||||
mazda_lkas_allowed = false;
|
||||
return &mazda_rx_checks;
|
||||
}
|
||||
|
||||
const safety_hooks mazda_hooks = {
|
||||
|
@ -196,6 +197,4 @@ const safety_hooks mazda_hooks = {
|
|||
.tx = mazda_tx_hook,
|
||||
.tx_lin = nooutput_tx_lin_hook,
|
||||
.fwd = mazda_fwd_hook,
|
||||
.addr_check = mazda_rx_checks,
|
||||
.addr_check_len = sizeof(mazda_rx_checks) / sizeof(mazda_rx_checks[0]),
|
||||
};
|
||||
|
|
|
@ -14,7 +14,7 @@ const int NISSAN_DEG_TO_CAN = 100;
|
|||
const CanMsg NISSAN_TX_MSGS[] = {{0x169, 0, 8}, {0x2b1, 0, 8}, {0x4cc, 0, 8}, {0x20b, 2, 6}, {0x20b, 1, 6}, {0x280, 2, 8}};
|
||||
|
||||
// Signals duplicated below due to the fact that these messages can come in on either CAN bus, depending on car model.
|
||||
AddrCheckStruct nissan_rx_checks[] = {
|
||||
AddrCheckStruct nissan_addr_checks[] = {
|
||||
{.msg = {{0x2, 0, 5, .expected_timestep = 10000U},
|
||||
{0x2, 1, 5, .expected_timestep = 10000U}, { 0 }}}, // STEER_ANGLE_SENSOR (100Hz)
|
||||
{.msg = {{0x285, 0, 8, .expected_timestep = 20000U},
|
||||
|
@ -28,15 +28,15 @@ AddrCheckStruct nissan_rx_checks[] = {
|
|||
{0x454, 1, 8, .expected_timestep = 100000U},
|
||||
{0x1cc, 0, 4, .expected_timestep = 10000U}}}, // DOORS_LIGHTS (10Hz) / BRAKE (100Hz)
|
||||
};
|
||||
const int NISSAN_RX_CHECK_LEN = sizeof(nissan_rx_checks) / sizeof(nissan_rx_checks[0]);
|
||||
#define NISSAN_ADDR_CHECK_LEN (sizeof(nissan_addr_checks) / sizeof(nissan_addr_checks[0]))
|
||||
addr_checks nissan_rx_checks = {nissan_addr_checks, NISSAN_ADDR_CHECK_LEN};
|
||||
|
||||
// EPS Location. false = V-CAN, true = C-CAN
|
||||
bool nissan_alt_eps = false;
|
||||
|
||||
static int nissan_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
|
||||
|
||||
bool valid = addr_safety_check(to_push, nissan_rx_checks, NISSAN_RX_CHECK_LEN,
|
||||
NULL, NULL, NULL);
|
||||
bool valid = addr_safety_check(to_push, &nissan_rx_checks, NULL, NULL, NULL);
|
||||
|
||||
if (valid) {
|
||||
int bus = GET_BUS(to_push);
|
||||
|
@ -190,10 +190,11 @@ static int nissan_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) {
|
|||
return bus_fwd;
|
||||
}
|
||||
|
||||
static void nissan_init(int16_t param) {
|
||||
static const addr_checks* nissan_init(int16_t param) {
|
||||
controls_allowed = 0;
|
||||
nissan_alt_eps = param ? 1 : 0;
|
||||
relay_malfunction_reset();
|
||||
return &nissan_rx_checks;
|
||||
}
|
||||
|
||||
const safety_hooks nissan_hooks = {
|
||||
|
@ -202,6 +203,4 @@ const safety_hooks nissan_hooks = {
|
|||
.tx = nissan_tx_hook,
|
||||
.tx_lin = nooutput_tx_lin_hook,
|
||||
.fwd = nissan_fwd_hook,
|
||||
.addr_check = nissan_rx_checks,
|
||||
.addr_check_len = sizeof(nissan_rx_checks) / sizeof(nissan_rx_checks[0]),
|
||||
};
|
||||
|
|
|
@ -13,27 +13,29 @@ const int SUBARU_L_DRIVER_TORQUE_ALLOWANCE = 75;
|
|||
const int SUBARU_L_DRIVER_TORQUE_FACTOR = 10;
|
||||
|
||||
const CanMsg SUBARU_TX_MSGS[] = {{0x122, 0, 8}, {0x221, 0, 8}, {0x322, 0, 8}};
|
||||
const int SUBARU_TX_MSGS_LEN = sizeof(SUBARU_TX_MSGS) / sizeof(SUBARU_TX_MSGS[0]);
|
||||
#define SUBARU_TX_MSGS_LEN (sizeof(SUBARU_TX_MSGS) / sizeof(SUBARU_TX_MSGS[0]))
|
||||
|
||||
AddrCheckStruct subaru_rx_checks[] = {
|
||||
AddrCheckStruct subaru_addr_checks[] = {
|
||||
{.msg = {{ 0x40, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 10000U}, { 0 }, { 0 }}},
|
||||
{.msg = {{0x119, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}, { 0 }, { 0 }}},
|
||||
{.msg = {{0x139, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}, { 0 }, { 0 }}},
|
||||
{.msg = {{0x13a, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}, { 0 }, { 0 }}},
|
||||
{.msg = {{0x240, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 50000U}, { 0 }, { 0 }}},
|
||||
};
|
||||
const int SUBARU_RX_CHECK_LEN = sizeof(subaru_rx_checks) / sizeof(subaru_rx_checks[0]);
|
||||
#define SUBARU_ADDR_CHECK_LEN (sizeof(subaru_addr_checks) / sizeof(subaru_addr_checks[0]))
|
||||
addr_checks subaru_rx_checks = {subaru_addr_checks, SUBARU_ADDR_CHECK_LEN};
|
||||
|
||||
const CanMsg SUBARU_L_TX_MSGS[] = {{0x161, 0, 8}, {0x164, 0, 8}};
|
||||
const int SUBARU_L_TX_MSGS_LEN = sizeof(SUBARU_L_TX_MSGS) / sizeof(SUBARU_L_TX_MSGS[0]);
|
||||
#define SUBARU_L_TX_MSGS_LEN (sizeof(SUBARU_L_TX_MSGS) / sizeof(SUBARU_L_TX_MSGS[0]))
|
||||
|
||||
// TODO: do checksum and counter checks after adding the signals to the outback dbc file
|
||||
AddrCheckStruct subaru_l_rx_checks[] = {
|
||||
AddrCheckStruct subaru_l_addr_checks[] = {
|
||||
{.msg = {{0x140, 0, 8, .expected_timestep = 10000U}, { 0 }, { 0 }}},
|
||||
{.msg = {{0x371, 0, 8, .expected_timestep = 20000U}, { 0 }, { 0 }}},
|
||||
{.msg = {{0x144, 0, 8, .expected_timestep = 50000U}, { 0 }, { 0 }}},
|
||||
};
|
||||
const int SUBARU_L_RX_CHECK_LEN = sizeof(subaru_l_rx_checks) / sizeof(subaru_l_rx_checks[0]);
|
||||
#define SUBARU_L_ADDR_CHECK_LEN (sizeof(subaru_l_addr_checks) / sizeof(subaru_l_addr_checks[0]))
|
||||
addr_checks subaru_l_rx_checks = {subaru_addr_checks, SUBARU_L_ADDR_CHECK_LEN};
|
||||
|
||||
static uint8_t subaru_get_checksum(CAN_FIFOMailBox_TypeDef *to_push) {
|
||||
return (uint8_t)GET_BYTE(to_push, 0);
|
||||
|
@ -55,7 +57,7 @@ static uint8_t subaru_compute_checksum(CAN_FIFOMailBox_TypeDef *to_push) {
|
|||
|
||||
static int subaru_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
|
||||
|
||||
bool valid = addr_safety_check(to_push, subaru_rx_checks, SUBARU_RX_CHECK_LEN,
|
||||
bool valid = addr_safety_check(to_push, &subaru_rx_checks,
|
||||
subaru_get_checksum, subaru_compute_checksum, subaru_get_counter);
|
||||
|
||||
if (valid && (GET_BUS(to_push) == 0)) {
|
||||
|
@ -102,8 +104,7 @@ static int subaru_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
|
|||
|
||||
static int subaru_legacy_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
|
||||
|
||||
bool valid = addr_safety_check(to_push, subaru_l_rx_checks, SUBARU_L_RX_CHECK_LEN,
|
||||
NULL, NULL, NULL);
|
||||
bool valid = addr_safety_check(to_push, &subaru_l_rx_checks, NULL, NULL, NULL);
|
||||
|
||||
if (valid && (GET_BUS(to_push) == 0)) {
|
||||
int addr = GET_ADDR(to_push);
|
||||
|
@ -320,22 +321,32 @@ static int subaru_legacy_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd)
|
|||
return bus_fwd;
|
||||
}
|
||||
|
||||
static const addr_checks* subaru_init(int16_t param) {
|
||||
UNUSED(param);
|
||||
controls_allowed = false;
|
||||
relay_malfunction_reset();
|
||||
return &subaru_rx_checks;
|
||||
}
|
||||
|
||||
const safety_hooks subaru_hooks = {
|
||||
.init = nooutput_init,
|
||||
.init = subaru_init,
|
||||
.rx = subaru_rx_hook,
|
||||
.tx = subaru_tx_hook,
|
||||
.tx_lin = nooutput_tx_lin_hook,
|
||||
.fwd = subaru_fwd_hook,
|
||||
.addr_check = subaru_rx_checks,
|
||||
.addr_check_len = sizeof(subaru_rx_checks) / sizeof(subaru_rx_checks[0]),
|
||||
};
|
||||
|
||||
static const addr_checks* subaru_legacy_init(int16_t param) {
|
||||
UNUSED(param);
|
||||
controls_allowed = false;
|
||||
relay_malfunction_reset();
|
||||
return &subaru_l_rx_checks;
|
||||
}
|
||||
|
||||
const safety_hooks subaru_legacy_hooks = {
|
||||
.init = nooutput_init,
|
||||
.init = subaru_legacy_init,
|
||||
.rx = subaru_legacy_rx_hook,
|
||||
.tx = subaru_legacy_tx_hook,
|
||||
.tx_lin = nooutput_tx_lin_hook,
|
||||
.fwd = subaru_legacy_fwd_hook,
|
||||
.addr_check = subaru_l_rx_checks,
|
||||
.addr_check_len = sizeof(subaru_l_rx_checks) / sizeof(subaru_l_rx_checks[0]),
|
||||
};
|
||||
|
|
|
@ -14,7 +14,7 @@ const CanMsg TESLA_TX_MSGS[] = {
|
|||
{0x45, 2, 8}, // STW_ACTN_RQ
|
||||
};
|
||||
|
||||
AddrCheckStruct tesla_rx_checks[] = {
|
||||
AddrCheckStruct tesla_addr_checks[] = {
|
||||
{.msg = {{0x370, 0, 8, .expected_timestep = 40000U}, { 0 }, { 0 }}}, // EPAS_sysStatus (25Hz)
|
||||
{.msg = {{0x108, 0, 8, .expected_timestep = 10000U}, { 0 }, { 0 }}}, // DI_torque1 (100Hz)
|
||||
{.msg = {{0x118, 0, 6, .expected_timestep = 10000U}, { 0 }, { 0 }}}, // DI_torque2 (100Hz)
|
||||
|
@ -23,12 +23,13 @@ AddrCheckStruct tesla_rx_checks[] = {
|
|||
{.msg = {{0x368, 0, 8, .expected_timestep = 100000U}, { 0 }, { 0 }}}, // DI_state (10Hz)
|
||||
{.msg = {{0x318, 0, 8, .expected_timestep = 100000U}, { 0 }, { 0 }}}, // GTW_carState (10Hz)
|
||||
};
|
||||
#define TESLA_RX_CHECK_LEN (sizeof(tesla_rx_checks) / sizeof(tesla_rx_checks[0]))
|
||||
#define TESLA_ADDR_CHECK_LEN (sizeof(tesla_addr_checks) / sizeof(tesla_addr_checks[0]))
|
||||
addr_checks tesla_rx_checks = {tesla_addr_checks, TESLA_ADDR_CHECK_LEN};
|
||||
|
||||
bool autopilot_enabled = false;
|
||||
|
||||
static int tesla_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
|
||||
bool valid = addr_safety_check(to_push, tesla_rx_checks, TESLA_RX_CHECK_LEN,
|
||||
bool valid = addr_safety_check(to_push, &tesla_rx_checks,
|
||||
NULL, NULL, NULL);
|
||||
|
||||
if(valid) {
|
||||
|
@ -189,10 +190,11 @@ static int tesla_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) {
|
|||
return bus_fwd;
|
||||
}
|
||||
|
||||
static void tesla_init(int16_t param) {
|
||||
static const addr_checks* tesla_init(int16_t param) {
|
||||
UNUSED(param);
|
||||
controls_allowed = 0;
|
||||
relay_malfunction_reset();
|
||||
return &tesla_rx_checks;
|
||||
}
|
||||
|
||||
const safety_hooks tesla_hooks = {
|
||||
|
@ -201,6 +203,4 @@ const safety_hooks tesla_hooks = {
|
|||
.tx = tesla_tx_hook,
|
||||
.tx_lin = nooutput_tx_lin_hook,
|
||||
.fwd = tesla_fwd_hook,
|
||||
.addr_check = tesla_rx_checks,
|
||||
.addr_check_len = TESLA_RX_CHECK_LEN,
|
||||
};
|
||||
|
|
|
@ -13,11 +13,8 @@ const int TOYOTA_MAX_RT_DELTA = 375; // max delta torque allowed for real t
|
|||
const uint32_t TOYOTA_RT_INTERVAL = 250000; // 250ms between real time checks
|
||||
|
||||
// longitudinal limits
|
||||
const int TOYOTA_MAX_ACCEL = 1500; // 1.5 m/s2
|
||||
const int TOYOTA_MIN_ACCEL = -3000; // -3.0 m/s2
|
||||
|
||||
const int TOYOTA_ISO_MAX_ACCEL = 2000; // 2.0 m/s2
|
||||
const int TOYOTA_ISO_MIN_ACCEL = -3500; // -3.5 m/s2
|
||||
const int TOYOTA_MAX_ACCEL = 2000; // 2.0 m/s2
|
||||
const int TOYOTA_MIN_ACCEL = -3500; // -3.5 m/s2
|
||||
|
||||
const int TOYOTA_STANDSTILL_THRSLD = 100; // 1kph
|
||||
|
||||
|
@ -34,14 +31,15 @@ const CanMsg TOYOTA_TX_MSGS[] = {{0x283, 0, 7}, {0x2E6, 0, 8}, {0x2E7, 0, 8}, {0
|
|||
{0x2E4, 0, 5}, {0x191, 0, 8}, {0x411, 0, 8}, {0x412, 0, 8}, {0x343, 0, 8}, {0x1D2, 0, 8}, // LKAS + ACC
|
||||
{0x200, 0, 6}}; // interceptor
|
||||
|
||||
AddrCheckStruct toyota_rx_checks[] = {
|
||||
AddrCheckStruct toyota_addr_checks[] = {
|
||||
{.msg = {{ 0xaa, 0, 8, .check_checksum = false, .expected_timestep = 12000U}, { 0 }, { 0 }}},
|
||||
{.msg = {{0x260, 0, 8, .check_checksum = true, .expected_timestep = 20000U}, { 0 }, { 0 }}},
|
||||
{.msg = {{0x1D2, 0, 8, .check_checksum = true, .expected_timestep = 30000U}, { 0 }, { 0 }}},
|
||||
{.msg = {{0x224, 0, 8, .check_checksum = false, .expected_timestep = 25000U},
|
||||
{0x226, 0, 8, .check_checksum = false, .expected_timestep = 25000U}, { 0 }}},
|
||||
};
|
||||
const int TOYOTA_RX_CHECKS_LEN = sizeof(toyota_rx_checks) / sizeof(toyota_rx_checks[0]);
|
||||
#define TOYOTA_ADDR_CHECKS_LEN (sizeof(toyota_addr_checks) / sizeof(toyota_addr_checks[0]))
|
||||
addr_checks toyota_rx_checks = {toyota_addr_checks, TOYOTA_ADDR_CHECKS_LEN};
|
||||
|
||||
// global actuation limit states
|
||||
int toyota_dbc_eps_torque_factor = 100; // conversion factor for STEER_TORQUE_EPS in %: see dbc file
|
||||
|
@ -63,7 +61,7 @@ static uint8_t toyota_get_checksum(CAN_FIFOMailBox_TypeDef *to_push) {
|
|||
|
||||
static int toyota_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
|
||||
|
||||
bool valid = addr_safety_check(to_push, toyota_rx_checks, TOYOTA_RX_CHECKS_LEN,
|
||||
bool valid = addr_safety_check(to_push, &toyota_rx_checks,
|
||||
toyota_get_checksum, toyota_compute_checksum, NULL);
|
||||
|
||||
if (valid && (GET_BUS(to_push) == 0)) {
|
||||
|
@ -171,9 +169,7 @@ static int toyota_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) {
|
|||
tx = 0;
|
||||
}
|
||||
}
|
||||
bool violation = (unsafe_mode & UNSAFE_RAISE_LONGITUDINAL_LIMITS_TO_ISO_MAX)?
|
||||
max_limit_check(desired_accel, TOYOTA_ISO_MAX_ACCEL, TOYOTA_ISO_MIN_ACCEL) :
|
||||
max_limit_check(desired_accel, TOYOTA_MAX_ACCEL, TOYOTA_MIN_ACCEL);
|
||||
bool violation = max_limit_check(desired_accel, TOYOTA_MAX_ACCEL, TOYOTA_MIN_ACCEL);
|
||||
|
||||
if (violation) {
|
||||
tx = 0;
|
||||
|
@ -247,11 +243,12 @@ static int toyota_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) {
|
|||
return tx;
|
||||
}
|
||||
|
||||
static void toyota_init(int16_t param) {
|
||||
static const addr_checks* toyota_init(int16_t param) {
|
||||
controls_allowed = 0;
|
||||
relay_malfunction_reset();
|
||||
gas_interceptor_detected = 0;
|
||||
toyota_dbc_eps_torque_factor = param;
|
||||
return &toyota_rx_checks;
|
||||
}
|
||||
|
||||
static int toyota_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) {
|
||||
|
@ -283,6 +280,4 @@ const safety_hooks toyota_hooks = {
|
|||
.tx = toyota_tx_hook,
|
||||
.tx_lin = nooutput_tx_lin_hook,
|
||||
.fwd = toyota_fwd_hook,
|
||||
.addr_check = toyota_rx_checks,
|
||||
.addr_check_len = sizeof(toyota_rx_checks)/sizeof(toyota_rx_checks[0]),
|
||||
};
|
||||
|
|
|
@ -19,16 +19,17 @@ const int VOLKSWAGEN_DRIVER_TORQUE_FACTOR = 3;
|
|||
|
||||
// Transmit of GRA_ACC_01 is allowed on bus 0 and 2 to keep compatibility with gateway and camera integration
|
||||
const CanMsg VOLKSWAGEN_MQB_TX_MSGS[] = {{MSG_HCA_01, 0, 8}, {MSG_GRA_ACC_01, 0, 8}, {MSG_GRA_ACC_01, 2, 8}, {MSG_LDW_02, 0, 8}};
|
||||
const int VOLKSWAGEN_MQB_TX_MSGS_LEN = sizeof(VOLKSWAGEN_MQB_TX_MSGS) / sizeof(VOLKSWAGEN_MQB_TX_MSGS[0]);
|
||||
#define VOLKSWAGEN_MQB_TX_MSGS_LEN (sizeof(VOLKSWAGEN_MQB_TX_MSGS) / sizeof(VOLKSWAGEN_MQB_TX_MSGS[0]))
|
||||
|
||||
AddrCheckStruct volkswagen_mqb_rx_checks[] = {
|
||||
AddrCheckStruct volkswagen_mqb_addr_checks[] = {
|
||||
{.msg = {{MSG_ESP_19, 0, 8, .check_checksum = false, .max_counter = 0U, .expected_timestep = 10000U}, { 0 }, { 0 }}},
|
||||
{.msg = {{MSG_LH_EPS_03, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 10000U}, { 0 }, { 0 }}},
|
||||
{.msg = {{MSG_ESP_05, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}, { 0 }, { 0 }}},
|
||||
{.msg = {{MSG_TSK_06, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}, { 0 }, { 0 }}},
|
||||
{.msg = {{MSG_MOTOR_20, 0, 8, .check_checksum = true, .max_counter = 15U, .expected_timestep = 20000U}, { 0 }, { 0 }}},
|
||||
};
|
||||
const int VOLKSWAGEN_MQB_RX_CHECKS_LEN = sizeof(volkswagen_mqb_rx_checks) / sizeof(volkswagen_mqb_rx_checks[0]);
|
||||
#define VOLKSWAGEN_MQB_ADDR_CHECKS_LEN (sizeof(volkswagen_mqb_addr_checks) / sizeof(volkswagen_mqb_addr_checks[0]))
|
||||
addr_checks volkswagen_mqb_rx_checks = {volkswagen_mqb_addr_checks, VOLKSWAGEN_MQB_ADDR_CHECKS_LEN};
|
||||
|
||||
// Safety-relevant CAN messages for the Volkswagen PQ35/PQ46/NMS platforms
|
||||
#define MSG_LENKHILFE_3 0x0D0 // RX from EPS, for steering angle and driver steering torque
|
||||
|
@ -41,15 +42,16 @@ const int VOLKSWAGEN_MQB_RX_CHECKS_LEN = sizeof(volkswagen_mqb_rx_checks) / size
|
|||
|
||||
// Transmit of GRA_Neu is allowed on bus 0 and 2 to keep compatibility with gateway and camera integration
|
||||
const CanMsg VOLKSWAGEN_PQ_TX_MSGS[] = {{MSG_HCA_1, 0, 5}, {MSG_GRA_NEU, 0, 4}, {MSG_GRA_NEU, 2, 4}, {MSG_LDW_1, 0, 8}};
|
||||
const int VOLKSWAGEN_PQ_TX_MSGS_LEN = sizeof(VOLKSWAGEN_PQ_TX_MSGS) / sizeof(VOLKSWAGEN_PQ_TX_MSGS[0]);
|
||||
#define VOLKSWAGEN_PQ_TX_MSGS_LEN (sizeof(VOLKSWAGEN_PQ_TX_MSGS) / sizeof(VOLKSWAGEN_PQ_TX_MSGS[0]))
|
||||
|
||||
AddrCheckStruct volkswagen_pq_rx_checks[] = {
|
||||
AddrCheckStruct volkswagen_pq_addr_checks[] = {
|
||||
{.msg = {{MSG_LENKHILFE_3, 0, 6, .check_checksum = true, .max_counter = 15U, .expected_timestep = 10000U}, { 0 }, { 0 }}},
|
||||
{.msg = {{MSG_MOTOR_2, 0, 8, .check_checksum = false, .max_counter = 0U, .expected_timestep = 20000U}, { 0 }, { 0 }}},
|
||||
{.msg = {{MSG_MOTOR_3, 0, 8, .check_checksum = false, .max_counter = 0U, .expected_timestep = 10000U}, { 0 }, { 0 }}},
|
||||
{.msg = {{MSG_BREMSE_3, 0, 8, .check_checksum = false, .max_counter = 0U, .expected_timestep = 10000U}, { 0 }, { 0 }}},
|
||||
};
|
||||
const int VOLKSWAGEN_PQ_RX_CHECKS_LEN = sizeof(volkswagen_pq_rx_checks) / sizeof(volkswagen_pq_rx_checks[0]);
|
||||
#define VOLKSWAGEN_PQ_ADDR_CHECKS_LEN (sizeof(volkswagen_pq_addr_checks) / sizeof(volkswagen_pq_addr_checks[0]))
|
||||
addr_checks volkswagen_pq_rx_checks = {volkswagen_pq_addr_checks, VOLKSWAGEN_PQ_ADDR_CHECKS_LEN};
|
||||
|
||||
int volkswagen_torque_msg = 0;
|
||||
int volkswagen_lane_msg = 0;
|
||||
|
@ -117,7 +119,7 @@ static uint8_t volkswagen_pq_compute_checksum(CAN_FIFOMailBox_TypeDef *to_push)
|
|||
return checksum;
|
||||
}
|
||||
|
||||
static void volkswagen_mqb_init(int16_t param) {
|
||||
static const addr_checks* volkswagen_mqb_init(int16_t param) {
|
||||
UNUSED(param);
|
||||
|
||||
controls_allowed = false;
|
||||
|
@ -125,20 +127,22 @@ static void volkswagen_mqb_init(int16_t param) {
|
|||
volkswagen_torque_msg = MSG_HCA_01;
|
||||
volkswagen_lane_msg = MSG_LDW_02;
|
||||
gen_crc_lookup_table(0x2F, volkswagen_crc8_lut_8h2f);
|
||||
return &volkswagen_mqb_rx_checks;
|
||||
}
|
||||
|
||||
static void volkswagen_pq_init(int16_t param) {
|
||||
static const addr_checks* volkswagen_pq_init(int16_t param) {
|
||||
UNUSED(param);
|
||||
|
||||
controls_allowed = false;
|
||||
relay_malfunction_reset();
|
||||
volkswagen_torque_msg = MSG_HCA_1;
|
||||
volkswagen_lane_msg = MSG_LDW_1;
|
||||
return &volkswagen_pq_rx_checks;
|
||||
}
|
||||
|
||||
static int volkswagen_mqb_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
|
||||
|
||||
bool valid = addr_safety_check(to_push, volkswagen_mqb_rx_checks, VOLKSWAGEN_MQB_RX_CHECKS_LEN,
|
||||
bool valid = addr_safety_check(to_push, &volkswagen_mqb_rx_checks,
|
||||
volkswagen_get_checksum, volkswagen_mqb_compute_crc, volkswagen_mqb_get_counter);
|
||||
|
||||
if (valid && (GET_BUS(to_push) == 0)) {
|
||||
|
@ -167,11 +171,18 @@ static int volkswagen_mqb_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
|
|||
update_sample(&torque_driver, torque_driver_new);
|
||||
}
|
||||
|
||||
// Update ACC status from drivetrain coordinator for controls-allowed state
|
||||
// Enter controls on rising edge of stock ACC, exit controls if stock ACC disengages
|
||||
// Signal: TSK_06.TSK_Status
|
||||
if (addr == MSG_TSK_06) {
|
||||
int acc_status = (GET_BYTE(to_push, 3) & 0x7);
|
||||
controls_allowed = ((acc_status == 3) || (acc_status == 4) || (acc_status == 5)) ? 1 : 0;
|
||||
int cruise_engaged = ((acc_status == 3) || (acc_status == 4) || (acc_status == 5)) ? 1 : 0;
|
||||
if (cruise_engaged && !cruise_engaged_prev) {
|
||||
controls_allowed = 1;
|
||||
}
|
||||
if (!cruise_engaged) {
|
||||
controls_allowed = 0;
|
||||
}
|
||||
cruise_engaged_prev = cruise_engaged;
|
||||
}
|
||||
|
||||
// Signal: Motor_20.MO_Fahrpedalrohwert_01
|
||||
|
@ -191,7 +202,7 @@ static int volkswagen_mqb_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
|
|||
|
||||
static int volkswagen_pq_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
|
||||
|
||||
bool valid = addr_safety_check(to_push, volkswagen_pq_rx_checks, VOLKSWAGEN_PQ_RX_CHECKS_LEN,
|
||||
bool valid = addr_safety_check(to_push, &volkswagen_pq_rx_checks,
|
||||
volkswagen_get_checksum, volkswagen_pq_compute_checksum, volkswagen_pq_get_counter);
|
||||
|
||||
if (valid && (GET_BUS(to_push) == 0)) {
|
||||
|
@ -220,11 +231,18 @@ static int volkswagen_pq_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
|
|||
update_sample(&torque_driver, torque_driver_new);
|
||||
}
|
||||
|
||||
// Update ACC status from ECU for controls-allowed state
|
||||
// Enter controls on rising edge of stock ACC, exit controls if stock ACC disengages
|
||||
// Signal: Motor_2.GRA_Status
|
||||
if (addr == MSG_MOTOR_2) {
|
||||
int acc_status = (GET_BYTE(to_push, 2) & 0xC0) >> 6;
|
||||
controls_allowed = ((acc_status == 1) || (acc_status == 2)) ? 1 : 0;
|
||||
int cruise_engaged = ((acc_status == 1) || (acc_status == 2)) ? 1 : 0;
|
||||
if (cruise_engaged && !cruise_engaged_prev) {
|
||||
controls_allowed = 1;
|
||||
}
|
||||
if (!cruise_engaged) {
|
||||
controls_allowed = 0;
|
||||
}
|
||||
cruise_engaged_prev = cruise_engaged;
|
||||
}
|
||||
|
||||
// Signal: Motor_3.Fahrpedal_Rohsignal
|
||||
|
@ -390,8 +408,6 @@ const safety_hooks volkswagen_mqb_hooks = {
|
|||
.tx = volkswagen_mqb_tx_hook,
|
||||
.tx_lin = nooutput_tx_lin_hook,
|
||||
.fwd = volkswagen_fwd_hook,
|
||||
.addr_check = volkswagen_mqb_rx_checks,
|
||||
.addr_check_len = sizeof(volkswagen_mqb_rx_checks) / sizeof(volkswagen_mqb_rx_checks[0]),
|
||||
};
|
||||
|
||||
// Volkswagen PQ35/PQ46/NMS platforms
|
||||
|
@ -401,6 +417,4 @@ const safety_hooks volkswagen_pq_hooks = {
|
|||
.tx = volkswagen_pq_tx_hook,
|
||||
.tx_lin = nooutput_tx_lin_hook,
|
||||
.fwd = volkswagen_fwd_hook,
|
||||
.addr_check = volkswagen_pq_rx_checks,
|
||||
.addr_check_len = sizeof(volkswagen_pq_rx_checks) / sizeof(volkswagen_pq_rx_checks[0]),
|
||||
};
|
||||
|
|
|
@ -43,6 +43,11 @@ typedef struct {
|
|||
bool lagging; // true if and only if the time between updates is excessive
|
||||
} AddrCheckStruct;
|
||||
|
||||
typedef struct {
|
||||
AddrCheckStruct *check;
|
||||
int len;
|
||||
} addr_checks;
|
||||
|
||||
int safety_rx_hook(CAN_FIFOMailBox_TypeDef *to_push);
|
||||
int safety_tx_hook(CAN_FIFOMailBox_TypeDef *to_send);
|
||||
int safety_tx_lin_hook(int lin_num, uint8_t *data, int len);
|
||||
|
@ -64,8 +69,7 @@ void update_counter(AddrCheckStruct addr_list[], int index, uint8_t counter);
|
|||
void update_addr_timestamp(AddrCheckStruct addr_list[], int index);
|
||||
bool is_msg_valid(AddrCheckStruct addr_list[], int index);
|
||||
bool addr_safety_check(CAN_FIFOMailBox_TypeDef *to_push,
|
||||
AddrCheckStruct *addr_check,
|
||||
const int addr_check_len,
|
||||
const addr_checks *rx_checks,
|
||||
uint8_t (*get_checksum)(CAN_FIFOMailBox_TypeDef *to_push),
|
||||
uint8_t (*compute_checksum)(CAN_FIFOMailBox_TypeDef *to_push),
|
||||
uint8_t (*get_counter)(CAN_FIFOMailBox_TypeDef *to_push));
|
||||
|
@ -73,7 +77,7 @@ void generic_rx_checks(bool stock_ecu_detected);
|
|||
void relay_malfunction_set(void);
|
||||
void relay_malfunction_reset(void);
|
||||
|
||||
typedef void (*safety_hook_init)(int16_t param);
|
||||
typedef const addr_checks* (*safety_hook_init)(int16_t param);
|
||||
typedef int (*rx_hook)(CAN_FIFOMailBox_TypeDef *to_push);
|
||||
typedef int (*tx_hook)(CAN_FIFOMailBox_TypeDef *to_send);
|
||||
typedef int (*tx_lin_hook)(int lin_num, uint8_t *data, int len);
|
||||
|
@ -85,11 +89,9 @@ typedef struct {
|
|||
tx_hook tx;
|
||||
tx_lin_hook tx_lin;
|
||||
fwd_hook fwd;
|
||||
AddrCheckStruct *addr_check;
|
||||
const int addr_check_len;
|
||||
} safety_hooks;
|
||||
|
||||
void safety_tick(const safety_hooks *hooks);
|
||||
void safety_tick(const addr_checks *addr_checks);
|
||||
|
||||
// This can be set by the safety hooks
|
||||
bool controls_allowed = false;
|
||||
|
@ -129,6 +131,7 @@ struct sample_t angle_meas; // last 3 steer angles
|
|||
|
||||
// If using this flag, be aware that harder braking is more likely to lead to rear endings,
|
||||
// and that alone this flag doesn't make braking compliant because there's also a time element.
|
||||
// Setting this flag is used for allowing the full -5.0 to +4.0 m/s^2 at lower speeds
|
||||
// See ISO 15622:2018 for more information.
|
||||
#define UNSAFE_RAISE_LONGITUDINAL_LIMITS_TO_ISO_MAX 8
|
||||
|
||||
|
|
|
@ -62,6 +62,7 @@ find . -name '*.pyc' -delete
|
|||
find . -name '__pycache__' -delete
|
||||
rm -rf panda/board panda/certs panda/crypto
|
||||
rm -rf .sconsign.dblite Jenkinsfile release/
|
||||
rm models/supercombo.dlc
|
||||
|
||||
# Move back signed panda fw
|
||||
mkdir -p panda/board/obj
|
||||
|
|
|
@ -580,7 +580,6 @@ opendbc/honda_crv_ex_2017_body_generated.dbc
|
|||
opendbc/honda_crv_executive_2016_can_generated.dbc
|
||||
opendbc/honda_crv_hybrid_2019_can_generated.dbc
|
||||
opendbc/honda_fit_ex_2018_can_generated.dbc
|
||||
opendbc/honda_hrv_touring_2019_can_generated.dbc
|
||||
opendbc/honda_odyssey_exl_2018_generated.dbc
|
||||
opendbc/honda_odyssey_extreme_edition_2018_china_can_generated.dbc
|
||||
opendbc/honda_pilot_touring_2017_can_generated.dbc
|
||||
|
@ -623,3 +622,4 @@ opendbc/toyota_tss2_adas.dbc
|
|||
opendbc/vw_mqb_2010.dbc
|
||||
|
||||
opendbc/tesla_can.dbc
|
||||
opendbc/tesla_radar.dbc
|
||||
|
|
|
@ -35,14 +35,12 @@
|
|||
#define SATURATE_IL 1600
|
||||
#define NIBBLE_TO_HEX(n) ((n) < 10 ? (n) + '0' : ((n) - 10) + 'a')
|
||||
|
||||
Panda * panda = nullptr;
|
||||
std::atomic<bool> safety_setter_thread_running(false);
|
||||
std::atomic<bool> ignition(false);
|
||||
|
||||
ExitHandler do_exit;
|
||||
|
||||
|
||||
void safety_setter_thread() {
|
||||
void safety_setter_thread(Panda *panda) {
|
||||
LOGD("Starting safety setter thread");
|
||||
// diagnostic only is the default, needed for VIN query
|
||||
panda->set_safety_model(cereal::CarParams::SafetyModel::ELM327);
|
||||
|
@ -101,24 +99,21 @@ void safety_setter_thread() {
|
|||
}
|
||||
|
||||
|
||||
bool usb_connect() {
|
||||
static bool connected_once = false;
|
||||
|
||||
std::unique_ptr<Panda> tmp_panda;
|
||||
Panda *usb_connect() {
|
||||
std::unique_ptr<Panda> panda;
|
||||
try {
|
||||
assert(panda == nullptr);
|
||||
tmp_panda = std::make_unique<Panda>();
|
||||
panda = std::make_unique<Panda>();
|
||||
} catch (std::exception &e) {
|
||||
return false;
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
Params params = Params();
|
||||
|
||||
if (getenv("BOARDD_LOOPBACK")) {
|
||||
tmp_panda->set_loopback(true);
|
||||
panda->set_loopback(true);
|
||||
}
|
||||
|
||||
if (auto fw_sig = tmp_panda->get_firmware_version(); fw_sig) {
|
||||
if (auto fw_sig = panda->get_firmware_version(); fw_sig) {
|
||||
params.put("PandaFirmware", (const char *)fw_sig->data(), fw_sig->size());
|
||||
|
||||
// Convert to hex for offroad
|
||||
|
@ -131,25 +126,24 @@ bool usb_connect() {
|
|||
|
||||
params.put("PandaFirmwareHex", fw_sig_hex_buf, 16);
|
||||
LOGW("fw signature: %.*s", 16, fw_sig_hex_buf);
|
||||
} else { return false; }
|
||||
} else { return nullptr; }
|
||||
|
||||
// get panda serial
|
||||
if (auto serial = tmp_panda->get_serial(); serial) {
|
||||
if (auto serial = panda->get_serial(); serial) {
|
||||
params.put("PandaDongleId", serial->c_str(), serial->length());
|
||||
LOGW("panda serial: %s", serial->c_str());
|
||||
} else { return false; }
|
||||
} else { return nullptr; }
|
||||
|
||||
// power on charging, only the first time. Panda can also change mode and it causes a brief disconneciton
|
||||
#ifndef __x86_64__
|
||||
if (!connected_once) {
|
||||
tmp_panda->set_usb_power_mode(cereal::PandaState::UsbPowerMode::CDP);
|
||||
}
|
||||
static std::once_flag connected_once;
|
||||
std::call_once(connected_once, &Panda::set_usb_power_mode, panda, cereal::PandaState::UsbPowerMode::CDP);
|
||||
#endif
|
||||
|
||||
if (tmp_panda->has_rtc) {
|
||||
if (panda->has_rtc) {
|
||||
setenv("TZ","UTC",1);
|
||||
struct tm sys_time = util::get_time();
|
||||
struct tm rtc_time = tmp_panda->get_rtc();
|
||||
struct tm rtc_time = panda->get_rtc();
|
||||
|
||||
if (!util::time_valid(sys_time) && util::time_valid(rtc_time)) {
|
||||
LOGE("System time wrong, setting from RTC. "
|
||||
|
@ -164,29 +158,31 @@ bool usb_connect() {
|
|||
}
|
||||
}
|
||||
|
||||
connected_once = true;
|
||||
panda = tmp_panda.release();
|
||||
return true;
|
||||
return panda.release();
|
||||
}
|
||||
|
||||
// must be called before threads or with mutex
|
||||
static bool usb_retry_connect() {
|
||||
static Panda *usb_retry_connect() {
|
||||
LOGW("attempting to connect");
|
||||
while (!do_exit && !usb_connect()) { util::sleep_for(100); }
|
||||
if (panda) {
|
||||
LOGW("connected to board");
|
||||
}
|
||||
return !do_exit;
|
||||
while (!do_exit) {
|
||||
Panda *panda = usb_connect();
|
||||
if (panda) {
|
||||
LOGW("connected to board");
|
||||
return panda;
|
||||
}
|
||||
util::sleep_for(100);
|
||||
};
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
void can_recv(PubMaster &pm) {
|
||||
void can_recv(Panda *panda, PubMaster &pm) {
|
||||
kj::Array<capnp::word> can_data;
|
||||
panda->can_receive(can_data);
|
||||
auto bytes = can_data.asBytes();
|
||||
pm.send("can", bytes.begin(), bytes.size());
|
||||
}
|
||||
|
||||
void can_send_thread(bool fake_send) {
|
||||
void can_send_thread(Panda *panda, bool fake_send) {
|
||||
LOGD("start send thread");
|
||||
|
||||
AlignedBuffer aligned_buf;
|
||||
|
@ -223,7 +219,7 @@ void can_send_thread(bool fake_send) {
|
|||
delete context;
|
||||
}
|
||||
|
||||
void can_recv_thread() {
|
||||
void can_recv_thread(Panda *panda) {
|
||||
LOGD("start recv thread");
|
||||
|
||||
// can = 8006
|
||||
|
@ -234,7 +230,7 @@ void can_recv_thread() {
|
|||
uint64_t next_frame_time = nanos_since_boot() + dt;
|
||||
|
||||
while (!do_exit && panda->connected) {
|
||||
can_recv(pm);
|
||||
can_recv(panda, pm);
|
||||
|
||||
uint64_t cur_time = nanos_since_boot();
|
||||
int64_t remaining = next_frame_time - cur_time;
|
||||
|
@ -251,7 +247,7 @@ void can_recv_thread() {
|
|||
}
|
||||
}
|
||||
|
||||
void panda_state_thread(bool spoofing_started) {
|
||||
void panda_state_thread(Panda *&panda, bool spoofing_started) {
|
||||
LOGD("start panda state thread");
|
||||
PubMaster pm({"pandaState"});
|
||||
|
||||
|
@ -308,7 +304,7 @@ void panda_state_thread(bool spoofing_started) {
|
|||
|
||||
if (!safety_setter_thread_running) {
|
||||
safety_setter_thread_running = true;
|
||||
std::thread(safety_setter_thread).detach();
|
||||
std::thread(safety_setter_thread, panda).detach();
|
||||
} else {
|
||||
LOGW("Safety setter thread already running");
|
||||
}
|
||||
|
@ -352,8 +348,8 @@ void panda_state_thread(bool spoofing_started) {
|
|||
|
||||
if (Hardware::TICI()) {
|
||||
double read_time = millis_since_boot();
|
||||
ps.setVoltage(std::stoi(util::read_file("/sys/class/hwmon/hwmon1/in1_input")));
|
||||
ps.setCurrent(std::stoi(util::read_file("/sys/class/hwmon/hwmon1/curr1_input")));
|
||||
ps.setVoltage(std::atoi(util::read_file("/sys/class/hwmon/hwmon1/in1_input").c_str()));
|
||||
ps.setCurrent(std::atoi(util::read_file("/sys/class/hwmon/hwmon1/curr1_input").c_str()));
|
||||
read_time = millis_since_boot() - read_time;
|
||||
if (read_time > 50) {
|
||||
LOGW("reading hwmon took %lfms", read_time);
|
||||
|
@ -400,7 +396,7 @@ void panda_state_thread(bool spoofing_started) {
|
|||
}
|
||||
}
|
||||
|
||||
void hardware_control_thread() {
|
||||
void hardware_control_thread(Panda *panda) {
|
||||
LOGD("start hardware control thread");
|
||||
SubMaster sm({"deviceState", "driverCameraState"});
|
||||
|
||||
|
@ -481,7 +477,7 @@ static void pigeon_publish_raw(PubMaster &pm, const std::string &dat) {
|
|||
pm.send("ubloxRaw", msg);
|
||||
}
|
||||
|
||||
void pigeon_thread() {
|
||||
void pigeon_thread(Panda *panda) {
|
||||
PubMaster pm({"ubloxRaw"});
|
||||
bool ignition_last = false;
|
||||
|
||||
|
@ -554,28 +550,28 @@ void pigeon_thread() {
|
|||
delete pigeon;
|
||||
}
|
||||
|
||||
|
||||
int main() {
|
||||
int err;
|
||||
LOGW("starting boardd");
|
||||
|
||||
// set process priority and affinity
|
||||
err = set_realtime_priority(54);
|
||||
int err = set_realtime_priority(54);
|
||||
LOG("set priority returns %d", err);
|
||||
|
||||
err = set_core_affinity(Hardware::TICI() ? 4 : 3);
|
||||
LOG("set affinity returns %d", err);
|
||||
|
||||
while (!do_exit) {
|
||||
Panda *panda = nullptr;
|
||||
std::vector<std::thread> threads;
|
||||
threads.push_back(std::thread(panda_state_thread, getenv("STARTED") != nullptr));
|
||||
threads.emplace_back(panda_state_thread, std::ref(panda), getenv("STARTED") != nullptr);
|
||||
|
||||
// connect to the board
|
||||
if (usb_retry_connect()) {
|
||||
threads.push_back(std::thread(can_send_thread, getenv("FAKESEND") != nullptr));
|
||||
threads.push_back(std::thread(can_recv_thread));
|
||||
threads.push_back(std::thread(hardware_control_thread));
|
||||
threads.push_back(std::thread(pigeon_thread));
|
||||
panda = usb_retry_connect();
|
||||
if (panda != nullptr) {
|
||||
threads.emplace_back(can_send_thread, panda, getenv("FAKESEND") != nullptr);
|
||||
threads.emplace_back(can_recv_thread, panda);
|
||||
threads.emplace_back(hardware_control_thread, panda);
|
||||
threads.emplace_back(pigeon_thread, panda);
|
||||
}
|
||||
|
||||
for (auto &t : threads) t.join();
|
||||
|
|
|
@ -11,19 +11,30 @@
|
|||
#include "selfdrive/common/swaglog.h"
|
||||
#include "selfdrive/common/util.h"
|
||||
|
||||
static int init_usb_ctx(libusb_context *context) {
|
||||
int err = libusb_init(&context);
|
||||
if (err != 0) {
|
||||
LOGE("libusb initialization error");
|
||||
return err;
|
||||
}
|
||||
|
||||
#if LIBUSB_API_VERSION >= 0x01000106
|
||||
libusb_set_option(context, LIBUSB_OPTION_LOG_LEVEL, LIBUSB_LOG_LEVEL_INFO);
|
||||
#else
|
||||
libusb_set_debug(context, 3);
|
||||
#endif
|
||||
|
||||
return err;
|
||||
}
|
||||
|
||||
|
||||
Panda::Panda(std::string serial) {
|
||||
// init libusb
|
||||
ssize_t num_devices;
|
||||
libusb_device **dev_list = NULL;
|
||||
int err = libusb_init(&ctx);
|
||||
int err = init_usb_ctx(ctx);
|
||||
if (err != 0) { goto fail; }
|
||||
|
||||
#if LIBUSB_API_VERSION >= 0x01000106
|
||||
libusb_set_option(ctx, LIBUSB_OPTION_LOG_LEVEL, LIBUSB_LOG_LEVEL_INFO);
|
||||
#else
|
||||
libusb_set_debug(ctx, 3);
|
||||
#endif
|
||||
|
||||
// connect by serial
|
||||
num_devices = libusb_get_device_list(ctx, &dev_list);
|
||||
if (num_devices < 0) { goto fail; }
|
||||
|
@ -34,18 +45,21 @@ Panda::Panda(std::string serial) {
|
|||
libusb_open(dev_list[i], &dev_handle);
|
||||
if (dev_handle == NULL) { goto fail; }
|
||||
|
||||
unsigned char desc_serial[25];
|
||||
int ret = libusb_get_string_descriptor_ascii(dev_handle, desc.iSerialNumber, desc_serial, sizeof(desc_serial));
|
||||
unsigned char desc_serial[26] = { 0 };
|
||||
int ret = libusb_get_string_descriptor_ascii(dev_handle, desc.iSerialNumber, desc_serial, std::size(desc_serial));
|
||||
if (ret < 0) { goto fail; }
|
||||
|
||||
if (serial.empty() || serial.compare(reinterpret_cast<const char*>(desc_serial)) == 0) {
|
||||
usb_serial = std::string((char *)desc_serial, ret).c_str();
|
||||
if (serial.empty() || serial == usb_serial) {
|
||||
break;
|
||||
}
|
||||
libusb_close(dev_handle);
|
||||
dev_handle = NULL;
|
||||
}
|
||||
}
|
||||
if (dev_handle == NULL) goto fail;
|
||||
libusb_free_device_list(dev_list, 1);
|
||||
dev_list = nullptr;
|
||||
|
||||
if (libusb_kernel_driver_active(dev_handle, 0) == 1) {
|
||||
libusb_detach_kernel_driver(dev_handle, 0);
|
||||
|
@ -68,10 +82,10 @@ Panda::Panda(std::string serial) {
|
|||
return;
|
||||
|
||||
fail:
|
||||
cleanup();
|
||||
if (dev_list != NULL) {
|
||||
libusb_free_device_list(dev_list, 1);
|
||||
}
|
||||
cleanup();
|
||||
throw std::runtime_error("Error connecting to panda");
|
||||
}
|
||||
|
||||
|
@ -92,6 +106,47 @@ void Panda::cleanup() {
|
|||
}
|
||||
}
|
||||
|
||||
std::vector<std::string> Panda::list() {
|
||||
// init libusb
|
||||
ssize_t num_devices;
|
||||
libusb_context *context = NULL;
|
||||
libusb_device **dev_list = NULL;
|
||||
std::vector<std::string> serials;
|
||||
|
||||
int err = init_usb_ctx(context);
|
||||
if (err != 0) { return serials; }
|
||||
|
||||
num_devices = libusb_get_device_list(context, &dev_list);
|
||||
if (num_devices < 0) {
|
||||
LOGE("libusb can't get device list");
|
||||
goto finish;
|
||||
}
|
||||
for (size_t i = 0; i < num_devices; ++i) {
|
||||
libusb_device *device = dev_list[i];
|
||||
libusb_device_descriptor desc;
|
||||
libusb_get_device_descriptor(device, &desc);
|
||||
if (desc.idVendor == 0xbbaa && desc.idProduct == 0xddcc) {
|
||||
libusb_device_handle *handle = NULL;
|
||||
libusb_open(device, &handle);
|
||||
unsigned char desc_serial[26] = { 0 };
|
||||
int ret = libusb_get_string_descriptor_ascii(handle, desc.iSerialNumber, desc_serial, std::size(desc_serial));
|
||||
libusb_close(handle);
|
||||
|
||||
if (ret < 0) { goto finish; }
|
||||
serials.push_back(std::string((char *)desc_serial, ret).c_str());
|
||||
}
|
||||
}
|
||||
|
||||
finish:
|
||||
if (dev_list != NULL) {
|
||||
libusb_free_device_list(dev_list, 1);
|
||||
}
|
||||
if (context) {
|
||||
libusb_exit(context);
|
||||
}
|
||||
return serials;
|
||||
}
|
||||
|
||||
void Panda::handle_usb_issue(int err, const char func[]) {
|
||||
LOGE_100("usb error %d \"%s\" in %s", err, libusb_strerror((enum libusb_error)err), func);
|
||||
if (err == LIBUSB_ERROR_NO_DEVICE) {
|
||||
|
|
|
@ -52,11 +52,15 @@ class Panda {
|
|||
Panda(std::string serial="");
|
||||
~Panda();
|
||||
|
||||
std::string usb_serial;
|
||||
std::atomic<bool> connected = true;
|
||||
std::atomic<bool> comms_healthy = true;
|
||||
cereal::PandaState::PandaType hw_type = cereal::PandaState::PandaType::UNKNOWN;
|
||||
bool has_rtc = false;
|
||||
|
||||
// Static functions
|
||||
static std::vector<std::string> list();
|
||||
|
||||
// HW communication
|
||||
int usb_write(uint8_t bRequest, uint16_t wValue, uint16_t wIndex, unsigned int timeout=TIMEOUT);
|
||||
int usb_read(uint8_t bRequest, uint16_t wValue, uint16_t wIndex, unsigned char *data, uint16_t wLength, unsigned int timeout=TIMEOUT);
|
||||
|
|
|
@ -193,7 +193,7 @@ void handle_tty_issue(int err, const char func[]) {
|
|||
}
|
||||
|
||||
void TTYPigeon::connect(const char * tty) {
|
||||
pigeon_tty_fd = open(tty, O_RDWR);
|
||||
pigeon_tty_fd = HANDLE_EINTR(open(tty, O_RDWR));
|
||||
if (pigeon_tty_fd < 0) {
|
||||
handle_tty_issue(errno, __func__);
|
||||
assert(pigeon_tty_fd >= 0);
|
||||
|
@ -253,7 +253,7 @@ void TTYPigeon::set_baud(int baud) {
|
|||
}
|
||||
|
||||
void TTYPigeon::send(const std::string &s) {
|
||||
int err = write(pigeon_tty_fd, s.data(), s.length());
|
||||
int err = HANDLE_EINTR(write(pigeon_tty_fd, s.data(), s.length()));
|
||||
|
||||
if(err < 0) { handle_tty_issue(err, __func__); }
|
||||
err = tcdrain(pigeon_tty_fd);
|
||||
|
|
|
@ -28,11 +28,11 @@
|
|||
|
||||
#define UI_BUF_COUNT 4
|
||||
|
||||
#define LOG_CAMERA_ID_FCAMERA 0
|
||||
#define LOG_CAMERA_ID_DCAMERA 1
|
||||
#define LOG_CAMERA_ID_ECAMERA 2
|
||||
#define LOG_CAMERA_ID_QCAMERA 3
|
||||
#define LOG_CAMERA_ID_MAX 4
|
||||
enum CameraType {
|
||||
RoadCam = 0,
|
||||
DriverCam,
|
||||
WideRoadCam
|
||||
};
|
||||
|
||||
const bool env_send_driver = getenv("SEND_DRIVER") != NULL;
|
||||
const bool env_send_road = getenv("SEND_ROAD") != NULL;
|
||||
|
@ -49,6 +49,7 @@ typedef struct CameraInfo {
|
|||
} CameraInfo;
|
||||
|
||||
typedef struct LogCameraInfo {
|
||||
CameraType type;
|
||||
const char* filename;
|
||||
const char* frame_packet_name;
|
||||
const char* encode_idx_name;
|
||||
|
@ -60,6 +61,7 @@ typedef struct LogCameraInfo {
|
|||
bool downscale;
|
||||
bool has_qcamera;
|
||||
bool trigger_rotate;
|
||||
bool enable;
|
||||
} LogCameraInfo;
|
||||
|
||||
typedef struct FrameMetadata {
|
||||
|
|
|
@ -32,7 +32,7 @@ const uint16_t INFINITY_DAC = 364;
|
|||
extern ExitHandler do_exit;
|
||||
|
||||
static int cam_ioctl(int fd, unsigned long int request, void *arg, const char *log_msg = nullptr) {
|
||||
int err = ioctl(fd, request, arg);
|
||||
int err = HANDLE_EINTR(ioctl(fd, request, arg));
|
||||
if (err != 0 && log_msg) {
|
||||
LOG(util::string_format("%s: %d", log_msg, err).c_str());
|
||||
}
|
||||
|
@ -82,7 +82,7 @@ static void camera_release_buffer(void* cookie, int buf_idx) {
|
|||
CameraState *s = (CameraState *)cookie;
|
||||
// printf("camera_release_buffer %d\n", buf_idx);
|
||||
s->ss[0].qbuf_info[buf_idx].dirty_buf = 1;
|
||||
ioctl(s->isp_fd, VIDIOC_MSM_ISP_ENQUEUE_BUF, &s->ss[0].qbuf_info[buf_idx]);
|
||||
HANDLE_EINTR(ioctl(s->isp_fd, VIDIOC_MSM_ISP_ENQUEUE_BUF, &s->ss[0].qbuf_info[buf_idx]));
|
||||
}
|
||||
|
||||
int sensor_write_regs(CameraState *s, struct msm_camera_i2c_reg_array* arr, size_t size, msm_camera_i2c_data_type data_type) {
|
||||
|
@ -94,7 +94,7 @@ int sensor_write_regs(CameraState *s, struct msm_camera_i2c_reg_array* arr, size
|
|||
.delay = 0,
|
||||
};
|
||||
sensorb_cfg_data cfg_data = {.cfgtype = CFG_WRITE_I2C_ARRAY, .cfg.setting = &out_settings};
|
||||
return ioctl(s->sensor_fd, VIDIOC_MSM_SENSOR_CFG, &cfg_data);
|
||||
return HANDLE_EINTR(ioctl(s->sensor_fd, VIDIOC_MSM_SENSOR_CFG, &cfg_data));
|
||||
}
|
||||
|
||||
static int imx298_apply_exposure(CameraState *s, int gain, int integ_lines, uint32_t frame_length) {
|
||||
|
@ -399,7 +399,7 @@ static void sensors_init(MultiCameraState *s) {
|
|||
.output_format = MSM_SENSOR_BAYER,
|
||||
}};
|
||||
|
||||
unique_fd sensorinit_fd = open("/dev/v4l-subdev11", O_RDWR | O_NONBLOCK);
|
||||
unique_fd sensorinit_fd = HANDLE_EINTR(open("/dev/v4l-subdev11", O_RDWR | O_NONBLOCK));
|
||||
assert(sensorinit_fd >= 0);
|
||||
for (auto &info : slave_infos) {
|
||||
info.power_setting_array.power_setting = &info.power_setting_array.power_setting_a[0];
|
||||
|
@ -419,29 +419,29 @@ static void camera_open(CameraState *s, bool is_road_cam) {
|
|||
// open devices
|
||||
const char *sensor_dev;
|
||||
if (is_road_cam) {
|
||||
s->csid_fd = open("/dev/v4l-subdev3", O_RDWR | O_NONBLOCK);
|
||||
s->csid_fd = HANDLE_EINTR(open("/dev/v4l-subdev3", O_RDWR | O_NONBLOCK));
|
||||
assert(s->csid_fd >= 0);
|
||||
s->csiphy_fd = open("/dev/v4l-subdev0", O_RDWR | O_NONBLOCK);
|
||||
s->csiphy_fd = HANDLE_EINTR(open("/dev/v4l-subdev0", O_RDWR | O_NONBLOCK));
|
||||
assert(s->csiphy_fd >= 0);
|
||||
sensor_dev = "/dev/v4l-subdev17";
|
||||
s->isp_fd = open("/dev/v4l-subdev13", O_RDWR | O_NONBLOCK);
|
||||
s->isp_fd = HANDLE_EINTR(open("/dev/v4l-subdev13", O_RDWR | O_NONBLOCK));
|
||||
assert(s->isp_fd >= 0);
|
||||
s->actuator_fd = open("/dev/v4l-subdev7", O_RDWR | O_NONBLOCK);
|
||||
s->actuator_fd = HANDLE_EINTR(open("/dev/v4l-subdev7", O_RDWR | O_NONBLOCK));
|
||||
assert(s->actuator_fd >= 0);
|
||||
} else {
|
||||
s->csid_fd = open("/dev/v4l-subdev5", O_RDWR | O_NONBLOCK);
|
||||
s->csid_fd = HANDLE_EINTR(open("/dev/v4l-subdev5", O_RDWR | O_NONBLOCK));
|
||||
assert(s->csid_fd >= 0);
|
||||
s->csiphy_fd = open("/dev/v4l-subdev2", O_RDWR | O_NONBLOCK);
|
||||
s->csiphy_fd = HANDLE_EINTR(open("/dev/v4l-subdev2", O_RDWR | O_NONBLOCK));
|
||||
assert(s->csiphy_fd >= 0);
|
||||
sensor_dev = "/dev/v4l-subdev18";
|
||||
s->isp_fd = open("/dev/v4l-subdev14", O_RDWR | O_NONBLOCK);
|
||||
s->isp_fd = HANDLE_EINTR(open("/dev/v4l-subdev14", O_RDWR | O_NONBLOCK));
|
||||
assert(s->isp_fd >= 0);
|
||||
}
|
||||
|
||||
// wait for sensor device
|
||||
// on first startup, these devices aren't present yet
|
||||
for (int i = 0; i < 10; i++) {
|
||||
s->sensor_fd = open(sensor_dev, O_RDWR | O_NONBLOCK);
|
||||
s->sensor_fd = HANDLE_EINTR(open(sensor_dev, O_RDWR | O_NONBLOCK));
|
||||
if (s->sensor_fd >= 0) break;
|
||||
LOGW("waiting for sensors...");
|
||||
util::sleep_for(1000); // sleep one second
|
||||
|
@ -797,7 +797,7 @@ void actuator_move(CameraState *s, uint16_t target) {
|
|||
.curr_lens_pos = s->cur_lens_pos,
|
||||
.ringing_params = &actuator_ringing_params,
|
||||
};
|
||||
ioctl(s->actuator_fd, VIDIOC_MSM_ACTUATOR_CFG, &actuator_cfg_data);
|
||||
HANDLE_EINTR(ioctl(s->actuator_fd, VIDIOC_MSM_ACTUATOR_CFG, &actuator_cfg_data));
|
||||
|
||||
s->cur_step_pos = dest_step_pos;
|
||||
s->cur_lens_pos = actuator_cfg_data.cfg.move.curr_lens_pos;
|
||||
|
@ -927,15 +927,15 @@ void cameras_open(MultiCameraState *s) {
|
|||
{.vfe_intf = VFE0, .intftype = RDI2, .num_cids = 1, .cids[0] = CID2, .csid = CSID0},
|
||||
},
|
||||
};
|
||||
s->msmcfg_fd = open("/dev/media0", O_RDWR | O_NONBLOCK);
|
||||
s->msmcfg_fd = HANDLE_EINTR(open("/dev/media0", O_RDWR | O_NONBLOCK));
|
||||
assert(s->msmcfg_fd >= 0);
|
||||
|
||||
sensors_init(s);
|
||||
|
||||
s->v4l_fd = open("/dev/video0", O_RDWR | O_NONBLOCK);
|
||||
s->v4l_fd = HANDLE_EINTR(open("/dev/video0", O_RDWR | O_NONBLOCK));
|
||||
assert(s->v4l_fd >= 0);
|
||||
|
||||
s->ispif_fd = open("/dev/v4l-subdev15", O_RDWR | O_NONBLOCK);
|
||||
s->ispif_fd = HANDLE_EINTR(open("/dev/v4l-subdev15", O_RDWR | O_NONBLOCK));
|
||||
assert(s->ispif_fd >= 0);
|
||||
|
||||
// ISPIF: stop
|
||||
|
@ -962,7 +962,7 @@ void cameras_open(MultiCameraState *s) {
|
|||
|
||||
// ISPIF: set vfe info
|
||||
struct ispif_cfg_data ispif_cfg_data = {.cfg_type = ISPIF_SET_VFE_INFO, .vfe_info.num_vfe = 2};
|
||||
int err = ioctl(s->ispif_fd, VIDIOC_MSM_ISPIF_CFG, &ispif_cfg_data);
|
||||
int err = HANDLE_EINTR(ioctl(s->ispif_fd, VIDIOC_MSM_ISPIF_CFG, &ispif_cfg_data));
|
||||
LOG("ispif set vfe info: %d", err);
|
||||
|
||||
// ISPIF: setup
|
||||
|
@ -1142,7 +1142,7 @@ void cameras_run(MultiCameraState *s) {
|
|||
CameraState *c = cameras[i];
|
||||
|
||||
struct v4l2_event ev = {};
|
||||
ret = ioctl(c->isp_fd, VIDIOC_DQEVENT, &ev);
|
||||
ret = HANDLE_EINTR(ioctl(c->isp_fd, VIDIOC_DQEVENT, &ev));
|
||||
const msm_isp_event_data *isp_event_data = (const msm_isp_event_data *)ev.u.data;
|
||||
|
||||
if (ev.type == ISP_EVENT_BUF_DIVERT) {
|
||||
|
@ -1157,7 +1157,7 @@ void cameras_run(MultiCameraState *s) {
|
|||
parse_autofocus(c, (uint8_t *)(ss.bufs[buf_idx].addr));
|
||||
}
|
||||
ss.qbuf_info[buf_idx].dirty_buf = 1;
|
||||
ioctl(c->isp_fd, VIDIOC_MSM_ISP_ENQUEUE_BUF, &ss.qbuf_info[buf_idx]);
|
||||
HANDLE_EINTR(ioctl(c->isp_fd, VIDIOC_MSM_ISP_ENQUEUE_BUF, &ss.qbuf_info[buf_idx]));
|
||||
}
|
||||
|
||||
} else if (ev.type == ISP_EVENT_EOF) {
|
||||
|
|
|
@ -68,7 +68,7 @@ int cam_control(int fd, int op_code, void *handle, int size) {
|
|||
camcontrol.handle_type = CAM_HANDLE_USER_POINTER;
|
||||
}
|
||||
|
||||
int ret = ioctl(fd, VIDIOC_CAM_CONTROL, &camcontrol);
|
||||
int ret = HANDLE_EINTR(ioctl(fd, VIDIOC_CAM_CONTROL, &camcontrol));
|
||||
if (ret == -1) {
|
||||
printf("OP CODE ERR - %d \n", op_code);
|
||||
perror("wat");
|
||||
|
@ -76,12 +76,30 @@ int cam_control(int fd, int op_code, void *handle, int size) {
|
|||
return ret;
|
||||
}
|
||||
|
||||
std::optional<int32_t> device_acquire(int fd, int32_t session_handle, void *data) {
|
||||
struct cam_acquire_dev_cmd cmd = {
|
||||
.session_handle = session_handle,
|
||||
.handle_type = CAM_HANDLE_USER_POINTER,
|
||||
.num_resources = (uint32_t)(data ? 1 : 0),
|
||||
.resource_hdl = (uint64_t)data,
|
||||
};
|
||||
int err = cam_control(fd, CAM_ACQUIRE_DEV, &cmd, sizeof(cmd));
|
||||
return err == 0 ? std::make_optional(cmd.dev_handle) : std::nullopt;
|
||||
};
|
||||
|
||||
int device_config(int fd, int32_t session_handle, int32_t dev_handle, uint64_t packet_handle) {
|
||||
struct cam_config_dev_cmd cmd = {
|
||||
.session_handle = session_handle,
|
||||
.dev_handle = dev_handle,
|
||||
.packet_handle = packet_handle,
|
||||
};
|
||||
return cam_control(fd, CAM_CONFIG_DEV, &cmd, sizeof(cmd));
|
||||
}
|
||||
|
||||
int device_control(int fd, int op_code, int session_handle, int dev_handle) {
|
||||
// start stop and release are all the same
|
||||
static struct cam_release_dev_cmd release_dev_cmd;
|
||||
release_dev_cmd.session_handle = session_handle;
|
||||
release_dev_cmd.dev_handle = dev_handle;
|
||||
return cam_control(fd, op_code, &release_dev_cmd, sizeof(release_dev_cmd));
|
||||
struct cam_start_stop_dev_cmd cmd { .session_handle = session_handle, .dev_handle = dev_handle };
|
||||
return cam_control(fd, op_code, &cmd, sizeof(cmd));
|
||||
}
|
||||
|
||||
void *alloc_w_mmu_hdl(int video0_fd, int len, uint32_t *handle, int align = 8, int flags = CAM_MEM_FLAG_KMD_ACCESS | CAM_MEM_FLAG_UMD_ACCESS | CAM_MEM_FLAG_CMD_BUF_TYPE,
|
||||
|
@ -151,13 +169,7 @@ void sensors_poke(struct CameraState *s, int request_id) {
|
|||
pkt->header.op_code = 0x7f;
|
||||
pkt->header.request_id = request_id;
|
||||
|
||||
struct cam_config_dev_cmd config_dev_cmd = {};
|
||||
config_dev_cmd.session_handle = s->session_handle;
|
||||
config_dev_cmd.dev_handle = s->sensor_dev_handle;
|
||||
config_dev_cmd.offset = 0;
|
||||
config_dev_cmd.packet_handle = cam_packet_handle;
|
||||
|
||||
int ret = cam_control(s->sensor_fd, CAM_CONFIG_DEV, &config_dev_cmd, sizeof(config_dev_cmd));
|
||||
int ret = device_config(s->sensor_fd, s->session_handle, s->sensor_dev_handle, cam_packet_handle);
|
||||
assert(ret == 0);
|
||||
|
||||
munmap(pkt, size);
|
||||
|
@ -186,13 +198,7 @@ void sensors_i2c(struct CameraState *s, struct i2c_random_wr_payload* dat, int l
|
|||
i2c_random_wr->header.addr_type = CAMERA_SENSOR_I2C_TYPE_WORD;
|
||||
memcpy(i2c_random_wr->random_wr_payload, dat, len*sizeof(struct i2c_random_wr_payload));
|
||||
|
||||
struct cam_config_dev_cmd config_dev_cmd = {};
|
||||
config_dev_cmd.session_handle = s->session_handle;
|
||||
config_dev_cmd.dev_handle = s->sensor_dev_handle;
|
||||
config_dev_cmd.offset = 0;
|
||||
config_dev_cmd.packet_handle = cam_packet_handle;
|
||||
|
||||
int ret = cam_control(s->sensor_fd, CAM_CONFIG_DEV, &config_dev_cmd, sizeof(config_dev_cmd));
|
||||
int ret = device_config(s->sensor_fd, s->session_handle, s->sensor_dev_handle, cam_packet_handle);
|
||||
assert(ret == 0);
|
||||
|
||||
munmap(i2c_random_wr, buf_desc[0].size);
|
||||
|
@ -432,13 +438,8 @@ void config_isp(struct CameraState *s, int io_mem_handle, int fence, int request
|
|||
io_cfg[0].framedrop_pattern = 0x1;
|
||||
}
|
||||
|
||||
struct cam_config_dev_cmd config_dev_cmd = {};
|
||||
config_dev_cmd.session_handle = s->session_handle;
|
||||
config_dev_cmd.dev_handle = s->isp_dev_handle;
|
||||
config_dev_cmd.offset = 0;
|
||||
config_dev_cmd.packet_handle = cam_packet_handle;
|
||||
|
||||
int ret = cam_control(s->multi_cam_state->isp_fd, CAM_CONFIG_DEV, &config_dev_cmd, sizeof(config_dev_cmd));
|
||||
int ret = device_config(s->multi_cam_state->isp_fd, s->session_handle, s->isp_dev_handle, cam_packet_handle);
|
||||
assert(ret == 0);
|
||||
if (ret != 0) {
|
||||
printf("ISP CONFIG FAILED\n");
|
||||
}
|
||||
|
@ -493,7 +494,7 @@ void enqueue_buffer(struct CameraState *s, int i, bool dp) {
|
|||
struct cam_mem_mgr_map_cmd mem_mgr_map_cmd = {0};
|
||||
mem_mgr_map_cmd.mmu_hdls[0] = s->multi_cam_state->device_iommu;
|
||||
mem_mgr_map_cmd.num_hdl = 1;
|
||||
mem_mgr_map_cmd.flags = 1;
|
||||
mem_mgr_map_cmd.flags = CAM_MEM_FLAG_HW_READ_WRITE;
|
||||
mem_mgr_map_cmd.fd = s->buf.camera_bufs[i].fd;
|
||||
ret = cam_control(s->multi_cam_state->video0_fd, CAM_REQ_MGR_MAP_BUF, &mem_mgr_map_cmd, sizeof(mem_mgr_map_cmd));
|
||||
// LOGD("map buf req: (fd: %d) 0x%x %d", s->bufs[i].fd, mem_mgr_map_cmd.out.buf_handle, ret);
|
||||
|
@ -540,41 +541,26 @@ static void camera_init(MultiCameraState *multi_cam_state, VisionIpcServer * v,
|
|||
s->buf.init(device_id, ctx, s, v, FRAME_BUF_COUNT, rgb_type, yuv_type);
|
||||
}
|
||||
|
||||
// TODO: refactor this to somewhere nicer, perhaps use in camera_qcom as well
|
||||
static int open_v4l_by_name_and_index(const char name[], int index, int flags) {
|
||||
char nbuf[0x100];
|
||||
int v4l_index = 0;
|
||||
int cnt_index = index;
|
||||
while (true) {
|
||||
snprintf(nbuf, sizeof(nbuf), "/sys/class/video4linux/v4l-subdev%d/name", v4l_index);
|
||||
FILE *f = fopen(nbuf, "rb");
|
||||
if (f == NULL) return -1;
|
||||
int len = fread(nbuf, 1, sizeof(nbuf), f);
|
||||
fclose(f);
|
||||
|
||||
// name ends with '\n', remove it
|
||||
if (len < 1) return -1;
|
||||
nbuf[len-1] = '\0';
|
||||
|
||||
if (strcmp(nbuf, name) == 0) {
|
||||
if (cnt_index == 0) {
|
||||
snprintf(nbuf, sizeof(nbuf), "/dev/v4l-subdev%d", v4l_index);
|
||||
LOGD("open %s for %s index %d", nbuf, name, index);
|
||||
return open(nbuf, flags);
|
||||
int open_v4l_by_name_and_index(const char name[], int index, int flags = O_RDWR | O_NONBLOCK) {
|
||||
for (int v4l_index = 0; /**/; ++v4l_index) {
|
||||
std::string v4l_name = util::read_file(util::string_format("/sys/class/video4linux/v4l-subdev%d/name", v4l_index));
|
||||
if (v4l_name.empty()) return -1;
|
||||
if (v4l_name.find(name) == 0) {
|
||||
if (index == 0) {
|
||||
return open(util::string_format("/dev/v4l-subdev%d", v4l_index).c_str(), flags);
|
||||
}
|
||||
cnt_index--;
|
||||
index--;
|
||||
}
|
||||
v4l_index++;
|
||||
}
|
||||
}
|
||||
|
||||
static void camera_open(CameraState *s) {
|
||||
int ret;
|
||||
s->sensor_fd = open_v4l_by_name_and_index("cam-sensor-driver", s->camera_num, O_RDWR | O_NONBLOCK);
|
||||
s->sensor_fd = open_v4l_by_name_and_index("cam-sensor-driver", s->camera_num);
|
||||
assert(s->sensor_fd >= 0);
|
||||
LOGD("opened sensor");
|
||||
|
||||
s->csiphy_fd = open_v4l_by_name_and_index("cam-csiphy-driver", s->camera_num, O_RDWR | O_NONBLOCK);
|
||||
s->csiphy_fd = open_v4l_by_name_and_index("cam-csiphy-driver", s->camera_num);
|
||||
assert(s->csiphy_fd >= 0);
|
||||
LOGD("opened csiphy");
|
||||
|
||||
|
@ -582,26 +568,20 @@ static void camera_open(CameraState *s) {
|
|||
LOGD("-- Probing sensor %d", s->camera_num);
|
||||
sensors_init(s->multi_cam_state->video0_fd, s->sensor_fd, s->camera_num);
|
||||
|
||||
memset(&s->req_mgr_session_info, 0, sizeof(s->req_mgr_session_info));
|
||||
ret = cam_control(s->multi_cam_state->video0_fd, CAM_REQ_MGR_CREATE_SESSION, &s->req_mgr_session_info, sizeof(s->req_mgr_session_info));
|
||||
LOGD("get session: %d 0x%X", ret, s->req_mgr_session_info.session_hdl);
|
||||
s->session_handle = s->req_mgr_session_info.session_hdl;
|
||||
// create session
|
||||
struct cam_req_mgr_session_info session_info = {};
|
||||
ret = cam_control(s->multi_cam_state->video0_fd, CAM_REQ_MGR_CREATE_SESSION, &session_info, sizeof(session_info));
|
||||
LOGD("get session: %d 0x%X", ret, session_info.session_hdl);
|
||||
s->session_handle = session_info.session_hdl;
|
||||
|
||||
// access the sensor
|
||||
LOGD("-- Accessing sensor");
|
||||
static struct cam_acquire_dev_cmd acquire_dev_cmd = {0};
|
||||
acquire_dev_cmd.session_handle = s->session_handle;
|
||||
acquire_dev_cmd.handle_type = CAM_HANDLE_USER_POINTER;
|
||||
ret = cam_control(s->sensor_fd, CAM_ACQUIRE_DEV, &acquire_dev_cmd, sizeof(acquire_dev_cmd));
|
||||
LOGD("acquire sensor dev: %d", ret);
|
||||
s->sensor_dev_handle = acquire_dev_cmd.dev_handle;
|
||||
auto sensor_dev_handle = device_acquire(s->sensor_fd, s->session_handle, nullptr);
|
||||
assert(sensor_dev_handle);
|
||||
s->sensor_dev_handle = *sensor_dev_handle;
|
||||
LOGD("acquire sensor dev");
|
||||
|
||||
static struct cam_isp_resource isp_resource = {0};
|
||||
|
||||
acquire_dev_cmd.session_handle = s->session_handle;
|
||||
acquire_dev_cmd.handle_type = CAM_HANDLE_USER_POINTER;
|
||||
acquire_dev_cmd.num_resources = 1;
|
||||
acquire_dev_cmd.resource_hdl = (uint64_t)&isp_resource;
|
||||
|
||||
isp_resource.resource_id = CAM_ISP_RES_ID_PORT;
|
||||
isp_resource.length = sizeof(struct cam_isp_in_port_info) + sizeof(struct cam_isp_out_port_info)*(1-1);
|
||||
isp_resource.handle_type = CAM_HANDLE_USER_POINTER;
|
||||
|
@ -663,23 +643,17 @@ static void camera_open(CameraState *s) {
|
|||
.comp_grp_id = 0x0, .split_point = 0x0, .secure_mode = 0x0,
|
||||
};
|
||||
|
||||
ret = cam_control(s->multi_cam_state->isp_fd, CAM_ACQUIRE_DEV, &acquire_dev_cmd, sizeof(acquire_dev_cmd));
|
||||
LOGD("acquire isp dev: %d", ret);
|
||||
auto isp_dev_handle = device_acquire(s->multi_cam_state->isp_fd, s->session_handle, &isp_resource);
|
||||
assert(isp_dev_handle);
|
||||
s->isp_dev_handle = *isp_dev_handle;
|
||||
LOGD("acquire isp dev");
|
||||
free(in_port_info);
|
||||
s->isp_dev_handle = acquire_dev_cmd.dev_handle;
|
||||
|
||||
static struct cam_csiphy_acquire_dev_info csiphy_acquire_dev_info = {0};
|
||||
csiphy_acquire_dev_info.combo_mode = 0;
|
||||
|
||||
acquire_dev_cmd.session_handle = s->session_handle;
|
||||
acquire_dev_cmd.handle_type = CAM_HANDLE_USER_POINTER;
|
||||
acquire_dev_cmd.num_resources = 1;
|
||||
acquire_dev_cmd.resource_hdl = (uint64_t)&csiphy_acquire_dev_info;
|
||||
|
||||
ret = cam_control(s->csiphy_fd, CAM_ACQUIRE_DEV, &acquire_dev_cmd, sizeof(acquire_dev_cmd));
|
||||
|
||||
LOGD("acquire csiphy dev: %d", ret);
|
||||
s->csiphy_dev_handle = acquire_dev_cmd.dev_handle;
|
||||
struct cam_csiphy_acquire_dev_info csiphy_acquire_dev_info = {.combo_mode = 0};
|
||||
auto csiphy_dev_handle = device_acquire(s->csiphy_fd, s->session_handle, &csiphy_acquire_dev_info);
|
||||
assert(csiphy_dev_handle);
|
||||
s->csiphy_dev_handle = *csiphy_dev_handle;
|
||||
LOGD("acquire csiphy dev");
|
||||
|
||||
// acquires done
|
||||
|
||||
|
@ -719,17 +693,13 @@ static void camera_open(CameraState *s) {
|
|||
csiphy_info->settle_time = MIPI_SETTLE_CNT * 200000000ULL;
|
||||
csiphy_info->data_rate = 48000000; // Calculated by camera_freqs.py
|
||||
|
||||
static struct cam_config_dev_cmd config_dev_cmd = {};
|
||||
config_dev_cmd.session_handle = s->session_handle;
|
||||
config_dev_cmd.dev_handle = s->csiphy_dev_handle;
|
||||
config_dev_cmd.offset = 0;
|
||||
config_dev_cmd.packet_handle = cam_packet_handle;
|
||||
|
||||
int ret = cam_control(s->csiphy_fd, CAM_CONFIG_DEV, &config_dev_cmd, sizeof(config_dev_cmd));
|
||||
int ret = device_config(s->csiphy_fd, s->session_handle, s->csiphy_dev_handle, cam_packet_handle);
|
||||
assert(ret == 0);
|
||||
|
||||
release(s->multi_cam_state->video0_fd, buf_desc[0].mem_handle);
|
||||
release(s->multi_cam_state->video0_fd, cam_packet_handle);
|
||||
munmap(csiphy_info, buf_desc[0].size);
|
||||
release_fd(s->multi_cam_state->video0_fd, buf_desc[0].mem_handle);
|
||||
munmap(pkt, size);
|
||||
release_fd(s->multi_cam_state->video0_fd, cam_packet_handle);
|
||||
}
|
||||
|
||||
// link devices
|
||||
|
@ -744,19 +714,19 @@ static void camera_open(CameraState *s) {
|
|||
s->link_handle = req_mgr_link_info.link_hdl;
|
||||
|
||||
static struct cam_req_mgr_link_control req_mgr_link_control = {0};
|
||||
req_mgr_link_control.ops = 0;
|
||||
req_mgr_link_control.ops = CAM_REQ_MGR_LINK_ACTIVATE;
|
||||
req_mgr_link_control.session_hdl = s->session_handle;
|
||||
req_mgr_link_control.num_links = 1;
|
||||
req_mgr_link_control.link_hdls[0] = s->link_handle;
|
||||
ret = cam_control(s->multi_cam_state->video0_fd, CAM_REQ_MGR_LINK_CONTROL, &req_mgr_link_control, sizeof(req_mgr_link_control));
|
||||
LOGD("link control: %d", ret);
|
||||
|
||||
LOGD("start csiphy: %d", ret);
|
||||
ret = device_control(s->csiphy_fd, CAM_START_DEV, s->session_handle, s->csiphy_dev_handle);
|
||||
LOGD("start isp: %d", ret);
|
||||
LOGD("start csiphy: %d", ret);
|
||||
ret = device_control(s->multi_cam_state->isp_fd, CAM_START_DEV, s->session_handle, s->isp_dev_handle);
|
||||
LOGD("start sensor: %d", ret);
|
||||
LOGD("start isp: %d", ret);
|
||||
ret = device_control(s->sensor_fd, CAM_START_DEV, s->session_handle, s->sensor_dev_handle);
|
||||
LOGD("start sensor: %d", ret);
|
||||
|
||||
enqueue_req_multi(s, 1, FRAME_BUF_COUNT, 0);
|
||||
}
|
||||
|
@ -781,17 +751,17 @@ void cameras_open(MultiCameraState *s) {
|
|||
|
||||
LOG("-- Opening devices");
|
||||
// video0 is req_mgr, the target of many ioctls
|
||||
s->video0_fd = open("/dev/v4l/by-path/platform-soc:qcom_cam-req-mgr-video-index0", O_RDWR | O_NONBLOCK);
|
||||
s->video0_fd = HANDLE_EINTR(open("/dev/v4l/by-path/platform-soc:qcom_cam-req-mgr-video-index0", O_RDWR | O_NONBLOCK));
|
||||
assert(s->video0_fd >= 0);
|
||||
LOGD("opened video0");
|
||||
|
||||
// video1 is cam_sync, the target of some ioctls
|
||||
s->video1_fd = open("/dev/v4l/by-path/platform-cam_sync-video-index0", O_RDWR | O_NONBLOCK);
|
||||
s->video1_fd = HANDLE_EINTR(open("/dev/v4l/by-path/platform-cam_sync-video-index0", O_RDWR | O_NONBLOCK));
|
||||
assert(s->video1_fd >= 0);
|
||||
LOGD("opened video1");
|
||||
|
||||
// looks like there's only one of these
|
||||
s->isp_fd = open("/dev/v4l-subdev1", O_RDWR | O_NONBLOCK);
|
||||
s->isp_fd = HANDLE_EINTR(open("/dev/v4l-subdev1", O_RDWR | O_NONBLOCK));
|
||||
assert(s->isp_fd >= 0);
|
||||
LOGD("opened isp");
|
||||
|
||||
|
@ -812,9 +782,9 @@ void cameras_open(MultiCameraState *s) {
|
|||
// subscribe
|
||||
LOG("-- Subscribing");
|
||||
static struct v4l2_event_subscription sub = {0};
|
||||
sub.type = 0x8000000;
|
||||
sub.type = V4L_EVENT_CAM_REQ_MGR_EVENT;
|
||||
sub.id = 2; // should use boot time for sof
|
||||
ret = ioctl(s->video0_fd, VIDIOC_SUBSCRIBE_EVENT, &sub);
|
||||
ret = HANDLE_EINTR(ioctl(s->video0_fd, VIDIOC_SUBSCRIBE_EVENT, &sub));
|
||||
printf("req mgr subscribe: %d\n", ret);
|
||||
|
||||
camera_open(&s->road_cam);
|
||||
|
@ -839,7 +809,7 @@ static void camera_close(CameraState *s) {
|
|||
// link control stop
|
||||
LOG("-- Stop link control");
|
||||
static struct cam_req_mgr_link_control req_mgr_link_control = {0};
|
||||
req_mgr_link_control.ops = 1;
|
||||
req_mgr_link_control.ops = CAM_REQ_MGR_LINK_DEACTIVATE;
|
||||
req_mgr_link_control.session_hdl = s->session_handle;
|
||||
req_mgr_link_control.num_links = 1;
|
||||
req_mgr_link_control.link_hdls[0] = s->link_handle;
|
||||
|
@ -863,7 +833,9 @@ static void camera_close(CameraState *s) {
|
|||
ret = device_control(s->csiphy_fd, CAM_RELEASE_DEV, s->session_handle, s->csiphy_dev_handle);
|
||||
LOGD("release csiphy: %d", ret);
|
||||
|
||||
ret = cam_control(s->multi_cam_state->video0_fd, CAM_REQ_MGR_DESTROY_SESSION, &s->req_mgr_session_info, sizeof(s->req_mgr_session_info));
|
||||
// destroyed session
|
||||
struct cam_req_mgr_session_info session_info = {.session_hdl = s->session_handle};
|
||||
ret = cam_control(s->multi_cam_state->video0_fd, CAM_REQ_MGR_DESTROY_SESSION, &session_info, sizeof(session_info));
|
||||
LOGD("destroyed session: %d", ret);
|
||||
}
|
||||
|
||||
|
@ -1096,22 +1068,26 @@ void cameras_run(MultiCameraState *s) {
|
|||
if (!fds[0].revents) continue;
|
||||
|
||||
struct v4l2_event ev = {0};
|
||||
ret = ioctl(fds[0].fd, VIDIOC_DQEVENT, &ev);
|
||||
if (ev.type == 0x8000000) {
|
||||
struct cam_req_mgr_message *event_data = (struct cam_req_mgr_message *)ev.u.data;
|
||||
// LOGD("v4l2 event: sess_hdl %d, link_hdl %d, frame_id %d, req_id %lld, timestamp 0x%llx, sof_status %d\n", event_data->session_hdl, event_data->u.frame_msg.link_hdl, event_data->u.frame_msg.frame_id, event_data->u.frame_msg.request_id, event_data->u.frame_msg.timestamp, event_data->u.frame_msg.sof_status);
|
||||
// printf("sess_hdl %d, link_hdl %d, frame_id %lu, req_id %lu, timestamp 0x%lx, sof_status %d\n", event_data->session_hdl, event_data->u.frame_msg.link_hdl, event_data->u.frame_msg.frame_id, event_data->u.frame_msg.request_id, event_data->u.frame_msg.timestamp, event_data->u.frame_msg.sof_status);
|
||||
ret = HANDLE_EINTR(ioctl(fds[0].fd, VIDIOC_DQEVENT, &ev));
|
||||
if (ret == 0) {
|
||||
if (ev.type == V4L_EVENT_CAM_REQ_MGR_EVENT) {
|
||||
struct cam_req_mgr_message *event_data = (struct cam_req_mgr_message *)ev.u.data;
|
||||
// LOGD("v4l2 event: sess_hdl %d, link_hdl %d, frame_id %d, req_id %lld, timestamp 0x%llx, sof_status %d\n", event_data->session_hdl, event_data->u.frame_msg.link_hdl, event_data->u.frame_msg.frame_id, event_data->u.frame_msg.request_id, event_data->u.frame_msg.timestamp, event_data->u.frame_msg.sof_status);
|
||||
// printf("sess_hdl %d, link_hdl %d, frame_id %lu, req_id %lu, timestamp 0x%lx, sof_status %d\n", event_data->session_hdl, event_data->u.frame_msg.link_hdl, event_data->u.frame_msg.frame_id, event_data->u.frame_msg.request_id, event_data->u.frame_msg.timestamp, event_data->u.frame_msg.sof_status);
|
||||
|
||||
if (event_data->session_hdl == s->road_cam.req_mgr_session_info.session_hdl) {
|
||||
handle_camera_event(&s->road_cam, event_data);
|
||||
} else if (event_data->session_hdl == s->wide_road_cam.req_mgr_session_info.session_hdl) {
|
||||
handle_camera_event(&s->wide_road_cam, event_data);
|
||||
} else if (event_data->session_hdl == s->driver_cam.req_mgr_session_info.session_hdl) {
|
||||
handle_camera_event(&s->driver_cam, event_data);
|
||||
} else {
|
||||
printf("Unknown vidioc event source\n");
|
||||
assert(false);
|
||||
if (event_data->session_hdl == s->road_cam.session_handle) {
|
||||
handle_camera_event(&s->road_cam, event_data);
|
||||
} else if (event_data->session_hdl == s->wide_road_cam.session_handle) {
|
||||
handle_camera_event(&s->wide_road_cam, event_data);
|
||||
} else if (event_data->session_hdl == s->driver_cam.session_handle) {
|
||||
handle_camera_event(&s->driver_cam, event_data);
|
||||
} else {
|
||||
printf("Unknown vidioc event source\n");
|
||||
assert(false);
|
||||
}
|
||||
}
|
||||
} else {
|
||||
LOGE("VIDIOC_DQEVENT failed, errno=%d", errno);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -1,7 +1,5 @@
|
|||
#pragma once
|
||||
|
||||
#include <pthread.h>
|
||||
|
||||
#include <cstdint>
|
||||
|
||||
#include <media/cam_req_mgr.h>
|
||||
|
@ -33,11 +31,10 @@ typedef struct CameraState {
|
|||
|
||||
int camera_num;
|
||||
|
||||
uint32_t session_handle;
|
||||
|
||||
uint32_t sensor_dev_handle;
|
||||
uint32_t isp_dev_handle;
|
||||
uint32_t csiphy_dev_handle;
|
||||
int32_t session_handle;
|
||||
int32_t sensor_dev_handle;
|
||||
int32_t isp_dev_handle;
|
||||
int32_t csiphy_dev_handle;
|
||||
|
||||
int32_t link_handle;
|
||||
|
||||
|
@ -50,14 +47,10 @@ typedef struct CameraState {
|
|||
int idx_offset;
|
||||
bool skipped;
|
||||
|
||||
struct cam_req_mgr_session_info req_mgr_session_info;
|
||||
|
||||
CameraBuf buf;
|
||||
} CameraState;
|
||||
|
||||
typedef struct MultiCameraState {
|
||||
int device;
|
||||
|
||||
unique_fd video0_fd;
|
||||
unique_fd video1_fd;
|
||||
unique_fd isp_fd;
|
||||
|
@ -69,8 +62,6 @@ typedef struct MultiCameraState {
|
|||
CameraState wide_road_cam;
|
||||
CameraState driver_cam;
|
||||
|
||||
pthread_mutex_t isp_lock;
|
||||
|
||||
SubMaster *sm;
|
||||
PubMaster *pm;
|
||||
} MultiCameraState;
|
||||
|
|
|
@ -6,10 +6,6 @@ from selfdrive.car.interfaces import CarInterfaceBase
|
|||
|
||||
|
||||
class CarInterface(CarInterfaceBase):
|
||||
@staticmethod
|
||||
def compute_gb(accel, speed):
|
||||
return float(accel) / 3.0
|
||||
|
||||
@staticmethod
|
||||
def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=None):
|
||||
ret = CarInterfaceBase.get_std_params(candidate, fingerprint)
|
||||
|
|
|
@ -67,13 +67,8 @@ FINGERPRINTS = {
|
|||
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, 515: 7, 516: 7, 517: 7, 518: 7, 520: 8, 524: 8, 526: 6, 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, 640: 1, 650: 8, 653: 8, 654: 8, 655: 8, 656: 4, 658: 6, 660: 8, 669: 3, 671: 8, 672: 8, 678: 8, 680: 8, 683: 8, 701: 8, 703: 8, 704: 8, 705: 8, 706: 8, 709: 8, 710: 8, 711: 8, 719: 8, 720: 6, 729: 5, 736: 8, 737: 8, 738: 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, 793: 8, 794: 8, 795: 8, 796: 8, 797: 8, 798: 8, 799: 8, 800: 8, 801: 8, 802: 8, 803: 8, 804: 8, 805: 8, 807: 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, 878: 8, 882: 8, 886: 8, 897: 8, 906: 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, 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, 1082: 8, 1083: 8, 1098: 8, 1100: 8, 1216: 8, 1218: 8, 1220: 8, 1225: 8, 1235: 8, 1242: 8, 1246: 8, 1250: 8, 1251: 8, 1252: 8, 1258: 8, 1259: 8, 1260: 8, 1262: 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, 1898: 8, 1899: 8, 1900: 8, 1902: 8, 2015: 8, 2016: 8, 2017: 8, 2018: 8, 2019: 8, 2020: 8, 2023: 8, 2024: 8, 2026: 8, 2027: 8, 2028: 8, 2031: 8
|
||||
}],
|
||||
CAR.JEEP_CHEROKEE: [{
|
||||
# JEEP GRAND CHEROKEE V6 2018
|
||||
55: 8, 168: 8, 181: 8, 256: 4, 257: 5, 258: 8, 264: 8, 268: 8, 272: 6, 273: 6, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 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, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 4, 571: 3, 579: 8, 584: 8, 608: 8, 618: 8, 624: 8, 625: 8, 632: 8, 639: 8, 656: 4, 658: 6, 660: 8, 671: 8, 672: 8, 676: 8, 678: 8, 680: 8, 683: 8, 684: 8, 703: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 737: 8, 738: 8, 746: 5, 752: 2, 754: 8, 760: 8, 761: 8, 764: 8, 766: 8, 773: 8, 776: 8, 779: 8, 782: 8, 783: 8, 784: 8, 785: 8, 788: 3, 792: 8, 799: 8, 800: 8, 804: 8, 806: 2, 808: 8, 810: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 831: 6, 832: 8, 838: 2, 844: 5, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 882: 8, 897: 8, 906: 8, 924: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 956: 8, 968: 8, 969: 4, 970: 8, 973: 8, 974: 5, 976: 8, 977: 4, 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, 1062: 8, 1098: 8, 1100: 8
|
||||
},
|
||||
# Jeep Grand Cherokee 2017 Trailhawk
|
||||
{
|
||||
257: 5, 258: 8, 264: 8, 268: 8, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 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, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 4, 571: 3, 584: 8, 608: 8, 618: 8, 624: 8, 625: 8, 632: 8, 639: 8, 658: 6, 660: 8, 671: 8, 672: 8, 680: 8, 684: 8, 703: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 736: 8, 737: 8, 746: 5, 752: 2, 760: 8, 761: 8, 764: 8, 766: 8, 773: 8, 776: 8, 779: 8, 783: 8, 784: 8, 792: 8, 799: 8, 800: 8, 804: 8, 806: 2, 808: 8, 810: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 831: 6, 832: 8, 838: 2, 844: 5, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 882: 8, 897: 8, 924: 3, 937: 8, 947: 8, 948: 8, 969: 4, 974: 5, 977: 4, 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, 1062: 8, 1098: 8, 1100: 8},
|
||||
],
|
||||
55: 8, 168: 8, 181: 8, 256: 4, 257: 5, 258: 8, 264: 8, 268: 8, 272: 6, 273: 6, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 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, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 4, 564: 4, 571: 3, 579: 8, 584: 8, 608: 8, 618: 8, 624: 8, 625: 8, 632: 8, 639: 8, 656: 4, 658: 6, 660: 8, 671: 8, 672: 8, 676: 8, 678: 8, 680: 8, 683: 8, 684: 8, 703: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 737: 8, 738: 8, 746: 5, 752: 2, 754: 8, 760: 8, 761: 8, 764: 8, 766: 8, 773: 8, 776: 8, 779: 8, 782: 8, 783: 8, 784: 8, 785: 8, 788: 3, 792: 8, 799: 8, 800: 8, 804: 8, 806: 2, 808: 8, 810: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 831: 6, 832: 8, 838: 2, 840: 8, 844: 5, 847: 1, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 874: 2, 882: 8, 897: 8, 906: 8, 924: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 956: 8, 968: 8, 969: 4, 970: 8, 973: 8, 974: 5, 975: 8, 976: 8, 977: 4, 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, 1062: 8, 1098: 8, 1100: 8, 1543: 8, 1562: 8, 2015: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8
|
||||
}],
|
||||
CAR.JEEP_CHEROKEE_2019: [{
|
||||
# Jeep Grand Cherokee 2019, including most 2020 models
|
||||
55: 8, 168: 8, 179: 8, 181: 8, 256: 4, 257: 5, 258: 8, 264: 8, 268: 8, 272: 6, 273: 6, 274: 2, 280: 8, 284: 8, 288: 7, 290: 6, 292: 8, 300: 8, 308: 8, 320: 8, 324: 8, 331: 8, 332: 8, 341: 8, 344: 8, 352: 8, 362: 8, 368: 8, 376: 3, 384: 8, 388: 4, 416: 7, 448: 6, 456: 4, 464: 8, 500: 8, 501: 8, 512: 8, 514: 8, 520: 8, 530: 8, 532: 8, 544: 8, 557: 8, 559: 8, 560: 8, 564: 8, 571: 3, 579: 8, 584: 8, 608: 8, 618: 8, 624: 8, 625: 8, 632: 8, 639: 8, 640: 1, 656: 4, 658: 6, 660: 8, 671: 8, 672: 8, 676: 8, 678: 8, 680: 8, 683: 8, 684: 8, 703: 8, 705: 8, 706: 8, 709: 8, 710: 8, 719: 8, 720: 6, 729: 5, 736: 8, 737: 8, 738: 8, 746: 5, 752: 2, 754: 8, 760: 8, 761: 8, 764: 8, 766: 8, 773: 8, 776: 8, 779: 8, 782: 8, 783: 8, 784: 8, 785: 8, 792: 8, 799: 8, 800: 8, 804: 8, 806: 2, 808: 8, 810: 8, 816: 8, 817: 8, 820: 8, 825: 2, 826: 8, 831: 6, 832: 8, 838: 2, 840: 8, 844: 5, 847: 1, 848: 8, 853: 8, 856: 4, 860: 6, 863: 8, 882: 8, 897: 8, 906: 8, 924: 8, 937: 8, 938: 8, 939: 8, 940: 8, 941: 8, 942: 8, 943: 8, 947: 8, 948: 8, 960: 4, 968: 8, 969: 4, 970: 8, 973: 8, 974: 5, 976: 8, 977: 4, 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, 1062: 8, 1098: 8, 1100: 8, 1216: 8, 1218: 8, 1220: 8, 1223: 8, 1225: 8, 1227: 8, 1235: 8, 1242: 8, 1250: 8, 1251: 8, 1252: 8, 1254: 8, 1264: 8, 1284: 8, 1536: 8, 1537: 8, 1543: 8, 1545: 8, 1562: 8, 1568: 8, 1570: 8, 1572: 8, 1593: 8, 1856: 8, 1858: 8, 1860: 8, 1863: 8, 1865: 8, 1867: 8, 1875: 8, 1882: 8, 1890: 8, 1891: 8, 1892: 8, 1894: 8, 1896: 8, 1904: 8, 2015: 8, 2016: 8, 2017: 8, 2024: 8, 2025: 8
|
||||
|
|
|
@ -7,11 +7,6 @@ from selfdrive.car.interfaces import CarInterfaceBase
|
|||
|
||||
|
||||
class CarInterface(CarInterfaceBase):
|
||||
|
||||
@staticmethod
|
||||
def compute_gb(accel, speed):
|
||||
return float(accel) / 3.0
|
||||
|
||||
@staticmethod
|
||||
def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=None):
|
||||
ret = CarInterfaceBase.get_std_params(candidate, fingerprint)
|
||||
|
|
|
@ -46,18 +46,13 @@ class CarController():
|
|||
|
||||
can_sends.append(gmcan.create_steering_control(self.packer_pt, CanBus.POWERTRAIN, apply_steer, idx, lkas_enabled))
|
||||
|
||||
# GAS/BRAKE
|
||||
# no output if not enabled, but keep sending keepalive messages
|
||||
# treat pedals as one
|
||||
final_pedal = actuators.gas - actuators.brake
|
||||
|
||||
if not enabled:
|
||||
# Stock ECU sends max regen when not enabled.
|
||||
apply_gas = P.MAX_ACC_REGEN
|
||||
apply_brake = 0
|
||||
else:
|
||||
apply_gas = int(round(interp(final_pedal, P.GAS_LOOKUP_BP, P.GAS_LOOKUP_V)))
|
||||
apply_brake = int(round(interp(final_pedal, P.BRAKE_LOOKUP_BP, P.BRAKE_LOOKUP_V)))
|
||||
apply_gas = int(round(interp(actuators.accel, P.GAS_LOOKUP_BP, P.GAS_LOOKUP_V)))
|
||||
apply_brake = int(round(interp(actuators.accel, P.BRAKE_LOOKUP_BP, P.BRAKE_LOOKUP_V)))
|
||||
|
||||
# Gas/regen and brakes - all at 25Hz
|
||||
if (frame % 4) == 0:
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
from cereal import car
|
||||
from selfdrive.config import Conversions as CV
|
||||
from selfdrive.car.gm.values import CAR, CruiseButtons, \
|
||||
AccState
|
||||
AccState, CarControllerParams
|
||||
from selfdrive.car import STD_CARGO_KG, scale_rot_inertia, scale_tire_stiffness, gen_empty_fingerprint
|
||||
from selfdrive.car.interfaces import CarInterfaceBase
|
||||
|
||||
|
@ -10,10 +10,10 @@ ButtonType = car.CarState.ButtonEvent.Type
|
|||
EventName = car.CarEvent.EventName
|
||||
|
||||
class CarInterface(CarInterfaceBase):
|
||||
|
||||
@staticmethod
|
||||
def compute_gb(accel, speed):
|
||||
return float(accel) / 4.0
|
||||
def get_pid_accel_limits(CP, current_speed, cruise_speed):
|
||||
params = CarControllerParams()
|
||||
return params.ACCEL_MIN, params.ACCEL_MAX
|
||||
|
||||
@staticmethod
|
||||
def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=None):
|
||||
|
|
|
@ -25,10 +25,20 @@ class CarControllerParams():
|
|||
MAX_GAS = 3072 # Only a safety limit
|
||||
ZERO_GAS = 2048
|
||||
MAX_BRAKE = 350 # Should be around 3.5m/s^2, including regen
|
||||
|
||||
self.ACCEL_MAX = 2.0 # m/s^2
|
||||
|
||||
# Allow small margin below -3.5 m/s^2 from ISO 15622:2018 since we
|
||||
# perform the closed loop control, and might need some
|
||||
# to apply some more braking if we're on a downhill slope.
|
||||
# Our controller should still keep the 2 second average above
|
||||
# -3.5 m/s^2 as per planner limits
|
||||
self.ACCEL_MIN = -4.0 # m/s^2
|
||||
|
||||
self.MAX_ACC_REGEN = 1404 # ACC Regen braking is slightly less powerful than max regen paddle
|
||||
self.GAS_LOOKUP_BP = [-0.25, 0., 0.5]
|
||||
self.GAS_LOOKUP_BP = [-1.0, 0., self.ACCEL_MAX]
|
||||
self.GAS_LOOKUP_V = [self.MAX_ACC_REGEN, ZERO_GAS, MAX_GAS]
|
||||
self.BRAKE_LOOKUP_BP = [-1., -0.25]
|
||||
self.BRAKE_LOOKUP_BP = [self.ACCEL_MIN, -1.0]
|
||||
self.BRAKE_LOOKUP_V = [MAX_BRAKE, 0]
|
||||
|
||||
class CAR:
|
||||
|
|
|
@ -5,13 +5,35 @@ from selfdrive.controls.lib.drive_helpers import rate_limit
|
|||
from common.numpy_fast import clip, interp
|
||||
from selfdrive.car import create_gas_command
|
||||
from selfdrive.car.honda import hondacan
|
||||
from selfdrive.car.honda.values import OLD_NIDEC_LONG_CONTROL, CruiseButtons, CAR, VISUAL_HUD, HONDA_BOSCH, CarControllerParams
|
||||
from selfdrive.car.honda.values import CruiseButtons, VISUAL_HUD, HONDA_BOSCH, HONDA_NIDEC_ALT_PCM_ACCEL, CarControllerParams
|
||||
from opendbc.can.packer import CANPacker
|
||||
|
||||
VisualAlert = car.CarControl.HUDControl.VisualAlert
|
||||
LongCtrlState = car.CarControl.Actuators.LongControlState
|
||||
|
||||
def compute_gb_honda_bosch(accel, speed):
|
||||
#TODO returns 0s, is unused
|
||||
return 0.0, 0.0
|
||||
|
||||
|
||||
# TODO: not clear this does anything useful
|
||||
def compute_gb_honda_nidec(accel, speed):
|
||||
creep_brake = 0.0
|
||||
creep_speed = 2.3
|
||||
creep_brake_value = 0.15
|
||||
if speed < creep_speed:
|
||||
creep_brake = (creep_speed - speed) / creep_speed * creep_brake_value
|
||||
gb = float(accel) / 4.8 - creep_brake
|
||||
return clip(gb, 0.0, 1.0), clip(-gb, 0.0, 1.0)
|
||||
|
||||
|
||||
def compute_gas_brake(accel, speed, fingerprint):
|
||||
if fingerprint in HONDA_BOSCH:
|
||||
return compute_gb_honda_bosch(accel, speed)
|
||||
else:
|
||||
return compute_gb_honda_nidec(accel, speed)
|
||||
|
||||
|
||||
#TODO not clear this does anything useful
|
||||
def actuator_hystereses(brake, braking, brake_steady, v_ego, car_fingerprint):
|
||||
# hyst params
|
||||
brake_hyst_on = 0.02 # to activate brakes exceed this value
|
||||
|
@ -32,9 +54,6 @@ def actuator_hystereses(brake, braking, brake_steady, v_ego, car_fingerprint):
|
|||
brake_steady = brake + brake_hyst_gap
|
||||
brake = brake_steady
|
||||
|
||||
if (car_fingerprint in (CAR.ACURA_ILX, CAR.CRV, CAR.CRV_EU)) and brake > 0.0:
|
||||
brake += 0.15
|
||||
|
||||
return brake, braking, brake_steady
|
||||
|
||||
|
||||
|
@ -94,8 +113,15 @@ class CarController():
|
|||
|
||||
P = self.params
|
||||
|
||||
if enabled:
|
||||
accel = actuators.accel
|
||||
gas, brake = compute_gas_brake(actuators.accel, CS.out.vEgo, CS.CP.carFingerprint)
|
||||
else:
|
||||
accel = 0.0
|
||||
gas, brake = 0.0, 0.0
|
||||
|
||||
# *** apply brake hysteresis ***
|
||||
brake, self.braking, self.brake_steady = actuator_hystereses(actuators.brake, self.braking, self.brake_steady, CS.out.vEgo, CS.CP.carFingerprint)
|
||||
pre_limit_brake, self.braking, self.brake_steady = actuator_hystereses(brake, self.braking, self.brake_steady, CS.out.vEgo, CS.CP.carFingerprint)
|
||||
|
||||
# *** no output if not enabled ***
|
||||
if not enabled and CS.out.cruiseState.enabled:
|
||||
|
@ -107,7 +133,7 @@ class CarController():
|
|||
pcm_cancel_cmd = pcm_cancel_cmd and CS.CP.pcmCruise
|
||||
|
||||
# *** rate limit after the enable check ***
|
||||
self.brake_last = rate_limit(brake, self.brake_last, -2., DT_CTRL)
|
||||
self.brake_last = rate_limit(pre_limit_brake, self.brake_last, -2., DT_CTRL)
|
||||
|
||||
# vehicle hud display, wait for one update from 10Hz 0x304 msg
|
||||
if hud_show_lanes:
|
||||
|
@ -146,35 +172,37 @@ class CarController():
|
|||
can_sends.append(hondacan.create_steering_control(self.packer, apply_steer,
|
||||
lkas_active, CS.CP.carFingerprint, idx, CS.CP.openpilotLongitudinalControl))
|
||||
|
||||
|
||||
accel = actuators.gas - actuators.brake
|
||||
|
||||
# TODO: pass in LoC.long_control_state and use that to decide starting/stoppping
|
||||
stopping = accel < 0 and CS.out.vEgo < 0.3
|
||||
starting = accel > 0 and CS.out.vEgo < 0.3
|
||||
stopping = actuators.longControlState == LongCtrlState.stopping
|
||||
starting = actuators.longControlState == LongCtrlState.starting
|
||||
|
||||
# Prevent rolling backwards
|
||||
accel = -1.0 if stopping else accel
|
||||
if CS.CP.carFingerprint in HONDA_BOSCH:
|
||||
apply_accel = interp(accel, P.BOSCH_ACCEL_LOOKUP_BP, P.BOSCH_ACCEL_LOOKUP_V)
|
||||
else:
|
||||
apply_accel = interp(accel, P.NIDEC_ACCEL_LOOKUP_BP, P.NIDEC_ACCEL_LOOKUP_V)
|
||||
accel = -4.0 if stopping else accel
|
||||
|
||||
# wind brake from air resistance decel at high speed
|
||||
wind_brake = interp(CS.out.vEgo, [0.0, 2.3, 35.0], [0.001, 0.002, 0.15])
|
||||
if CS.CP.carFingerprint in OLD_NIDEC_LONG_CONTROL:
|
||||
#pcm_speed = pcm_speed
|
||||
pcm_accel = int(clip(pcm_accel, 0, 1) * 0xc6)
|
||||
else:
|
||||
max_accel = interp(CS.out.vEgo, P.NIDEC_MAX_ACCEL_BP, P.NIDEC_MAX_ACCEL_V)
|
||||
pcm_accel = int(clip(apply_accel/max_accel, 0.0, 1.0) * 0xc6)
|
||||
pcm_speed_BP = [-wind_brake,
|
||||
-wind_brake*(3/4),
|
||||
0.0]
|
||||
# all of this is only relevant for HONDA NIDEC
|
||||
max_accel = interp(CS.out.vEgo, P.NIDEC_MAX_ACCEL_BP, P.NIDEC_MAX_ACCEL_V)
|
||||
# TODO this 1.44 is just to maintain previous behavior
|
||||
pcm_speed_BP = [-wind_brake,
|
||||
-wind_brake*(3/4),
|
||||
0.0,
|
||||
0.5]
|
||||
# The Honda ODYSSEY seems to have different PCM_ACCEL
|
||||
# msgs, is it other cars too?
|
||||
if CS.CP.carFingerprint in HONDA_NIDEC_ALT_PCM_ACCEL:
|
||||
pcm_speed_V = [0.0,
|
||||
clip(CS.out.vEgo + apply_accel/2.0 - 2.0, 0.0, 100.0),
|
||||
clip(CS.out.vEgo + apply_accel/2.0 + 2.0, 0.0, 100.0)]
|
||||
pcm_speed = interp(accel, pcm_speed_BP, pcm_speed_V)
|
||||
clip(CS.out.vEgo - 3.0, 0.0, 100.0),
|
||||
clip(CS.out.vEgo + 0.0, 0.0, 100.0),
|
||||
clip(CS.out.vEgo + 5.0, 0.0, 100.0)]
|
||||
pcm_accel = int((1.0) * 0xc6)
|
||||
else:
|
||||
pcm_speed_V = [0.0,
|
||||
clip(CS.out.vEgo - 2.0, 0.0, 100.0),
|
||||
clip(CS.out.vEgo + 2.0, 0.0, 100.0),
|
||||
clip(CS.out.vEgo + 5.0, 0.0, 100.0)]
|
||||
pcm_accel = int(clip((accel/1.44)/max_accel, 0.0, 1.0) * 0xc6)
|
||||
|
||||
pcm_speed = interp(gas-brake, pcm_speed_BP, pcm_speed_V)
|
||||
|
||||
if not CS.CP.openpilotLongitudinalControl:
|
||||
if (frame % 2) == 0:
|
||||
|
@ -193,8 +221,8 @@ class CarController():
|
|||
ts = frame * DT_CTRL
|
||||
|
||||
if CS.CP.carFingerprint in HONDA_BOSCH:
|
||||
apply_gas = interp(accel, P.BOSCH_GAS_LOOKUP_BP, P.BOSCH_GAS_LOOKUP_V)
|
||||
can_sends.extend(hondacan.create_acc_commands(self.packer, enabled, apply_accel, apply_gas, idx, stopping, starting, CS.CP.carFingerprint))
|
||||
bosch_gas = interp(accel, P.BOSCH_GAS_LOOKUP_BP, P.BOSCH_GAS_LOOKUP_V)
|
||||
can_sends.extend(hondacan.create_acc_commands(self.packer, enabled, accel, bosch_gas, idx, stopping, starting, CS.CP.carFingerprint))
|
||||
|
||||
else:
|
||||
apply_brake = clip(self.brake_last - wind_brake, 0.0, 1.0)
|
||||
|
@ -209,7 +237,7 @@ class CarController():
|
|||
gas_mult = interp(CS.out.vEgo, [0., 10.], [0.4, 1.0])
|
||||
# send exactly zero if apply_gas is zero. Interceptor will send the max between read value and apply_gas.
|
||||
# This prevents unexpected pedal range rescaling
|
||||
apply_gas = clip(gas_mult * actuators.gas, 0., 1.)
|
||||
apply_gas = clip(gas_mult * gas, 0., 1.)
|
||||
can_sends.append(create_gas_command(self.packer, apply_gas, idx))
|
||||
|
||||
hud = HUDData(int(pcm_accel), int(round(hud_v_cruise)), hud_car,
|
||||
|
|
|
@ -75,7 +75,7 @@ def get_can_signals(CP, gearbox_msg="GEARBOX"):
|
|||
("SCM_BUTTONS", 25),
|
||||
]
|
||||
|
||||
if CP.carFingerprint in (CAR.CRV_HYBRID, CAR.CIVIC_BOSCH_DIESEL, CAR.ACURA_RDX_3G):
|
||||
if CP.carFingerprint in (CAR.CRV_HYBRID, CAR.CIVIC_BOSCH_DIESEL, CAR.ACURA_RDX_3G, CAR.HONDA_E):
|
||||
checks += [
|
||||
(gearbox_msg, 50),
|
||||
]
|
||||
|
@ -119,7 +119,7 @@ def get_can_signals(CP, gearbox_msg="GEARBOX"):
|
|||
else:
|
||||
checks += [("CRUISE_PARAMS", 50)]
|
||||
|
||||
if CP.carFingerprint in (CAR.ACCORD, CAR.ACCORDH, CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_HYBRID, CAR.INSIGHT, CAR.ACURA_RDX_3G):
|
||||
if CP.carFingerprint in (CAR.ACCORD, CAR.ACCORDH, CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_HYBRID, CAR.INSIGHT, CAR.ACURA_RDX_3G, CAR.HONDA_E):
|
||||
signals += [("DRIVERS_DOOR_OPEN", "SCM_FEEDBACK", 1)]
|
||||
elif CP.carFingerprint == CAR.ODYSSEY_CHN:
|
||||
signals += [("DRIVERS_DOOR_OPEN", "SCM_BUTTONS", 1)]
|
||||
|
@ -163,12 +163,8 @@ def get_can_signals(CP, gearbox_msg="GEARBOX"):
|
|||
("GAS_PEDAL_2", 100),
|
||||
]
|
||||
elif CP.carFingerprint == CAR.HRV:
|
||||
signals += [("CAR_GAS", "GAS_PEDAL", 0),
|
||||
("MAIN_ON", "SCM_BUTTONS", 0),
|
||||
signals += [("MAIN_ON", "SCM_BUTTONS", 0),
|
||||
("BRAKE_HOLD_ACTIVE", "VSA_STATUS", 0)]
|
||||
checks += [
|
||||
("GAS_PEDAL", 100),
|
||||
]
|
||||
elif CP.carFingerprint == CAR.ODYSSEY:
|
||||
signals += [("MAIN_ON", "SCM_FEEDBACK", 0),
|
||||
("EPB_STATE", "EPB_STATUS", 0)]
|
||||
|
@ -211,7 +207,6 @@ class CarState(CarStateBase):
|
|||
self.shifter_values = can_define.dv[self.gearbox_msg]["GEAR_SHIFTER"]
|
||||
self.steer_status_values = defaultdict(lambda: "UNKNOWN", can_define.dv["STEER_STATUS"]["STEER_STATUS"])
|
||||
|
||||
self.user_gas, self.user_gas_pressed = 0., 0
|
||||
self.brake_switch_prev = 0
|
||||
self.brake_switch_prev_ts = 0
|
||||
self.cruise_setting = 0
|
||||
|
@ -230,13 +225,14 @@ class CarState(CarStateBase):
|
|||
|
||||
# ******************* parse out can *******************
|
||||
# TODO: find wheels moving bit in dbc
|
||||
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):
|
||||
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, CAR.HONDA_E):
|
||||
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"])
|
||||
elif self.CP.carFingerprint == CAR.HRV:
|
||||
ret.standstill = not cp.vl["STANDSTILL"]["WHEELS_MOVING"]
|
||||
ret.doorOpen = bool(cp.vl["SCM_BUTTONS"]["DRIVERS_DOOR_OPEN"])
|
||||
else:
|
||||
ret.standstill = not cp.vl["STANDSTILL"]["WHEELS_MOVING"]
|
||||
|
@ -280,7 +276,7 @@ class CarState(CarStateBase):
|
|||
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.ACCORDH, CAR.CIVIC_BOSCH,
|
||||
CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_HYBRID, CAR.INSIGHT, CAR.ACURA_RDX_3G):
|
||||
CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_HYBRID, CAR.INSIGHT, CAR.ACURA_RDX_3G, CAR.HONDA_E):
|
||||
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:
|
||||
|
@ -293,21 +289,20 @@ class CarState(CarStateBase):
|
|||
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"]
|
||||
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.
|
||||
ret.gas = pedal_gas / 256.
|
||||
else:
|
||||
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_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
|
||||
user_gas = (cp.vl["GAS_SENSOR"]["INTERCEPTOR_GAS"] + cp.vl["GAS_SENSOR"]["INTERCEPTOR_GAS2"]) / 2.
|
||||
ret.gasPressed = user_gas > 1e-5 # this works because interceptor read < 0 when pedal position is 0. Once calibrated, this will change
|
||||
else:
|
||||
ret.gasPressed = self.pedal_gas > 1e-5
|
||||
ret.gasPressed = pedal_gas > 1e-5
|
||||
|
||||
ret.steeringTorque = cp.vl["STEER_STATUS"]["STEER_TORQUE_SENSOR"]
|
||||
ret.steeringTorqueEps = cp.vl["STEER_MOTOR_TORQUE"]["MOTOR_TORQUE"]
|
||||
|
|
|
@ -15,37 +15,17 @@ EventName = car.CarEvent.EventName
|
|||
TransmissionType = car.CarParams.TransmissionType
|
||||
|
||||
|
||||
def compute_gb_honda_bosch(accel, speed):
|
||||
return float(accel) / 3.5
|
||||
|
||||
|
||||
def compute_gb_honda_nidec(accel, speed):
|
||||
creep_brake = 0.0
|
||||
creep_speed = 2.3
|
||||
creep_brake_value = 0.15
|
||||
if speed < creep_speed:
|
||||
creep_brake = (creep_speed - speed) / creep_speed * creep_brake_value
|
||||
return float(accel) / 4.8 - creep_brake
|
||||
|
||||
|
||||
def compute_gb_acura(accel, speed):
|
||||
GB_VALUES = [-2., 0.0, 0.8]
|
||||
GB_BP = [-5., 0.0, 4.0]
|
||||
return interp(accel, GB_BP, GB_VALUES)
|
||||
|
||||
|
||||
class CarInterface(CarInterfaceBase):
|
||||
def __init__(self, CP, CarController, CarState):
|
||||
super().__init__(CP, CarController, CarState)
|
||||
|
||||
if self.CS.CP.carFingerprint in HONDA_BOSCH:
|
||||
self.compute_gb = compute_gb_honda_bosch
|
||||
else:
|
||||
self.compute_gb = compute_gb_honda_nidec
|
||||
|
||||
@staticmethod
|
||||
def compute_gb(accel, speed): # pylint: disable=method-hidden
|
||||
raise NotImplementedError
|
||||
def get_pid_accel_limits(CP, current_speed, cruise_speed):
|
||||
if CP.carFingerprint in HONDA_BOSCH:
|
||||
return CarControllerParams.BOSCH_ACCEL_MIN, CarControllerParams.BOSCH_ACCEL_MAX
|
||||
else:
|
||||
# NIDECs don't allow acceleration near cruise_speed,
|
||||
# so limit limits of pid to prevent windup
|
||||
ACCEL_MAX_VALS = [CarControllerParams.NIDEC_ACCEL_MAX, 0.2]
|
||||
ACCEL_MAX_BP = [cruise_speed - 2., cruise_speed - .2]
|
||||
return CarControllerParams.NIDEC_ACCEL_MIN, interp(current_speed, ACCEL_MAX_BP, ACCEL_MAX_VALS)
|
||||
|
||||
@staticmethod
|
||||
def calc_accel_override(a_ego, a_target, v_ego, v_target):
|
||||
|
@ -77,7 +57,7 @@ class CarInterface(CarInterfaceBase):
|
|||
# accelOverride is more or less the max throttle allowed to pcm: usually set to a constant
|
||||
# unless aTargetMax is very high and then we scale with it; this help in quicker restart
|
||||
|
||||
return float(max(max_accel, a_target / CarControllerParams.ACCEL_MAX)) * min(speedLimiter, accelLimiter)
|
||||
return float(max(max_accel, a_target / CarControllerParams.NIDEC_ACCEL_MAX)) * min(speedLimiter, accelLimiter)
|
||||
|
||||
@staticmethod
|
||||
def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=[]): # pylint: disable=dangerous-default-value
|
||||
|
@ -309,6 +289,16 @@ class CarInterface(CarInterfaceBase):
|
|||
tire_stiffness_factor = 0.82
|
||||
ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.18]]
|
||||
|
||||
elif candidate == CAR.HONDA_E:
|
||||
stop_and_go = True
|
||||
ret.mass = 3338.8 * CV.LB_TO_KG + STD_CARGO_KG
|
||||
ret.wheelbase = 2.5
|
||||
ret.centerToFront = ret.wheelbase * 0.5
|
||||
ret.steerRatio = 16.71
|
||||
ret.lateralParams.torqueBP, ret.lateralParams.torqueV = [[0, 4096], [0, 4096]] # TODO: determine if there is a dead zone at the top end
|
||||
tire_stiffness_factor = 0.82
|
||||
ret.lateralTuning.pid.kpV, ret.lateralTuning.pid.kiV = [[0.6], [0.18]] # TODO: can probably use some tuning
|
||||
|
||||
else:
|
||||
raise ValueError("unsupported car %s" % candidate)
|
||||
|
||||
|
@ -333,17 +323,6 @@ class CarInterface(CarInterfaceBase):
|
|||
ret.tireStiffnessFront, ret.tireStiffnessRear = scale_tire_stiffness(ret.mass, ret.wheelbase, ret.centerToFront,
|
||||
tire_stiffness_factor=tire_stiffness_factor)
|
||||
|
||||
if candidate in HONDA_BOSCH:
|
||||
ret.gasMaxBP = [0.] # m/s
|
||||
ret.gasMaxV = [0.6]
|
||||
ret.brakeMaxBP = [0.] # m/s
|
||||
ret.brakeMaxV = [1.] # max brake allowed, 3.5m/s^2
|
||||
else:
|
||||
ret.gasMaxBP = [0.] # m/s
|
||||
ret.gasMaxV = [0.6] # max gas allowed
|
||||
ret.brakeMaxBP = [5., 20.] # m/s
|
||||
ret.brakeMaxV = [1., 0.8] # max brake allowed
|
||||
|
||||
ret.startAccel = 0.5
|
||||
|
||||
ret.steerActuatorDelay = 0.1
|
||||
|
@ -422,7 +401,7 @@ class CarInterface(CarInterfaceBase):
|
|||
# we engage when pcm is active (rising edge)
|
||||
if ret.cruiseState.enabled and not self.CS.out.cruiseState.enabled:
|
||||
events.add(EventName.pcmEnable)
|
||||
elif not ret.cruiseState.enabled and (c.actuators.brake <= 0. or not self.CP.openpilotLongitudinalControl):
|
||||
elif not ret.cruiseState.enabled and (c.actuators.accel >= 0. or not self.CP.openpilotLongitudinalControl):
|
||||
# it can happen that car cruise disables while comma system is enabled: need to
|
||||
# keep braking if needed or if the speed is very low
|
||||
if ret.vEgo < self.CP.minEnableSpeed + 2.:
|
||||
|
|
|
@ -5,7 +5,16 @@ Ecu = car.CarParams.Ecu
|
|||
VisualAlert = car.CarControl.HUDControl.VisualAlert
|
||||
|
||||
class CarControllerParams():
|
||||
ACCEL_MAX = 1.6
|
||||
# Allow small margin below -3.5 m/s^2 from ISO 15622:2018 since we
|
||||
# perform the closed loop control, and might need some
|
||||
# to apply some more braking if we're on a downhill slope.
|
||||
# Our controller should still keep the 2 second average above
|
||||
# -3.5 m/s^2 as per planner limits
|
||||
NIDEC_ACCEL_MIN = -4.0 # m/s^2
|
||||
NIDEC_ACCEL_MAX = 1.6 # m/s^2, lower than 2.0 m/s^2 for tuning reasons
|
||||
|
||||
BOSCH_ACCEL_MIN = -3.5 # m/s^2
|
||||
BOSCH_ACCEL_MAX = 2.0 # m/s^2
|
||||
|
||||
def __init__(self, CP):
|
||||
self.BRAKE_MAX = 1024//4
|
||||
|
@ -22,10 +31,7 @@ class CarControllerParams():
|
|||
self.NIDEC_MAX_ACCEL_V = [0.5, 2.4, 1.4, 0.6]
|
||||
self.NIDEC_MAX_ACCEL_BP = [0.0, 4.0, 10., 20.]
|
||||
|
||||
|
||||
self.BOSCH_ACCEL_LOOKUP_BP = [-1., 0., 0.6]
|
||||
self.BOSCH_ACCEL_LOOKUP_V = [-3.5, 0., 2.]
|
||||
self.BOSCH_GAS_LOOKUP_BP = [0., 0.6]
|
||||
self.BOSCH_GAS_LOOKUP_BP = [0., 2.0] # 2m/s^2
|
||||
self.BOSCH_GAS_LOOKUP_V = [0, 2000]
|
||||
|
||||
|
||||
|
@ -69,6 +75,7 @@ class CAR:
|
|||
PILOT_2019 = "HONDA PILOT 2019"
|
||||
RIDGELINE = "HONDA RIDGELINE 2017"
|
||||
INSIGHT = "HONDA INSIGHT 2019"
|
||||
HONDA_E = "HONDA E 2020"
|
||||
|
||||
# diag message that in some Nidec cars only appear with 1s freq if VIN query is performed
|
||||
DIAG_MSGS = {1600: 5, 1601: 8}
|
||||
|
@ -1225,6 +1232,32 @@ FW_VERSIONS = {
|
|||
b'78109-TV9-A510\x00\x00',
|
||||
],
|
||||
},
|
||||
CAR.HONDA_E:{
|
||||
(Ecu.eps, 0x18DA30F1, None):[
|
||||
b'39990-TYF-N030\x00\x00'
|
||||
],
|
||||
(Ecu.gateway, 0x18DAEFF1, None):[
|
||||
b'38897-TYF-E140\x00\x00'
|
||||
],
|
||||
(Ecu.shiftByWire, 0x18DA0BF1, None):[
|
||||
b'54008-TYF-E010\x00\x00'
|
||||
],
|
||||
(Ecu.srs, 0x18DA53F1, None):[
|
||||
b'77959-TYF-G430\x00\x00'
|
||||
],
|
||||
(Ecu.combinationMeter, 0x18DA60F1, None):[
|
||||
b'78108-TYF-G610\x00\x00'
|
||||
],
|
||||
(Ecu.fwdRadar, 0x18DAB0F1, None):[
|
||||
b'36802-TYF-E030\x00\x00'
|
||||
],
|
||||
(Ecu.fwdCamera, 0x18DAB5F1, None):[
|
||||
b'36161-TYF-E020\x00\x00'
|
||||
],
|
||||
(Ecu.vsa, 0x18DA28F1, None):[
|
||||
b'57114-TYF-E030\x00\x00'
|
||||
],
|
||||
},
|
||||
}
|
||||
|
||||
DBC = {
|
||||
|
@ -1241,13 +1274,14 @@ DBC = {
|
|||
CAR.CRV_EU: dbc_dict('honda_crv_executive_2016_can_generated', 'acura_ilx_2016_nidec'),
|
||||
CAR.CRV_HYBRID: dbc_dict('honda_crv_hybrid_2019_can_generated', None),
|
||||
CAR.FIT: dbc_dict('honda_fit_ex_2018_can_generated', 'acura_ilx_2016_nidec'),
|
||||
CAR.HRV: dbc_dict('honda_hrv_touring_2019_can_generated', 'acura_ilx_2016_nidec'),
|
||||
CAR.HRV: dbc_dict('honda_fit_ex_2018_can_generated', 'acura_ilx_2016_nidec'),
|
||||
CAR.ODYSSEY: dbc_dict('honda_odyssey_exl_2018_generated', 'acura_ilx_2016_nidec'),
|
||||
CAR.ODYSSEY_CHN: dbc_dict('honda_odyssey_extreme_edition_2018_china_can_generated', 'acura_ilx_2016_nidec'),
|
||||
CAR.PILOT: dbc_dict('honda_pilot_touring_2017_can_generated', 'acura_ilx_2016_nidec'),
|
||||
CAR.PILOT_2019: dbc_dict('honda_pilot_touring_2017_can_generated', 'acura_ilx_2016_nidec'),
|
||||
CAR.RIDGELINE: dbc_dict('honda_ridgeline_black_edition_2017_can_generated', 'acura_ilx_2016_nidec'),
|
||||
CAR.INSIGHT: dbc_dict('honda_insight_ex_2019_can_generated', None),
|
||||
CAR.HONDA_E: dbc_dict('acura_rdx_2020_can_generated', None),
|
||||
}
|
||||
|
||||
STEER_THRESHOLD = {
|
||||
|
@ -1266,6 +1300,6 @@ SPEED_FACTOR = {
|
|||
CAR.HRV: 1.025,
|
||||
}
|
||||
|
||||
OLD_NIDEC_LONG_CONTROL = set([CAR.ODYSSEY, CAR.ACURA_RDX, CAR.CRV, CAR.HRV])
|
||||
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])
|
||||
HONDA_NIDEC_ALT_PCM_ACCEL = set([CAR.ODYSSEY])
|
||||
HONDA_BOSCH = set([CAR.ACCORD, CAR.ACCORDH, CAR.CIVIC_BOSCH, CAR.CIVIC_BOSCH_DIESEL, CAR.CRV_5G, CAR.CRV_HYBRID, CAR.INSIGHT, CAR.ACURA_RDX_3G, CAR.HONDA_E])
|
||||
HONDA_BOSCH_ALT_BRAKE_SIGNAL = set([CAR.ACCORD, CAR.CRV_5G, CAR.ACURA_RDX_3G])
|
|
@ -19,7 +19,7 @@ def create_lkas11(packer, frame, car_fingerprint, apply_steer, steer_req,
|
|||
|
||||
if car_fingerprint in [CAR.SONATA, CAR.PALISADE, CAR.KIA_NIRO_EV, CAR.KIA_NIRO_HEV_2021, CAR.SANTA_FE,
|
||||
CAR.IONIQ_EV_2020, CAR.IONIQ_PHEV, CAR.KIA_SELTOS, CAR.ELANTRA_2021,
|
||||
CAR.ELANTRA_HEV_2021, CAR.SONATA_HYBRID, CAR.KONA_HEV]:
|
||||
CAR.ELANTRA_HEV_2021, CAR.SONATA_HYBRID, CAR.KONA_EV, CAR.KONA_HEV]:
|
||||
values["CF_Lkas_LdwsActivemode"] = int(left_lane) + (int(right_lane) << 1)
|
||||
values["CF_Lkas_LdwsOpt_USM"] = 2
|
||||
|
||||
|
|
|
@ -6,11 +6,6 @@ from selfdrive.car import STD_CARGO_KG, scale_rot_inertia, scale_tire_stiffness,
|
|||
from selfdrive.car.interfaces import CarInterfaceBase
|
||||
|
||||
class CarInterface(CarInterfaceBase):
|
||||
|
||||
@staticmethod
|
||||
def compute_gb(accel, speed):
|
||||
return float(accel) / 3.0
|
||||
|
||||
@staticmethod
|
||||
def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=[]): # pylint: disable=dangerous-default-value
|
||||
ret = CarInterfaceBase.get_std_params(candidate, fingerprint)
|
||||
|
|
|
@ -228,6 +228,7 @@ FW_VERSIONS = {
|
|||
b'\xf1\x8758910-L0100\xf1\x00DN ESC \x06 104\x19\x08\x01 58910-L0100\xf1\xa01.04',
|
||||
b'\xf1\x8758910-L0100\xf1\x00DN ESC \x06 106 \x07\x01 58910-L0100\xf1\xa01.06',
|
||||
b'\xf1\x8758910-L0100\xf1\x00DN ESC \x07 104\x19\x08\x01 58910-L0100\xf1\xa01.04',
|
||||
b'\xf1\x00DN ESC \x06 106 \x07\x01 58910-L0100',
|
||||
],
|
||||
(Ecu.engine, 0x7e0, None): [
|
||||
b'\xf1\x81HM6M1_0a0_F00',
|
||||
|
@ -288,9 +289,11 @@ FW_VERSIONS = {
|
|||
b'\xf1\x00LF__ SCC F-CUP 1.00 1.00 96401-C2200 ',
|
||||
],
|
||||
(Ecu.esp, 0x7d1, None): [
|
||||
b'\xf1\x00LF ESC \f 11 \x17\x01\x13 58920-C2610',
|
||||
b'\xf1\x00LF ESC \t 11 \x17\x01\x13 58920-C2610',
|
||||
],
|
||||
(Ecu.engine, 0x7e0, None): [
|
||||
b'\xf1\x81606D5051\x00\x00\x00\x00\x00\x00\x00\x00',
|
||||
b'\xf1\x81606D5K51\x00\x00\x00\x00\x00\x00\x00\x00',
|
||||
b'\xf1\x81606G1051\x00\x00\x00\x00\x00\x00\x00\x00',
|
||||
],
|
||||
|
@ -298,6 +301,8 @@ FW_VERSIONS = {
|
|||
b'\xf1\x00LFF LKAS AT USA LHD 1.00 1.01 95740-C1000 E51',
|
||||
],
|
||||
(Ecu.transmission, 0x7e1, None): [
|
||||
b'\xf1\x87LAHSGN012918KF10\x98\x88x\x87\x88\x88x\x87\x88\x88\x98\x88\x87w\x88w\x88\x88\x98\x886o\xf6\xff\x98w\x7f\xff3\x00\xf1\x816W3B1051\x00\x00\xf1\x006W351_C2\x00\x006W3B1051\x00\x00TLF0T20NL2\x00\x00\x00\x00',
|
||||
b'\xf1\x87LAHSGN012918KF10\x98\x88x\x87\x88\x88x\x87\x88\x88\x98\x88\x87w\x88w\x88\x88\x98\x886o\xf6\xff\x98w\x7f\xff3\x00\xf1\x816W3B1051\x00\x00\xf1\x006W351_C2\x00\x006W3B1051\x00\x00TLF0T20NL2H\r\xbdm',
|
||||
b'\xf1\x87\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xf1\x816T6B4051\x00\x00\xf1\x006T6H0_C2\x00\x006T6B4051\x00\x00TLF0G24NL1\xb0\x9f\xee\xf5',
|
||||
b'\xf1\x87\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xf1\x816T6B4051\x00\x00\xf1\x006T6H0_C2\x00\x006T6B4051\x00\x00TLF0G24NL1\x00\x00\x00\x00',
|
||||
b'\xf1\x006T6H0_C2\x00\x006T6B4051\x00\x00TLF0G24NL1\xb0\x9f\xee\xf5',
|
||||
|
@ -528,14 +533,17 @@ FW_VERSIONS = {
|
|||
(Ecu.fwdCamera, 0x7C4, None): [
|
||||
b'\xf1\x00OE2 LKAS AT EUR LHD 1.00 1.00 95740-K4200 200',
|
||||
b'\xf1\x00OSE LKAS AT EUR LHD 1.00 1.00 95740-K4100 W40',
|
||||
b'\xf1\x00OSE LKAS AT EUR RHD 1.00 1.00 95740-K4100 W40',
|
||||
b'\xf1\x00OSE LKAS AT KOR LHD 1.00 1.00 95740-K4100 W40',
|
||||
b'\xf1\x00OSE LKAS AT USA LHD 1.00 1.00 95740-K4300 W50',
|
||||
],
|
||||
(Ecu.eps, 0x7D4, None): [
|
||||
b'\xf1\x00OS MDPS C 1.00 1.03 56310/K4550 4OEDC103',
|
||||
b'\xf1\x00OS MDPS C 1.00 1.04 56310K4000\x00 4OEDC104',
|
||||
b'\xf1\x00OS MDPS C 1.00 1.04 56310K4050\x00 4OEDC104',
|
||||
],
|
||||
(Ecu.fwdRadar, 0x7D0, None): [
|
||||
b'\xf1\x00OSev SCC F-CUP 1.00 1.00 99110-K4000 \xf1\xa01.00',
|
||||
b'\xf1\x00OSev SCC F-CUP 1.00 1.00 99110-K4100 \xf1\xa01.00',
|
||||
b'\xf1\x00OSev SCC F-CUP 1.00 1.01 99110-K4000 \xf1\xa01.01',
|
||||
b'\xf1\x00OSev SCC FNCUP 1.00 1.01 99110-K4000 \xf1\xa01.01',
|
||||
|
@ -554,6 +562,8 @@ FW_VERSIONS = {
|
|||
(Ecu.esp, 0x7D1, None): [
|
||||
b'\xf1\x00OS IEB \r 212 \x11\x13 58520-K4000\xf1\xa02.12',
|
||||
b'\xf1\x00OS IEB \r 212 \x11\x13 58520-K4000',
|
||||
b'\xf1\xa01.06',
|
||||
b'\xf1\xa01.07',
|
||||
],
|
||||
(Ecu.eps, 0x7D4, None): [
|
||||
b'\xf1\x00DE MDPS C 1.00 1.05 56310Q4000\x00 4DEEC105',
|
||||
|
|
|
@ -17,6 +17,9 @@ EventName = car.CarEvent.EventName
|
|||
# WARNING: this value was determined based on the model's training distribution,
|
||||
# model predictions above this speed can be unpredictable
|
||||
MAX_CTRL_SPEED = (V_CRUISE_MAX + 4) * CV.KPH_TO_MS # 135 + 4 = 86 mph
|
||||
ACCEL_MAX = 2.0
|
||||
ACCEL_MIN = -3.5
|
||||
|
||||
|
||||
# generic car and radar interfaces
|
||||
|
||||
|
@ -42,12 +45,12 @@ class CarInterfaceBase():
|
|||
self.CC = CarController(self.cp.dbc_name, CP, self.VM)
|
||||
|
||||
@staticmethod
|
||||
def calc_accel_override(a_ego, a_target, v_ego, v_target):
|
||||
return 1.
|
||||
def get_pid_accel_limits(CP, current_speed, cruise_speed):
|
||||
return ACCEL_MIN, ACCEL_MAX
|
||||
|
||||
@staticmethod
|
||||
def compute_gb(accel, speed):
|
||||
raise NotImplementedError
|
||||
def calc_accel_override(a_ego, a_target, v_ego, v_target):
|
||||
return 1.
|
||||
|
||||
@staticmethod
|
||||
def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=None):
|
||||
|
@ -72,15 +75,11 @@ class CarInterfaceBase():
|
|||
ret.pcmCruise = True # openpilot's state is tied to the PCM's cruise state on most cars
|
||||
ret.minEnableSpeed = -1. # enable is done by stock ACC, so ignore this
|
||||
ret.steerRatioRear = 0. # no rear steering, at least on the listed cars aboveA
|
||||
ret.gasMaxBP = [0.]
|
||||
ret.gasMaxV = [.5] # half max brake
|
||||
ret.brakeMaxBP = [0.]
|
||||
ret.brakeMaxV = [1.]
|
||||
ret.openpilotLongitudinalControl = False
|
||||
ret.startAccel = 0.0
|
||||
ret.minSpeedCan = 0.3
|
||||
ret.stoppingBrakeRate = 0.2 # brake_travel/s while trying to stop
|
||||
ret.startingBrakeRate = 0.8 # brake_travel/s while releasing on restart
|
||||
ret.stoppingDecelRate = 0.8 # brake_travel/s while trying to stop
|
||||
ret.startingAccelRate = 3.2 # brake_travel/s while releasing on restart
|
||||
ret.stoppingControl = True
|
||||
ret.longitudinalTuning.deadzoneBP = [0.]
|
||||
ret.longitudinalTuning.deadzoneV = [0.]
|
||||
|
@ -88,6 +87,7 @@ class CarInterfaceBase():
|
|||
ret.longitudinalTuning.kpV = [1.]
|
||||
ret.longitudinalTuning.kiBP = [0.]
|
||||
ret.longitudinalTuning.kiV = [1.]
|
||||
ret.longitudinalActuatorDelay = 0.15
|
||||
return ret
|
||||
|
||||
# returns a car.CarState, pass in car.CarControl
|
||||
|
|
|
@ -45,15 +45,18 @@ FW_VERSIONS = {
|
|||
b'K319-3210X-A-00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
|
||||
],
|
||||
(Ecu.engine, 0x7e0, None): [
|
||||
b'PA53-188K2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
|
||||
b'PYNF-188K2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
|
||||
b'PYFA-188K2-J\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'PYFD-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'PX2H-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
|
||||
b'PX2H-188K2-D\0x0\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
|
||||
b'PX38-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
|
||||
b'PX42-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
|
||||
b'PX68-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
|
||||
b'SHKT-188K2-D\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',
|
||||
|
@ -77,6 +80,7 @@ FW_VERSIONS = {
|
|||
b'GSH7-67XK2-N\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
|
||||
],
|
||||
(Ecu.transmission, 0x7e1, None): [
|
||||
b'PA66-21PS1-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
|
||||
b'PX39-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
|
||||
b'PYB1-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
|
||||
b'PYB1-21PS1-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
|
||||
|
@ -86,6 +90,7 @@ FW_VERSIONS = {
|
|||
b'PYB2-21PS1-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
|
||||
b'PYB2-21PS1-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
|
||||
b'PYB2-21PS1-G\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
|
||||
b'SH9T-21PS1-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
|
||||
],
|
||||
},
|
||||
|
||||
|
@ -133,10 +138,12 @@ FW_VERSIONS = {
|
|||
(Ecu.eps, 0x730, None): [
|
||||
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',
|
||||
b'BHN1-3210X-J-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',
|
||||
b'PYKE-188K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
|
||||
b'PY2P-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
|
||||
],
|
||||
(Ecu.fwdRadar, 0x764, None): [
|
||||
|
@ -148,12 +155,14 @@ FW_VERSIONS = {
|
|||
b'B45A-437AS-0-08\x00\x00\x00\x00\x00\x00\x00\x00\x00',
|
||||
],
|
||||
(Ecu.fwdCamera, 0x706, None): [
|
||||
b'B61L-67XK2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
|
||||
b'B61L-67XK2-P\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
|
||||
b'B61L-67XK2-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-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
|
||||
b'PYKE-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
|
||||
],
|
||||
},
|
||||
|
@ -161,21 +170,27 @@ FW_VERSIONS = {
|
|||
CAR.MAZDA6: {
|
||||
(Ecu.eps, 0x730, None): [
|
||||
b'GBEF-3210X-B-00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
|
||||
b'GFBC-3210X-A-00\000\000\000\000\000\000\000\000\000',
|
||||
],
|
||||
(Ecu.engine, 0x7e0, None): [
|
||||
b'PYH7-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
|
||||
b'PX4F-188K2-D\000\000\000\000\000\000\000\000\000\000\000\000',
|
||||
],
|
||||
(Ecu.fwdRadar, 0x764, None): [
|
||||
b'K131-67XK2-A\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
|
||||
b'K131-67XK2-E\000\000\000\000\000\000\000\000\000\000\000\000',
|
||||
],
|
||||
(Ecu.esp, 0x760, None): [
|
||||
b'GBVH-437K2-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
|
||||
b'GDDM-437K2-A\000\000\000\000\000\000\000\000\000\000\000\000',
|
||||
],
|
||||
(Ecu.fwdCamera, 0x706, None): [
|
||||
b'B61L-67XK2-S\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
|
||||
b'GSH7-67XK2-P\000\000\000\000\000\000\000\000\000\000\000\000',
|
||||
],
|
||||
(Ecu.transmission, 0x7e1, None): [
|
||||
b'PYH7-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
|
||||
b'PYH3-21PS1-D\000\000\000\000\000\000\000\000\000\000\000\000',
|
||||
],
|
||||
},
|
||||
|
||||
|
@ -185,6 +200,7 @@ FW_VERSIONS = {
|
|||
],
|
||||
(Ecu.engine, 0x7e0, None): [
|
||||
b'PXM4-188K2-C\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
|
||||
b'PXM4-188K2-D\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
|
||||
],
|
||||
(Ecu.fwdRadar, 0x764, None): [
|
||||
b'K131-67XK2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
|
||||
|
@ -194,6 +210,7 @@ FW_VERSIONS = {
|
|||
],
|
||||
(Ecu.fwdCamera, 0x706, None): [
|
||||
b'GSH7-67XK2-M\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
|
||||
b'GSH7-67XK2-N\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
|
||||
],
|
||||
(Ecu.transmission, 0x7e1, None): [
|
||||
b'PXM4-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00',
|
||||
|
|
|
@ -9,10 +9,6 @@ class CarInterface(CarInterfaceBase):
|
|||
super().__init__(CP, CarController, CarState)
|
||||
self.cp_adas = self.CS.get_adas_can_parser(CP)
|
||||
|
||||
@staticmethod
|
||||
def compute_gb(accel, speed):
|
||||
return float(accel) / 4.0
|
||||
|
||||
@staticmethod
|
||||
def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=None):
|
||||
|
||||
|
|
|
@ -69,7 +69,7 @@ class CarController():
|
|||
self.es_distance_cnt = CS.es_distance_msg["Counter"]
|
||||
|
||||
if self.es_lkas_cnt != CS.es_lkas_msg["Counter"]:
|
||||
can_sends.append(subarucan.create_es_lkas(self.packer, CS.es_lkas_msg, visual_alert, left_line, right_line, left_lane_depart, right_lane_depart))
|
||||
can_sends.append(subarucan.create_es_lkas(self.packer, CS.es_lkas_msg, enabled, visual_alert, left_line, right_line, left_lane_depart, right_lane_depart))
|
||||
self.es_lkas_cnt = CS.es_lkas_msg["Counter"]
|
||||
|
||||
return can_sends
|
||||
|
|
|
@ -51,11 +51,8 @@ class CarState(CarStateBase):
|
|||
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:
|
||||
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]:
|
||||
if (self.car_fingerprint in PREGLOBAL_CARS and cp.vl["Dash_State2"]["UNITS"] == 1) or \
|
||||
(self.car_fingerprint not in PREGLOBAL_CARS and cp.vl["Dashlights"]["UNITS"] == 1):
|
||||
ret.cruiseState.speed *= CV.MPH_TO_KPH
|
||||
|
||||
ret.seatbeltUnlatched = cp.vl["Dashlights"]["SEATBELT_FL"] == 1
|
||||
|
@ -100,7 +97,6 @@ class CarState(CarStateBase):
|
|||
("DOOR_OPEN_FL", "BodyInfo", 1),
|
||||
("DOOR_OPEN_RR", "BodyInfo", 1),
|
||||
("DOOR_OPEN_RL", "BodyInfo", 1),
|
||||
("Units", "Dash_State", 1),
|
||||
("Gear", "Transmission", 0),
|
||||
]
|
||||
|
||||
|
@ -112,7 +108,6 @@ class CarState(CarStateBase):
|
|||
("Wheel_Speeds", 50),
|
||||
("Transmission", 100),
|
||||
("Steering_Torque", 50),
|
||||
("Dash_State", 1),
|
||||
("BodyInfo", 1),
|
||||
]
|
||||
|
||||
|
@ -130,6 +125,7 @@ class CarState(CarStateBase):
|
|||
if CP.carFingerprint not in PREGLOBAL_CARS:
|
||||
signals += [
|
||||
("Steer_Warning", "Steering_Torque", 0),
|
||||
("UNITS", "Dashlights", 0),
|
||||
]
|
||||
|
||||
checks += [
|
||||
|
@ -137,6 +133,14 @@ class CarState(CarStateBase):
|
|||
("BodyInfo", 10),
|
||||
("CruiseControl", 20),
|
||||
]
|
||||
else:
|
||||
signals += [
|
||||
("UNITS", "Dash_State2", 0),
|
||||
]
|
||||
|
||||
checks += [
|
||||
("Dash_State2", 1),
|
||||
]
|
||||
|
||||
if CP.carFingerprint == CAR.FORESTER_PREGLOBAL:
|
||||
checks += [
|
||||
|
@ -207,20 +211,18 @@ class CarState(CarStateBase):
|
|||
("Signal6", "ES_Distance", 0),
|
||||
|
||||
("Counter", "ES_LKAS_State", 0),
|
||||
("Keep_Hands_On_Wheel", "ES_LKAS_State", 0),
|
||||
("Empty_Box", "ES_LKAS_State", 0),
|
||||
("LKAS_Alert_Msg", "ES_LKAS_State", 0),
|
||||
("Signal1", "ES_LKAS_State", 0),
|
||||
("LKAS_ACTIVE", "ES_LKAS_State", 0),
|
||||
("LKAS_Dash_State", "ES_LKAS_State", 0),
|
||||
("Signal2", "ES_LKAS_State", 0),
|
||||
("Backward_Speed_Limit_Menu", "ES_LKAS_State", 0),
|
||||
("LKAS_ENABLE_3", "ES_LKAS_State", 0),
|
||||
("LKAS_Left_Line_Enable", "ES_LKAS_State", 0),
|
||||
("LKAS_Left_Line_Light_Blink", "ES_LKAS_State", 0),
|
||||
("LKAS_ENABLE_2", "ES_LKAS_State", 0),
|
||||
("LKAS_Right_Line_Enable", "ES_LKAS_State", 0),
|
||||
("LKAS_Right_Line_Light_Blink", "ES_LKAS_State", 0),
|
||||
("LKAS_Left_Line_Visible", "ES_LKAS_State", 0),
|
||||
("LKAS_Left_Line_Green", "ES_LKAS_State", 0),
|
||||
("LKAS_Right_Line_Visible", "ES_LKAS_State", 0),
|
||||
("LKAS_Right_Line_Green", "ES_LKAS_State", 0),
|
||||
("LKAS_Alert", "ES_LKAS_State", 0),
|
||||
("Signal3", "ES_LKAS_State", 0),
|
||||
]
|
||||
|
|
|
@ -6,10 +6,6 @@ from selfdrive.car.interfaces import CarInterfaceBase
|
|||
|
||||
class CarInterface(CarInterfaceBase):
|
||||
|
||||
@staticmethod
|
||||
def compute_gb(accel, speed):
|
||||
return float(accel) / 4.0
|
||||
|
||||
@staticmethod
|
||||
def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=None):
|
||||
ret = CarInterfaceBase.get_std_params(candidate, fingerprint)
|
||||
|
|
|
@ -27,20 +27,35 @@ def create_es_distance(packer, es_distance_msg, pcm_cancel_cmd):
|
|||
|
||||
return packer.make_can_msg("ES_Distance", 0, values)
|
||||
|
||||
def create_es_lkas(packer, es_lkas_msg, visual_alert, left_line, right_line, left_lane_depart, right_lane_depart):
|
||||
def create_es_lkas(packer, es_lkas_msg, enabled, visual_alert, left_line, right_line, left_lane_depart, right_lane_depart):
|
||||
|
||||
values = copy.copy(es_lkas_msg)
|
||||
|
||||
# Filter the stock LKAS "Keep hands on wheel" alert
|
||||
if values["LKAS_Alert_Msg"] == 1:
|
||||
values["LKAS_Alert_Msg"] = 0
|
||||
|
||||
# Filter the stock LKAS sending an audible alert when it turns off LKAS
|
||||
if values["LKAS_Alert"] == 27:
|
||||
values["LKAS_Alert"] = 0
|
||||
|
||||
# Show Keep hands on wheel alert for openpilot steerRequired alert
|
||||
if visual_alert == VisualAlert.steerRequired:
|
||||
values["Keep_Hands_On_Wheel"] = 1
|
||||
values["LKAS_Alert_Msg"] = 1
|
||||
|
||||
# Ensure we don't overwrite potentially more important alerts from stock (e.g. FCW)
|
||||
if visual_alert == VisualAlert.ldw and values["LKAS_Alert"] == 0:
|
||||
if left_lane_depart:
|
||||
values["LKAS_Alert"] = 12 # Left lane departure dash alert
|
||||
|
||||
elif right_lane_depart:
|
||||
values["LKAS_Alert"] = 11 # Right lane departure dash alert
|
||||
|
||||
if enabled:
|
||||
values["LKAS_ACTIVE"] = 1 # Show LKAS lane lines
|
||||
values["LKAS_Dash_State"] = 2 # Green enabled indicator
|
||||
else:
|
||||
values["LKAS_Dash_State"] = 0 # LKAS Not enabled
|
||||
|
||||
values["LKAS_Left_Line_Visible"] = int(left_line)
|
||||
values["LKAS_Right_Line_Visible"] = int(right_line)
|
||||
|
||||
|
|
|
@ -28,12 +28,7 @@ FINGERPRINTS = {
|
|||
2: 8, 64: 8, 65: 8, 72: 8, 73: 8, 280: 8, 281: 8, 290: 8, 312: 8, 313: 8, 314: 8, 315: 8, 316: 8, 326: 8, 544: 8, 545: 8, 546: 8, 552: 8, 554: 8, 557: 8, 576: 8, 577: 8, 722: 8, 801: 8, 802: 8, 805: 8, 808: 8, 811: 8, 816: 8, 826: 8, 837: 8, 838: 8, 839: 8, 842: 8, 912: 8, 915: 8, 940: 8, 1614: 8, 1617: 8, 1632: 8, 1650: 8, 1657: 8, 1658: 8, 1677: 8, 1722: 8, 1743: 8, 1759: 8, 1785: 5, 1786: 5, 1787: 5, 1788: 8
|
||||
}],
|
||||
CAR.IMPREZA: [{
|
||||
# SUBARU IMPREZA LIMITED 2019
|
||||
2: 8, 64: 8, 65: 8, 72: 8, 73: 8, 280: 8, 281: 8, 290: 8, 312: 8, 313: 8, 314: 8, 315: 8, 316: 8, 326: 8, 544: 8, 545: 8, 546: 8, 552: 8, 554: 8, 557: 8, 576: 8, 577: 8, 722: 8, 801: 8, 802: 8, 805: 8, 808: 8, 816: 8, 826: 8, 837: 8, 838: 8, 839: 8, 842: 8, 912: 8, 915: 8, 940: 8, 1614: 8, 1617: 8, 1632: 8, 1650: 8, 1657: 8, 1658: 8, 1677: 8, 1697: 8, 1722: 8, 1743: 8, 1759: 8, 1786: 5, 1787: 5, 1788: 8, 1809: 8, 1813: 8, 1817: 8, 1821: 8, 1840: 8, 1848: 8, 1924: 8, 1932: 8, 1952: 8, 1960: 8
|
||||
},
|
||||
# SUBARU CROSSTREK 2018
|
||||
{
|
||||
2: 8, 64: 8, 65: 8, 72: 8, 73: 8, 280: 8, 281: 8, 290: 8, 312: 8, 313: 8, 314: 8, 315: 8, 316: 8, 326: 8, 372: 8, 544: 8, 545: 8, 546: 8, 554: 8, 557: 8, 576: 8, 577: 8, 722: 8, 801: 8, 802: 8, 805: 8, 808: 8, 811: 8, 826: 8, 837: 8, 838: 8, 839: 8, 842: 8, 912: 8, 915: 8, 940: 8, 1614: 8, 1617: 8, 1632: 8, 1650: 8, 1657: 8, 1658: 8, 1677: 8, 1697: 8, 1759: 8, 1786: 5, 1787: 5, 1788: 8
|
||||
2: 8, 64: 8, 65: 8, 72: 8, 73: 8, 280: 8, 281: 8, 290: 8, 312: 8, 313: 8, 314: 8, 315: 8, 316: 8, 326: 8, 372: 8, 544: 8, 545: 8, 546: 8, 552: 8, 554: 8, 557: 8, 576: 8, 577: 8, 722: 8, 801: 8, 802: 8, 805: 8, 808: 8, 811: 8, 816: 8, 826: 8, 827: 8, 837: 8, 838: 8, 839: 8, 842: 8, 912: 8, 915: 8, 940: 8, 1614: 8, 1617: 8, 1632: 8, 1650: 8, 1657: 8, 1658: 8, 1677: 8, 1697: 8, 1722: 8, 1743: 8, 1759: 8, 1786: 5, 1787: 5, 1788: 8, 1809: 8, 1813: 8, 1817: 8, 1821: 8, 1840: 8, 1848: 8, 1924: 8, 1932: 8, 1952: 8, 1960: 8
|
||||
}],
|
||||
CAR.FORESTER: [{
|
||||
# Forester 2019-2020
|
||||
|
|
|
@ -6,11 +6,6 @@ from selfdrive.car.interfaces import CarInterfaceBase
|
|||
|
||||
|
||||
class CarInterface(CarInterfaceBase):
|
||||
@staticmethod
|
||||
def compute_gb(accel, speed):
|
||||
# TODO: is this correct?
|
||||
return accel
|
||||
|
||||
@staticmethod
|
||||
def get_params(candidate, fingerprint=gen_empty_fingerprint(), car_fw=None):
|
||||
ret = CarInterfaceBase.get_std_params(candidate, fingerprint)
|
||||
|
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue