commit
ff4c1557d8
|
@ -25,11 +25,12 @@ clcache
|
|||
|
||||
board/obj/
|
||||
selfdrive/boardd/boardd
|
||||
selfdrive/visiond/visiond
|
||||
selfdrive/logcatd/logcatd
|
||||
selfdrive/mapd/default_speeds_by_region.json
|
||||
selfdrive/proclogd/proclogd
|
||||
selfdrive/ui/ui
|
||||
selfdrive/test/tests/plant/out
|
||||
selfdrive/visiond/visiond
|
||||
/src/
|
||||
|
||||
one
|
||||
|
|
|
@ -7,6 +7,8 @@ install:
|
|||
- docker build -t tmppilot -f Dockerfile.openpilot .
|
||||
|
||||
script:
|
||||
- docker run --rm
|
||||
- docker run
|
||||
-v "$(pwd)"/selfdrive/test/tests/plant/out:/tmp/openpilot/selfdrive/test/tests/plant/out
|
||||
tmppilot /bin/sh -c 'cd /tmp/openpilot/selfdrive/test/tests/plant && OPTEST=1 ./test_longitudinal.py'
|
||||
- docker run
|
||||
tmppilot /bin/sh -c 'cd /tmp/openpilot/selfdrive/test/ && ./test_fingerprints.py'
|
||||
|
|
|
@ -1,4 +1,4 @@
|
|||
[![](https://i.imgur.com/UetIFyH.jpg)](#)
|
||||
[![](https://i.imgur.com/xY2gdHv.png)](#)
|
||||
|
||||
Welcome to openpilot
|
||||
======
|
||||
|
@ -114,12 +114,11 @@ Community Maintained Cars
|
|||
| Make | Model | Supported Package | Lateral | Longitudinal | No Accel Below | No Steer Below | Giraffe |
|
||||
| ---------------------| -------------------------| ---------------------| --------| ---------------| -----------------| ---------------|-------------------|
|
||||
| Honda | Fit 2018 | Honda Sensing | Yes | Yes | 25mph<sup>1</sup>| 12mph | Inverted Nidec |
|
||||
| Tesla | Model S 2012 | All | Yes | Not yet | Not applicable | 0mph | Custom<sup>9</sup>|
|
||||
| Tesla | Model S 2013 | All | Yes | Not yet | Not applicable | 0mph | Custom<sup>9</sup>|
|
||||
| Tesla | Model S 2012-13 | All | Yes | Not yet | Not applicable | 0mph | Custom<sup>8</sup>|
|
||||
|
||||
[[Honda Fit Pull Request]](https://github.com/commaai/openpilot/pull/266). <br />
|
||||
[[Tesla Model S Pull Request]](https://github.com/commaai/openpilot/pull/246) <br />
|
||||
<sup>9</sup>Community built Giraffe, find more information here [Community Tesla Giraffe](https://github.com/jeankalud/neo/tree/tesla_giraffe/giraffe/tesla) <br />
|
||||
<sup>8</sup>Community built Giraffe, find more information here [Community Tesla Giraffe](https://github.com/jeankalud/neo/tree/tesla_giraffe/giraffe/tesla) <br />
|
||||
|
||||
Community Maintained Cars are not confirmed by comma.ai to meet our [safety model](https://github.com/commaai/openpilot/blob/devel/SAFETY.md). Be extra cautious using them.
|
||||
|
||||
|
|
15
RELEASES.md
15
RELEASES.md
|
@ -1,3 +1,16 @@
|
|||
Version 0.5.10 (2019-03-19)
|
||||
========================
|
||||
* Self-tuning vehicle parameters: steering offset, tires stiffness and steering ratio
|
||||
* Improve longitudinal control at low speed when lead vehicle harshly decelerates
|
||||
* Fix panda bug going unexpectedly in DCP mode when EON is connected
|
||||
* Reduce white panda power consumption by 500mW when EON is disconnected by turning off WIFI
|
||||
* New Driver Monitoring Model
|
||||
* Support QR codes for login using comma connect
|
||||
* Refactor comma pedal FW and use CRC-8 checksum algorithm for safety. Reflashing pedal is required.
|
||||
Please see `#hw-pedal` on [discord](discord.comma.ai) for assistance updating comma pedal.
|
||||
* Additional speed limit rules for Germany thanks to arne182
|
||||
* Allow negative speed limit offsets
|
||||
|
||||
Version 0.5.9 (2019-02-10)
|
||||
========================
|
||||
* Improve calibration using a dedicated neural network
|
||||
|
@ -8,7 +21,7 @@ Version 0.5.9 (2019-02-10)
|
|||
* Kia Optima support thanks to emmertex!
|
||||
* Buick Regal 2018 support thanks to HOYS!
|
||||
* Comma pedal support for Toyota thanks to wocsor! Note: tuning needed and not maintained by comma
|
||||
* Chrysler Pacifica and Jeep Grand Cherokee suppor thanks to adhintz!
|
||||
* Chrysler Pacifica and Jeep Grand Cherokee support thanks to adhintz!
|
||||
|
||||
Version 0.5.8 (2019-01-17)
|
||||
========================
|
||||
|
|
33
SAFETY.md
33
SAFETY.md
|
@ -89,7 +89,7 @@ GM/Chevrolet
|
|||
and openpilot to 350. This is approximately 0.3g of braking.
|
||||
|
||||
- Steering torque is controlled through the 0x180 CAN message and it's limited by the panda firmware and by
|
||||
openpilot to a value between -255 and 255. In addition, the vehicle EPS unit will not fault when
|
||||
openpilot to a value between -300 and 300. In addition, the vehicle EPS unit will fault for
|
||||
commands outside these limits. A steering torque rate limit is enforced by the panda firmware and by
|
||||
openpilot, so that the commanded steering torque must rise from 0 to max value no faster than
|
||||
0.75s. Commanded steering torque is gradually limited by the panda firmware and by openpilot if the driver's
|
||||
|
@ -105,5 +105,34 @@ GM/Chevrolet
|
|||
- GM CAN uses both a counter and a checksum to ensure integrity and prevent
|
||||
replay of the same message.
|
||||
|
||||
**Extra note"**: comma.ai strongly discourages the use of openpilot forks with safety code either missing or
|
||||
Hyundai/Kia (Lateral only)
|
||||
------
|
||||
|
||||
- While the system is engaged, steer commands are subject to the same limits used by
|
||||
the stock system.
|
||||
|
||||
- Steering torque is controlled through the 0x340 CAN message and it's limited by the panda firmware and by
|
||||
openpilot to a value between -255 and 255. In addition, the vehicle EPS unit will fault for
|
||||
commands outside the values of -409 and 409. A steering torque rate limit is enforced by the panda firmware and by
|
||||
openpilot, so that the commanded steering torque must rise from 0 to max value no faster than
|
||||
0.85s. Commanded steering torque is gradually limited by the panda firmware and by openpilot if the driver's
|
||||
torque exceeds 50 units in the opposite dicrection to ensure limited applied torque against the
|
||||
driver's will.
|
||||
|
||||
Chrysler/Jeep/Fiat (Lateral only)
|
||||
------
|
||||
|
||||
- While the system is engaged, steer commands are subject to the same limits used by
|
||||
the stock system.
|
||||
|
||||
- Steering torque is controlled through the 0x292 CAN message and it's limited by the panda firmware and by
|
||||
openpilot to a value between -261 and 261. In addition, the vehicle EPS unit will fault for
|
||||
commands outside these limits. A steering torque rate limit is enforced by the panda firmware and by
|
||||
openpilot, so that the commanded steering torque must rise from 0 to max value no faster than
|
||||
0.87s. Commanded steering torque is limited by the panda firmware and by openpilot to be no more than 80
|
||||
units above the actual EPS generated motor torque to ensure limited differences between
|
||||
commanded and actual torques.
|
||||
|
||||
|
||||
**Extra note**: comma.ai strongly discourages the use of openpilot forks with safety code either missing or
|
||||
not fully meeting the above requirements.
|
||||
|
|
Binary file not shown.
|
@ -72,6 +72,7 @@ struct CarEvent @0x9b1657f34caf3ad3 {
|
|||
calibrationProgress @47;
|
||||
lowBattery @48;
|
||||
invalidGiraffeHonda @49;
|
||||
vehicleModelInvalid @50;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -317,6 +318,7 @@ struct CarParams {
|
|||
hyundai @8;
|
||||
chrysler @9;
|
||||
tesla @10;
|
||||
subaru @11;
|
||||
}
|
||||
|
||||
# things about the car in the manual
|
||||
|
|
|
@ -419,7 +419,7 @@ struct Live100Data {
|
|||
alertType @44 :Text;
|
||||
alertSound @45 :Text;
|
||||
awarenessStatus @26 :Float32;
|
||||
angleOffset @27 :Float32;
|
||||
angleModelBias @27 :Float32;
|
||||
gpsPlannerActive @40 :Bool;
|
||||
engageable @41 :Bool; # can OP be engaged?
|
||||
driverMonitoringOn @43 :Bool;
|
||||
|
@ -582,6 +582,9 @@ struct Plan {
|
|||
vCurvature @21 :Float32;
|
||||
decelForTurn @22 :Bool;
|
||||
mapValid @25 :Bool;
|
||||
radarValid @28 :Bool;
|
||||
|
||||
processingDelay @29 :Float32;
|
||||
|
||||
|
||||
struct GpsTrajectory {
|
||||
|
@ -608,8 +611,12 @@ struct PathPlan {
|
|||
rPoly @6 :List(Float32);
|
||||
rProb @7 :Float32;
|
||||
|
||||
angleSteers @8 :Float32;
|
||||
angleSteers @8 :Float32; # deg
|
||||
rateSteers @13 :Float32; # deg/s
|
||||
valid @9 :Bool;
|
||||
paramsValid @10 :Bool;
|
||||
modelValid @12 :Bool;
|
||||
angleOffset @11 :Float32;
|
||||
}
|
||||
|
||||
struct LiveLocationData {
|
||||
|
@ -1602,6 +1609,9 @@ struct LiveParametersData {
|
|||
valid @0 :Bool;
|
||||
gyroBias @1 :Float32;
|
||||
angleOffset @2 :Float32;
|
||||
angleOffsetAverage @3 :Float32;
|
||||
stiffnessFactor @4 :Float32;
|
||||
steerRatio @5 :Float32;
|
||||
}
|
||||
|
||||
struct LiveMapData {
|
||||
|
|
|
@ -6,7 +6,11 @@ from cffi import FFI
|
|||
|
||||
TMPDIR = "/tmp/ccache"
|
||||
|
||||
def ffi_wrap(name, c_code, c_header, tmpdir=TMPDIR, cflags="", libraries=[]):
|
||||
|
||||
def ffi_wrap(name, c_code, c_header, tmpdir=TMPDIR, cflags="", libraries=None):
|
||||
if libraries is None:
|
||||
libraries = []
|
||||
|
||||
cache = name + "_" + hashlib.sha1(c_code).hexdigest()
|
||||
try:
|
||||
os.mkdir(tmpdir)
|
||||
|
@ -28,7 +32,11 @@ def ffi_wrap(name, c_code, c_header, tmpdir=TMPDIR, cflags="", libraries=[]):
|
|||
|
||||
return mod.ffi, mod.lib
|
||||
|
||||
def compile_code(name, c_code, c_header, directory, cflags="", libraries=[]):
|
||||
|
||||
def compile_code(name, c_code, c_header, directory, cflags="", libraries=None):
|
||||
if libraries is None:
|
||||
libraries = []
|
||||
|
||||
ffibuilder = FFI()
|
||||
ffibuilder.set_source(name, c_code, source_extension='.cpp', libraries=libraries)
|
||||
ffibuilder.cdef(c_header)
|
||||
|
@ -36,6 +44,7 @@ def compile_code(name, c_code, c_header, directory, cflags="", libraries=[]):
|
|||
os.environ['CFLAGS'] = cflags
|
||||
ffibuilder.compile(verbose=True, debug=False, tmpdir=directory)
|
||||
|
||||
|
||||
def wrap_compiled(name, directory):
|
||||
sys.path.append(directory)
|
||||
mod = __import__(name)
|
||||
|
|
|
@ -29,6 +29,7 @@ import fcntl
|
|||
import tempfile
|
||||
from enum import Enum
|
||||
|
||||
|
||||
def mkdirs_exists_ok(path):
|
||||
try:
|
||||
os.makedirs(path)
|
||||
|
@ -36,52 +37,47 @@ def mkdirs_exists_ok(path):
|
|||
if not os.path.isdir(path):
|
||||
raise
|
||||
|
||||
|
||||
class TxType(Enum):
|
||||
PERSISTENT = 1
|
||||
CLEAR_ON_MANAGER_START = 2
|
||||
CLEAR_ON_CAR_START = 3
|
||||
|
||||
|
||||
class UnknownKeyName(Exception):
|
||||
pass
|
||||
|
||||
|
||||
keys = {
|
||||
# written: manager
|
||||
# read: loggerd, uploaderd, offroad
|
||||
"DongleId": TxType.PERSISTENT,
|
||||
"AccessToken": TxType.PERSISTENT,
|
||||
"Version": TxType.PERSISTENT,
|
||||
"TrainingVersion": TxType.PERSISTENT,
|
||||
"GitCommit": TxType.PERSISTENT,
|
||||
"GitBranch": TxType.PERSISTENT,
|
||||
"GitRemote": TxType.PERSISTENT,
|
||||
# written: baseui
|
||||
# read: ui, controls
|
||||
"IsMetric": TxType.PERSISTENT,
|
||||
"IsFcwEnabled": TxType.PERSISTENT,
|
||||
"HasAcceptedTerms": TxType.PERSISTENT,
|
||||
"CompletedTrainingVersion": TxType.PERSISTENT,
|
||||
"IsUploadVideoOverCellularEnabled": TxType.PERSISTENT,
|
||||
"IsDriverMonitoringEnabled": TxType.PERSISTENT,
|
||||
"IsGeofenceEnabled": TxType.PERSISTENT,
|
||||
"SpeedLimitOffset": TxType.PERSISTENT,
|
||||
# written: visiond
|
||||
# read: visiond, controlsd
|
||||
"CalibrationParams": TxType.PERSISTENT,
|
||||
"ControlsParams": TxType.PERSISTENT,
|
||||
# written: controlsd
|
||||
# read: radard
|
||||
"CarParams": TxType.CLEAR_ON_CAR_START,
|
||||
|
||||
"Passive": TxType.PERSISTENT,
|
||||
"CompletedTrainingVersion": TxType.PERSISTENT,
|
||||
"ControlsParams": TxType.PERSISTENT,
|
||||
"DoUninstall": TxType.CLEAR_ON_MANAGER_START,
|
||||
"ShouldDoUpdate": TxType.CLEAR_ON_MANAGER_START,
|
||||
"DongleId": TxType.PERSISTENT,
|
||||
"GitBranch": TxType.PERSISTENT,
|
||||
"GitCommit": TxType.PERSISTENT,
|
||||
"GitRemote": TxType.PERSISTENT,
|
||||
"HasAcceptedTerms": TxType.PERSISTENT,
|
||||
"IsDriverMonitoringEnabled": TxType.PERSISTENT,
|
||||
"IsFcwEnabled": TxType.PERSISTENT,
|
||||
"IsGeofenceEnabled": TxType.PERSISTENT,
|
||||
"IsMetric": TxType.PERSISTENT,
|
||||
"IsUpdateAvailable": TxType.PERSISTENT,
|
||||
"LongitudinalControl": TxType.PERSISTENT,
|
||||
"IsUploadVideoOverCellularEnabled": TxType.PERSISTENT,
|
||||
"LimitSetSpeed": TxType.PERSISTENT,
|
||||
|
||||
"LiveParameters": TxType.PERSISTENT,
|
||||
"LongitudinalControl": TxType.PERSISTENT,
|
||||
"Passive": TxType.PERSISTENT,
|
||||
"RecordFront": TxType.PERSISTENT,
|
||||
"ShouldDoUpdate": TxType.CLEAR_ON_MANAGER_START,
|
||||
"SpeedLimitOffset": TxType.PERSISTENT,
|
||||
"TrainingVersion": TxType.PERSISTENT,
|
||||
"Version": TxType.PERSISTENT,
|
||||
}
|
||||
|
||||
|
||||
def fsync_dir(path):
|
||||
fd = os.open(path, os.O_RDONLY)
|
||||
try:
|
||||
|
|
|
@ -0,0 +1,81 @@
|
|||
#!/usr/bin/env python
|
||||
import sympy as sp
|
||||
import numpy as np
|
||||
|
||||
def cross(x):
|
||||
ret = sp.Matrix(np.zeros((3,3)))
|
||||
ret[0,1], ret[0,2] = -x[2], x[1]
|
||||
ret[1,0], ret[1,2] = x[2], -x[0]
|
||||
ret[2,0], ret[2,1] = -x[1], x[0]
|
||||
return ret
|
||||
|
||||
def euler_rotate(roll, pitch, yaw):
|
||||
# make symbolic rotation matrix from eulers
|
||||
matrix_roll = sp.Matrix([[1, 0, 0],
|
||||
[0, sp.cos(roll), -sp.sin(roll)],
|
||||
[0, sp.sin(roll), sp.cos(roll)]])
|
||||
matrix_pitch = sp.Matrix([[sp.cos(pitch), 0, sp.sin(pitch)],
|
||||
[0, 1, 0],
|
||||
[-sp.sin(pitch), 0, sp.cos(pitch)]])
|
||||
matrix_yaw = sp.Matrix([[sp.cos(yaw), -sp.sin(yaw), 0],
|
||||
[sp.sin(yaw), sp.cos(yaw), 0],
|
||||
[0, 0, 1]])
|
||||
return matrix_yaw*matrix_pitch*matrix_roll
|
||||
|
||||
def quat_rotate(q0, q1, q2, q3):
|
||||
# make symbolic rotation matrix from quat
|
||||
return sp.Matrix([[q0**2 + q1**2 - q2**2 - q3**2, 2*(q1*q2 + q0*q3), 2*(q1*q3 - q0*q2)],
|
||||
[2*(q1*q2 - q0*q3), q0**2 - q1**2 + q2**2 - q3**2, 2*(q2*q3 + q0*q1)],
|
||||
[2*(q1*q3 + q0*q2), 2*(q2*q3 - q0*q1), q0**2 - q1**2 - q2**2 + q3**2]]).T
|
||||
|
||||
def quat_matrix_l(p):
|
||||
return sp.Matrix([[p[0], -p[1], -p[2], -p[3]],
|
||||
[p[1], p[0], -p[3], p[2]],
|
||||
[p[2], p[3], p[0], -p[1]],
|
||||
[p[3], -p[2], p[1], p[0]]])
|
||||
|
||||
def quat_matrix_r(p):
|
||||
return sp.Matrix([[p[0], -p[1], -p[2], -p[3]],
|
||||
[p[1], p[0], p[3], -p[2]],
|
||||
[p[2], -p[3], p[0], p[1]],
|
||||
[p[3], p[2], -p[1], p[0]]])
|
||||
|
||||
|
||||
def sympy_into_c(sympy_functions):
|
||||
from sympy.utilities import codegen
|
||||
routines = []
|
||||
for name, expr, args in sympy_functions:
|
||||
r = codegen.make_routine(name, expr, language="C99")
|
||||
|
||||
# argument ordering input to sympy is broken with function with output arguments
|
||||
nargs = []
|
||||
# reorder the input arguments
|
||||
for aa in args:
|
||||
if aa is None:
|
||||
nargs.append(codegen.InputArgument(sp.Symbol('unused'), dimensions=[1,1]))
|
||||
continue
|
||||
found = False
|
||||
for a in r.arguments:
|
||||
if str(aa.name) == str(a.name):
|
||||
nargs.append(a)
|
||||
found = True
|
||||
break
|
||||
if not found:
|
||||
# [1,1] is a hack for Matrices
|
||||
nargs.append(codegen.InputArgument(aa, dimensions=[1,1]))
|
||||
# add the output arguments
|
||||
for a in r.arguments:
|
||||
if type(a) == codegen.OutputArgument:
|
||||
nargs.append(a)
|
||||
|
||||
#assert len(r.arguments) == len(args)+1
|
||||
r.arguments = nargs
|
||||
|
||||
# add routine to list
|
||||
routines.append(r)
|
||||
|
||||
[(c_name, c_code), (h_name, c_header)] = codegen.get_code_generator('C', 'ekf', 'C99').write(routines, "ekf")
|
||||
c_code = '\n'.join(filter(lambda x: len(x) > 0 and x[0] != '#', c_code.split("\n")))
|
||||
c_header = '\n'.join(filter(lambda x: len(x) > 0 and x[0] != '#', c_header.split("\n")))
|
||||
|
||||
return c_header, c_code
|
|
@ -112,6 +112,7 @@ def img_from_device(pt_device):
|
|||
return pt_img.reshape(input_shape)[:,:2]
|
||||
|
||||
|
||||
#TODO please use generic img transform below
|
||||
def rotate_img(img, eulers, crop=None, intrinsics=eon_intrinsics):
|
||||
size = img.shape[:2]
|
||||
rot = orient.rot_from_euler(eulers)
|
||||
|
@ -138,3 +139,36 @@ def rotate_img(img, eulers, crop=None, intrinsics=eon_intrinsics):
|
|||
img_warped = cv2.warpPerspective(img, M, size[::-1])
|
||||
return img_warped[H_border: size[0] - H_border,
|
||||
W_border: size[1] - W_border]
|
||||
|
||||
|
||||
def transform_img(base_img,
|
||||
augment_trans=np.array([0,0,0]),
|
||||
augment_eulers=np.array([0,0,0]),
|
||||
from_intr=eon_intrinsics,
|
||||
to_intr=eon_intrinsics,
|
||||
calib_rot_view=None,
|
||||
output_size=None):
|
||||
cy = from_intr[1,2]
|
||||
size = base_img.shape[:2]
|
||||
if not output_size:
|
||||
output_size = size[::-1]
|
||||
h = 1.22
|
||||
quadrangle = np.array([[0, cy + 20],
|
||||
[size[1]-1, cy + 20],
|
||||
[0, size[0]-1],
|
||||
[size[1]-1, size[0]-1]], dtype=np.float32)
|
||||
quadrangle_norm = np.hstack((normalize(quadrangle, intrinsics=from_intr), np.ones((4,1))))
|
||||
quadrangle_world = np.column_stack((h*quadrangle_norm[:,0]/quadrangle_norm[:,1],
|
||||
h*np.ones(4),
|
||||
h/quadrangle_norm[:,1]))
|
||||
rot = orient.rot_from_euler(augment_eulers)
|
||||
if calib_rot_view is not None:
|
||||
rot = calib_rot_view.dot(rot)
|
||||
to_extrinsics = np.hstack((rot.T, -augment_trans[:,None]))
|
||||
to_KE = to_intr.dot(to_extrinsics)
|
||||
warped_quadrangle_full = np.einsum('jk,ik->ij', to_KE, np.hstack((quadrangle_world, np.ones((4,1)))))
|
||||
warped_quadrangle = np.column_stack((warped_quadrangle_full[:,0]/warped_quadrangle_full[:,2],
|
||||
warped_quadrangle_full[:,1]/warped_quadrangle_full[:,2])).astype(np.float32)
|
||||
M = cv2.getPerspectiveTransform(quadrangle, warped_quadrangle.astype(np.float32))
|
||||
augmented_rgb = cv2.warpPerspective(base_img, M, output_size, borderMode=cv2.BORDER_REPLICATE)
|
||||
return augmented_rgb
|
||||
|
|
|
@ -31,6 +31,18 @@ model_intrinsics = np.array(
|
|||
[ 0. , 0. , 1.]])
|
||||
|
||||
|
||||
# MED model
|
||||
MEDMODEL_INPUT_SIZE = (640, 240)
|
||||
MEDMODEL_YUV_SIZE = (MEDMODEL_INPUT_SIZE[0], MEDMODEL_INPUT_SIZE[1] * 3 // 2)
|
||||
MEDMODEL_CY = 47.6
|
||||
|
||||
medmodel_zoom = 1.
|
||||
medmodel_intrinsics = np.array(
|
||||
[[ eon_focal_length / medmodel_zoom, 0. , 0.5 * MEDMODEL_INPUT_SIZE[0]],
|
||||
[ 0. , eon_focal_length / medmodel_zoom, MEDMODEL_CY],
|
||||
[ 0. , 0. , 1.]])
|
||||
|
||||
|
||||
# BIG model
|
||||
|
||||
BIGMODEL_INPUT_SIZE = (864, 288)
|
||||
|
@ -57,6 +69,9 @@ model_frame_from_road_frame = np.dot(model_intrinsics,
|
|||
bigmodel_frame_from_road_frame = np.dot(bigmodel_intrinsics,
|
||||
get_view_frame_from_road_frame(0, 0, 0, model_height))
|
||||
|
||||
medmodel_frame_from_road_frame = np.dot(medmodel_intrinsics,
|
||||
get_view_frame_from_road_frame(0, 0, 0, model_height))
|
||||
|
||||
model_frame_from_bigmodel_frame = np.dot(model_intrinsics, np.linalg.inv(bigmodel_intrinsics))
|
||||
|
||||
# 'camera from model camera'
|
||||
|
@ -110,3 +125,17 @@ def get_camera_frame_from_bigmodel_frame(camera_frame_from_road_frame):
|
|||
camera_frame_from_bigmodel_frame = np.dot(camera_frame_from_ground, ground_from_bigmodel_frame)
|
||||
|
||||
return camera_frame_from_bigmodel_frame
|
||||
|
||||
|
||||
def get_model_frame(snu_full, camera_frame_from_model_frame, size):
|
||||
idxs = camera_frame_from_model_frame.dot(np.column_stack([np.tile(np.arange(size[0]), size[1]),
|
||||
np.tile(np.arange(size[1]), (size[0],1)).T.flatten(),
|
||||
np.ones(size[0] * size[1])]).T).T.astype(int)
|
||||
calib_flat = snu_full[idxs[:,1], idxs[:,0]]
|
||||
if len(snu_full.shape) == 3:
|
||||
calib = calib_flat.reshape((size[1], size[0], 3))
|
||||
elif len(snu_full.shape) == 2:
|
||||
calib = calib_flat.reshape((size[1], size[0]))
|
||||
else:
|
||||
raise ValueError("shape of input img is weird")
|
||||
return calib
|
||||
|
|
Binary file not shown.
File diff suppressed because it is too large
Load Diff
|
@ -6,15 +6,15 @@ 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 : 45|2@0+ (1,0) [0|3] "" INTERCEPTOR
|
||||
SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" 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|8@0+ (1,0) [0|255] "" EON
|
||||
SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" 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" ;
|
||||
|
||||
|
|
|
@ -6,15 +6,15 @@ 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 : 45|2@0+ (1,0) [0|3] "" INTERCEPTOR
|
||||
SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" 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|8@0+ (1,0) [0|255] "" EON
|
||||
SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" 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" ;
|
||||
|
||||
|
|
|
@ -44,15 +44,15 @@ BO_ 544 a_1: 8 XXX
|
|||
SG_ status2 : 39|6@0+ (1,0) [0|15] "" XXX
|
||||
SG_ sig2 : 33|10@0+ (1,0) [0|255] "" XXX
|
||||
SG_ zeros : 55|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ COUNTER : 48|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ COUNTER : 51|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 576 b_1: 8 XXX
|
||||
SG_ sig0 : 0|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ sig0 : 7|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ sig1 : 15|16@0+ (1,0) [0|65535] "" XXX
|
||||
SG_ sig2 : 31|16@0+ (1,0) [0|255] "" XXX
|
||||
SG_ zeros : 47|12@0+ (1,0) [0|255] "" XXX
|
||||
SG_ COUNTER : 48|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ COUNTER : 51|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 608 a_2: 8 XXX
|
||||
|
@ -63,15 +63,15 @@ BO_ 608 a_2: 8 XXX
|
|||
SG_ status2 : 39|6@0+ (1,0) [0|15] "" XXX
|
||||
SG_ sig2 : 33|10@0+ (1,0) [0|255] "" XXX
|
||||
SG_ zeros : 55|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ COUNTER : 48|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ COUNTER : 51|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 640 b_2: 8 XXX
|
||||
SG_ sig0 : 0|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ sig0 : 7|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ sig1 : 15|16@0+ (1,0) [0|65535] "" XXX
|
||||
SG_ sig2 : 31|16@0+ (1,0) [0|255] "" XXX
|
||||
SG_ zeros : 47|12@0+ (1,0) [0|255] "" XXX
|
||||
SG_ COUNTER : 48|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ COUNTER : 51|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 644 a_3: 8 XXX
|
||||
|
@ -82,15 +82,15 @@ BO_ 644 a_3: 8 XXX
|
|||
SG_ status2 : 39|6@0+ (1,0) [0|15] "" XXX
|
||||
SG_ sig2 : 33|10@0+ (1,0) [0|255] "" XXX
|
||||
SG_ zeros : 55|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ COUNTER : 48|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ COUNTER : 51|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 648 b_3: 8 XXX
|
||||
SG_ sig0 : 0|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ sig0 : 7|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ sig1 : 15|16@0+ (1,0) [0|65535] "" XXX
|
||||
SG_ sig2 : 31|16@0+ (1,0) [0|255] "" XXX
|
||||
SG_ zeros : 47|12@0+ (1,0) [0|255] "" XXX
|
||||
SG_ COUNTER : 48|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ COUNTER : 51|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 652 a_4: 8 XXX
|
||||
|
@ -101,19 +101,19 @@ BO_ 652 a_4: 8 XXX
|
|||
SG_ status2 : 39|6@0+ (1,0) [0|15] "" XXX
|
||||
SG_ sig2 : 33|10@0+ (1,0) [0|255] "" XXX
|
||||
SG_ zeros : 55|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ COUNTER : 48|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ COUNTER : 51|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 656 b_4: 8 XXX
|
||||
SG_ sig0 : 0|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ sig0 : 7|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ sig1 : 15|16@0+ (1,0) [0|65535] "" XXX
|
||||
SG_ sig2 : 31|16@0+ (1,0) [0|255] "" XXX
|
||||
SG_ zeros : 47|12@0+ (1,0) [0|255] "" XXX
|
||||
SG_ COUNTER : 48|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ COUNTER : 51|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 512 unknown_200: 8 XXX
|
||||
SG_ COUNTER : 48|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ COUNTER : 51|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ increasing : 31|16@0+ (1,0) [0|255] "" XXX
|
||||
SG_ zeros_0 : 3|12@0+ (1,0) [0|63] "" XXX
|
||||
|
|
|
@ -2,14 +2,14 @@ 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 : 45|2@0+ (1,0) [0|3] "" INTERCEPTOR
|
||||
SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" 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|8@0+ (1,0) [0|255] "" EON
|
||||
SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" 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" ;
|
||||
|
|
|
@ -0,0 +1,48 @@
|
|||
CM_ "IMPORT _bosch_2018.dbc"
|
||||
|
||||
BO_ 419 GEARBOX: 8 PCM
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
|
||||
SG_ GEAR_SHIFTER : 29|6@0+ (1,0) [0|63] "" EON
|
||||
SG_ GEAR : 7|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
BO_ 432 STANDSTILL: 7 VSA
|
||||
SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" EON
|
||||
|
||||
BO_ 927 RADAR_HUD: 8 RADAR
|
||||
SG_ ZEROS_BOH : 7|10@0+ (1,0) [0|127] "" BDY
|
||||
SG_ CMBS_OFF : 12|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ ZEROS_BOH3 : 31|32@0+ (1,0) [0|4294967295] "" XXX
|
||||
SG_ RESUME_INSTRUCTION : 21|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ SET_TO_1 : 13|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ ZEROS_BOH2 : 11|4@0+ (1,0) [0|1] "" XXX
|
||||
SG_ APPLY_BRAKES_FOR_CANC : 23|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ ACC_ALERTS : 20|5@0+ (1,0) [0|1] "" BDY
|
||||
SG_ SET_TO_0 : 22|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
|
||||
|
||||
BO_ 1302 ODOMETER: 8 XXX
|
||||
SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" EON
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
|
||||
|
||||
CM_ SG_ 344 DISTANCE_COUNTER "";
|
||||
CM_ SG_ 450 EPB_STATE "3: On, 2: Disengaging, 1: Engaging, 0: Off";
|
||||
CM_ SG_ 479 CONTROL_ON "Set to 5 when car is being controlled";
|
||||
CM_ SG_ 479 RELATED_TO_GAS "bits 7, 3, and 1 set to 1 when gas not applied";
|
||||
CM_ SG_ 479 GAS_BRAKE "Signed value, negative when braking and positive when applying gas";
|
||||
|
||||
VAL_ 419 GEAR_SHIFTER 32 "D" 8 "R" 4 "P" ;
|
||||
VAL_ 545 ECON_ON_2 0 "off" 3 "on" ;
|
||||
VAL_ 662 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ;
|
||||
VAL_ 662 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ;
|
||||
VAL_ 806 CMBS_BUTTON 3 "pressed" 0 "released" ;
|
||||
VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off" ;
|
||||
VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ;
|
||||
|
||||
CM_ "CHFFR_METRIC 330 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0";
|
|
@ -14,12 +14,14 @@ CM BO_ STEERING_IPAS_COMMA "Copy of msg 614 so we can do angle control while the
|
|||
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_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" 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|8@0+ (1,0) [0|255] "" EON
|
||||
SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" 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" ;
|
||||
|
|
|
@ -0,0 +1,41 @@
|
|||
CM_ "IMPORT _toyota_2017.dbc"
|
||||
CM_ "IMPORT _comma.dbc"
|
||||
|
||||
BO_ 581 GAS_PEDAL: 5 XXX
|
||||
SG_ GAS_PEDAL : 23|8@0+ (0.005,0) [0|1] "" XXX
|
||||
|
||||
BO_ 550 BRAKE_MODULE: 8 XXX
|
||||
SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|511] "" XXX
|
||||
SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|511] "" XXX
|
||||
SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 608 STEER_TORQUE_SENSOR: 8 XXX
|
||||
SG_ STEER_TORQUE_EPS : 47|16@0- (0.66,0) [-20000|20000] "" XXX
|
||||
SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX
|
||||
SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 610 EPS_STATUS: 5 EPS
|
||||
SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX
|
||||
SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 956 GEAR_PACKET: 8 XXX
|
||||
SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX
|
||||
|
||||
BO_ 1009 PCM_CRUISE_ISH: 8 XXX
|
||||
SG_ MAIN_ON : 13|1@0+ (1,0) [0|3] "" XXX
|
||||
SG_ CRUISE_STATE : 10|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "mph" XXX
|
||||
|
||||
BO_ 1599 LIGHT_STALK_ISH: 8 SCM
|
||||
SG_ AUTO_HIGH_BEAM : 19|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
CM_ SG_ 550 BRAKE_PRESSURE "seems prop to pedal force";
|
||||
CM_ SG_ 550 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8";
|
||||
CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others";
|
||||
CM_ SG_ 1009 SET_SPEED "units seem to be whatever the car is set to";
|
||||
VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P";
|
||||
VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled";
|
||||
VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby";
|
|
@ -20,6 +20,7 @@ BO_ 608 STEER_TORQUE_SENSOR: 8 XXX
|
|||
SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX
|
||||
SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ STEER_ANGLE : 31|16@0- (0.05527,0) [-500|500] "" XXX
|
||||
|
||||
BO_ 610 EPS_STATUS: 8 EPS
|
||||
SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX
|
||||
|
|
|
@ -6,15 +6,15 @@ 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 : 45|2@0+ (1,0) [0|3] "" INTERCEPTOR
|
||||
SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" 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|8@0+ (1,0) [0|255] "" EON
|
||||
SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" 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" ;
|
||||
|
||||
|
|
|
@ -0,0 +1,316 @@
|
|||
CM_ "AUTOGENERATED FILE, DO NOT EDIT"
|
||||
|
||||
|
||||
CM_ "Imported file _bosch_2018.dbc starts here"
|
||||
VERSION ""
|
||||
|
||||
|
||||
NS_ :
|
||||
NS_DESC_
|
||||
CM_
|
||||
BA_DEF_
|
||||
BA_
|
||||
VAL_
|
||||
CAT_DEF_
|
||||
CAT_
|
||||
FILTER
|
||||
BA_DEF_DEF_
|
||||
EV_DATA_
|
||||
ENVVAR_DATA_
|
||||
SGTYPE_
|
||||
SGTYPE_VAL_
|
||||
BA_DEF_SGTYPE_
|
||||
BA_SGTYPE_
|
||||
SIG_TYPE_REF_
|
||||
VAL_TABLE_
|
||||
SIG_GROUP_
|
||||
SIG_VALTYPE_
|
||||
SIGTYPE_VALTYPE_
|
||||
BO_TX_BU_
|
||||
BA_DEF_REL_
|
||||
BA_REL_
|
||||
BA_DEF_DEF_REL_
|
||||
BU_SG_REL_
|
||||
BU_EV_REL_
|
||||
BU_BO_REL_
|
||||
SG_MUL_VAL_
|
||||
|
||||
BU_: EBCM EON CAM RADAR PCM EPS VSA SCM BDY XXX EPB
|
||||
|
||||
BO_ 228 STEERING_CONTROL: 5 EON
|
||||
SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS
|
||||
SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS
|
||||
SG_ SET_ME_X00_2 : 31|8@0+ (1,0) [0|0] "" EPS
|
||||
SG_ STEER_TORQUE : 7|16@0- (1,0) [-4096|4096] "" EPS
|
||||
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS
|
||||
SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" EPS
|
||||
|
||||
BO_ 232 BRAKE_HOLD: 7 XXX
|
||||
SG_ XMISSION_SPEED : 7|14@0- (1,0) [1|0] "" XXX
|
||||
SG_ COMPUTER_BRAKE : 39|16@0+ (1,0) [0|0] "" XXX
|
||||
SG_ COMPUTER_BRAKE_REQUEST : 29|1@0+ (1,0) [0|0] "" XXX
|
||||
SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" XXX
|
||||
|
||||
BO_ 304 GAS_PEDAL_2: 8 PCM
|
||||
SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON
|
||||
SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON
|
||||
SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON
|
||||
|
||||
BO_ 330 STEERING_SENSORS: 8 EPS
|
||||
SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON
|
||||
SG_ STEER_ANGLE_RATE : 23|16@0- (-1,0) [-3000|3000] "deg/s" EON
|
||||
SG_ STEER_ANGLE_OFFSET : 39|8@0- (-0.1,0) [-128|127] "deg" EON
|
||||
SG_ STEER_WHEEL_ANGLE : 47|16@0- (-0.1,0) [-500|500] "deg" EON
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON
|
||||
|
||||
BO_ 344 ENGINE_DATA: 8 PCM
|
||||
SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" EON
|
||||
SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON
|
||||
SG_ XMISSION_SPEED2 : 39|16@0+ (0.01,0) [0|250] "kph" EON
|
||||
SG_ ODOMETER : 55|8@0+ (10,0) [0|2550] "m" XXX
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON
|
||||
|
||||
BO_ 380 POWERTRAIN_DATA: 8 PCM
|
||||
SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" EON
|
||||
SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON
|
||||
SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "" EON
|
||||
SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "" EON
|
||||
SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "" EON
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON
|
||||
|
||||
BO_ 399 STEER_STATUS: 7 EPS
|
||||
SG_ STEER_TORQUE_SENSOR : 7|16@0- (1,0) [-31000|31000] "tbd" EON
|
||||
SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" 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_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" EON
|
||||
|
||||
BO_ 420 VSA_STATUS: 8 VSA
|
||||
SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON
|
||||
SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ BRAKE_HOLD_ENABLED : 45|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON
|
||||
|
||||
BO_ 450 EPB_STATUS: 8 EPB
|
||||
SG_ EPB_ACTIVE : 3|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ EPB_STATE : 29|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
|
||||
|
||||
BO_ 464 WHEEL_SPEEDS: 8 VSA
|
||||
SG_ WHEEL_SPEED_FL : 7|15@0+ (0.01,0) [0|250] "kph" EON
|
||||
SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON
|
||||
SG_ WHEEL_SPEED_RL : 25|15@0+ (0.01,0) [0|250] "kph" EON
|
||||
SG_ WHEEL_SPEED_RR : 42|15@0+ (0.01,0) [0|250] "kph" EON
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
|
||||
|
||||
BO_ 479 ACC_CONTROL: 8 EON
|
||||
SG_ SET_TO_1 : 20|5@0+ (1,0) [0|1] "" PCM
|
||||
SG_ CONTROL_ON : 23|3@0+ (1,0) [0|5] "" XXX
|
||||
SG_ RELATED_TO_GAS : 7|7@0+ (1,0) [0|69] "" XXX
|
||||
SG_ GAS_COMMAND : 0|9@0+ (1,0) [0|1] "" PCM
|
||||
SG_ GAS_BRAKE : 31|14@0- (1,0) [0|1] "" XXX
|
||||
SG_ ZEROS_BOH : 33|18@0+ (1,0) [100|100] "" XXX
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
|
||||
|
||||
BO_ 495 ACC_CONTROL_ON: 8 XXX
|
||||
SG_ SET_TO_75 : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_TO_30 : 39|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ ZEROS_BOH : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ ZEROS_BOH2 : 47|16@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_TO_FF : 15|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_TO_3 : 6|7@0+ (1,0) [0|4095] "" XXX
|
||||
SG_ CONTROL_ON : 7|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
|
||||
|
||||
BO_ 545 XXX_16: 6 SCM
|
||||
SG_ ECON_ON : 23|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DRIVE_MODE : 37|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" BDY
|
||||
SG_ CHECKSUM : 43|4@0+ (1,0) [0|15] "" BDY
|
||||
|
||||
BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA
|
||||
SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" EON
|
||||
SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" EON
|
||||
SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" EON
|
||||
SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" EON
|
||||
SG_ SET_TO_X55 : 39|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_TO_X55_2 : 47|8@0+ (1,0) [0|255] "" EON
|
||||
SG_ LONG_COUNTER : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
|
||||
|
||||
BO_ 662 SCM_BUTTONS: 4 SCM
|
||||
SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON
|
||||
SG_ CRUISE_SETTING : 3|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 27|4@0+ (1,0) [0|15] "" EON
|
||||
|
||||
BO_ 773 SEATBELT_STATUS: 7 BDY
|
||||
SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON
|
||||
|
||||
BO_ 777 CAR_SPEED: 8 PCM
|
||||
SG_ ROUGH_CAR_SPEED : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CAR_SPEED : 7|16@0+ (1,0) [0|65535] "" XXX
|
||||
SG_ ROUGH_CAR_SPEED_3 : 39|16@0+ (1,0) [0|65535] "" XXX
|
||||
SG_ ROUGH_CAR_SPEED_2 : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ LOCK_STATUS : 55|2@0+ (1,0) [0|255] "" XXX
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
|
||||
|
||||
BO_ 780 ACC_HUD: 8 ADAS
|
||||
SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY
|
||||
SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY
|
||||
SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY
|
||||
SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY
|
||||
SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY
|
||||
SG_ ZEROS_BOH : 7|24@0+ (0.002759506,0) [0|100] "m/s" BDY
|
||||
SG_ FCM_OFF : 35|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ SET_TO_1 : 36|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ HUD_DISTANCE : 47|2@0+ (1,0) [0|3] "" BDY
|
||||
SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY
|
||||
SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ ACC_ON : 52|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ BOH_6 : 51|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ SET_TO_X3 : 55|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
|
||||
|
||||
BO_ 804 CRUISE: 8 PCM
|
||||
SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON
|
||||
|
||||
BO_ 806 SCM_FEEDBACK: 8 SCM
|
||||
SG_ DRIVERS_DOOR_OPEN : 17|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ MAIN_ON : 28|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ RIGHT_BLINKER : 27|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ LEFT_BLINKER : 26|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ CMBS_STATES : 22|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
|
||||
|
||||
BO_ 829 LKAS_HUD: 5 ADAS
|
||||
SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY
|
||||
SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY
|
||||
SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY
|
||||
SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY
|
||||
SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY
|
||||
SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY
|
||||
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY
|
||||
SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY
|
||||
|
||||
BO_ 862 CAMERA_MESSAGES: 8 CAM
|
||||
SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY
|
||||
SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ ZEROS_BOH_2 : 51|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
|
||||
|
||||
BO_ 884 STALK_STATUS: 8 XXX
|
||||
SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ WIPER_SWITCH : 53|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
|
||||
|
||||
BO_ 891 STALK_STATUS_2: 8 XXX
|
||||
SG_ WIPERS : 17|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ LOW_BEAMS : 35|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ HIGH_BEAMS : 34|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ PARK_LIGHTS : 36|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
|
||||
|
||||
VAL_ 399 STEER_STATUS 6 "tmp_fault" 5 "fault_1" 4 "no_torque_alert_2" 3 "low_speed_lockout" 2 "no_torque_alert_1" 0 "normal" ;
|
||||
CM_ "honda_crv_hybrid_2019_can.dbc starts here"
|
||||
|
||||
|
||||
BO_ 419 GEARBOX: 8 PCM
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
|
||||
SG_ GEAR_SHIFTER : 29|6@0+ (1,0) [0|63] "" EON
|
||||
SG_ GEAR : 7|8@0+ (1,0) [0|255] "" EON
|
||||
|
||||
BO_ 432 STANDSTILL: 7 VSA
|
||||
SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 51|4@0+ (1,0) [0|15] "" EON
|
||||
|
||||
BO_ 927 RADAR_HUD: 8 RADAR
|
||||
SG_ ZEROS_BOH : 7|10@0+ (1,0) [0|127] "" BDY
|
||||
SG_ CMBS_OFF : 12|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ ZEROS_BOH3 : 31|32@0+ (1,0) [0|4294967295] "" XXX
|
||||
SG_ RESUME_INSTRUCTION : 21|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ SET_TO_1 : 13|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ ZEROS_BOH2 : 11|4@0+ (1,0) [0|1] "" XXX
|
||||
SG_ APPLY_BRAKES_FOR_CANC : 23|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ ACC_ALERTS : 20|5@0+ (1,0) [0|1] "" BDY
|
||||
SG_ SET_TO_0 : 22|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
|
||||
|
||||
BO_ 1302 ODOMETER: 8 XXX
|
||||
SG_ ODOMETER : 7|24@0+ (1,0) [0|16777215] "km" EON
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
|
||||
|
||||
CM_ SG_ 344 DISTANCE_COUNTER "";
|
||||
CM_ SG_ 450 EPB_STATE "3: On, 2: Disengaging, 1: Engaging, 0: Off";
|
||||
CM_ SG_ 479 CONTROL_ON "Set to 5 when car is being controlled";
|
||||
CM_ SG_ 479 RELATED_TO_GAS "bits 7, 3, and 1 set to 1 when gas not applied";
|
||||
CM_ SG_ 479 GAS_BRAKE "Signed value, negative when braking and positive when applying gas";
|
||||
|
||||
VAL_ 419 GEAR_SHIFTER 32 "D" 8 "R" 4 "P" ;
|
||||
VAL_ 545 ECON_ON_2 0 "off" 3 "on" ;
|
||||
VAL_ 662 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ;
|
||||
VAL_ 662 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ;
|
||||
VAL_ 806 CMBS_BUTTON 3 "pressed" 0 "released" ;
|
||||
VAL_ 891 WIPERS 4 "High" 2 "Low" 0 "Off" ;
|
||||
VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ;
|
||||
|
||||
CM_ "CHFFR_METRIC 330 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0";
|
|
@ -6,15 +6,15 @@ 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 : 45|2@0+ (1,0) [0|3] "" INTERCEPTOR
|
||||
SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" 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|8@0+ (1,0) [0|255] "" EON
|
||||
SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" 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" ;
|
||||
|
||||
|
|
|
@ -6,15 +6,15 @@ 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 : 45|2@0+ (1,0) [0|3] "" INTERCEPTOR
|
||||
SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" 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|8@0+ (1,0) [0|255] "" EON
|
||||
SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" 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" ;
|
||||
|
||||
|
|
|
@ -6,15 +6,15 @@ 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 : 45|2@0+ (1,0) [0|3] "" INTERCEPTOR
|
||||
SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" 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|8@0+ (1,0) [0|255] "" EON
|
||||
SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" 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" ;
|
||||
|
||||
|
|
|
@ -6,15 +6,15 @@ 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 : 45|2@0+ (1,0) [0|3] "" INTERCEPTOR
|
||||
SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" 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|8@0+ (1,0) [0|255] "" EON
|
||||
SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" 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" ;
|
||||
|
||||
|
|
|
@ -6,15 +6,15 @@ 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 : 45|2@0+ (1,0) [0|3] "" INTERCEPTOR
|
||||
SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" 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|8@0+ (1,0) [0|255] "" EON
|
||||
SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" 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" ;
|
||||
|
||||
|
|
|
@ -18,13 +18,15 @@ CM BO_ STEERING_IPAS_COMMA "Copy of msg 614 so we can do angle control while the
|
|||
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_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" 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|8@0+ (1,0) [0|255] "" EON
|
||||
SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" 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" ;
|
||||
|
||||
|
|
|
@ -0,0 +1,331 @@
|
|||
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 : 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.0244140625,0) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.0244140625,0) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.0244140625,-11.962890625) [0|1] "" EON
|
||||
SG_ STATE : 39|8@0+ (1,0) [0|255] "" EON
|
||||
SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" 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 _toyota_2017.dbc starts here"
|
||||
VERSION ""
|
||||
|
||||
|
||||
NS_ :
|
||||
NS_DESC_
|
||||
CM_
|
||||
BA_DEF_
|
||||
BA_
|
||||
VAL_
|
||||
CAT_DEF_
|
||||
CAT_
|
||||
FILTER
|
||||
BA_DEF_DEF_
|
||||
EV_DATA_
|
||||
ENVVAR_DATA_
|
||||
SGTYPE_
|
||||
SGTYPE_VAL_
|
||||
BA_DEF_SGTYPE_
|
||||
BA_SGTYPE_
|
||||
SIG_TYPE_REF_
|
||||
VAL_TABLE_
|
||||
SIG_GROUP_
|
||||
SIG_VALTYPE_
|
||||
SIGTYPE_VALTYPE_
|
||||
BO_TX_BU_
|
||||
BA_DEF_REL_
|
||||
BA_REL_
|
||||
BA_DEF_DEF_REL_
|
||||
BU_SG_REL_
|
||||
BU_EV_REL_
|
||||
BU_BO_REL_
|
||||
SG_MUL_VAL_
|
||||
|
||||
BS_:
|
||||
|
||||
BU_: XXX DSU HCU EPS IPAS
|
||||
|
||||
BO_ 36 KINEMATICS: 8 XXX
|
||||
SG_ ACCEL_Y : 33|10@0+ (1,-512) [0|65535] "" XXX
|
||||
SG_ YAW_RATE : 1|10@0+ (1,-512) [0|65535] "" XXX
|
||||
SG_ STEERING_TORQUE : 17|10@0+ (1,-512) [0|65535] "" XXX
|
||||
|
||||
BO_ 37 STEER_ANGLE_SENSOR: 8 XXX
|
||||
SG_ STEER_ANGLE : 3|12@0- (1.5,0) [-500|500] "deg" XXX
|
||||
SG_ STEER_FRACTION : 39|4@0- (0.1,0) [-0.7|0.7] "deg" XXX
|
||||
SG_ STEER_RATE : 35|12@0- (1,0) [-2000|2000] "deg/s" XXX
|
||||
|
||||
BO_ 166 BRAKE: 8 XXX
|
||||
SG_ BRAKE_AMOUNT : 7|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ BRAKE_PEDAL : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 170 WHEEL_SPEEDS: 8 XXX
|
||||
SG_ WHEEL_SPEED_FR : 7|16@0+ (0.01,-67.67) [0|250] "kph" XXX
|
||||
SG_ WHEEL_SPEED_FL : 23|16@0+ (0.01,-67.67) [0|250] "kph" XXX
|
||||
SG_ WHEEL_SPEED_RR : 39|16@0+ (0.01,-67.67) [0|250] "kph" XXX
|
||||
SG_ WHEEL_SPEED_RL : 55|16@0+ (0.01,-67.67) [0|250] "kph" XXX
|
||||
|
||||
BO_ 180 SPEED: 8 XXX
|
||||
SG_ ENCODER : 39|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SPEED : 47|16@0+ (0.01,0) [0|250] "kph" XXX
|
||||
|
||||
BO_ 466 PCM_CRUISE: 8 XXX
|
||||
SG_ GAS_RELEASED : 4|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ CRUISE_ACTIVE : 5|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ STANDSTILL_ON : 12|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ ACCEL_NET : 23|16@0- (0.001,0) [-20|20] "m/s2" XXX
|
||||
SG_ CRUISE_STATE : 55|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 467 PCM_CRUISE_2: 8 XXX
|
||||
SG_ MAIN_ON : 15|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ LOW_SPEED_LOCKOUT : 14|2@0+ (1,0) [0|3] "kph" XXX
|
||||
SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "kph" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 552 ACCELEROMETER: 8 XXX
|
||||
SG_ ACCEL_Z : 22|15@0- (1,0) [0|32767] "" XXX
|
||||
SG_ ACCEL_X : 6|15@0- (0.001,0) [-20|20] "m/s2" XXX
|
||||
|
||||
BO_ 560 BRAKE_MODULE2: 7 XXX
|
||||
SG_ BRAKE_PRESSED : 26|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 614 STEERING_IPAS: 8 IPAS
|
||||
SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX
|
||||
SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00 : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 643 PRE_COLLISION: 8 XXX
|
||||
|
||||
BO_ 740 STEERING_LKA: 5 XXX
|
||||
SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ STEER_REQUEST : 0|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ COUNTER : 6|6@0+ (1,0) [0|63] "" XXX
|
||||
SG_ SET_ME_1 : 7|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ STEER_TORQUE_CMD : 15|16@0- (1,0) [0|65535] "" XXX
|
||||
SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 742 LEAD_INFO: 8 DSU
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" HCU
|
||||
SG_ LEAD_REL_SPEED : 23|12@0- (0.025,0) [-100|100] "m/s" HCU
|
||||
SG_ LEAD_LONG_DIST : 7|13@0+ (0.05,0) [0|300] "m" HCU
|
||||
|
||||
BO_ 835 ACC_CONTROL: 8 DSU
|
||||
SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU
|
||||
SG_ SET_ME_X63 : 23|8@0+ (1,0) [0|255] "" HCU
|
||||
SG_ SET_ME_1 : 30|1@0+ (1,0) [0|1] "" HCU
|
||||
SG_ RELEASE_STANDSTILL : 31|1@0+ (1,0) [0|1] "" HCU
|
||||
SG_ CANCEL_REQ : 24|1@0+ (1,0) [0|1] "" HCU
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 921 PCM_CRUISE_SM: 8 XXX
|
||||
SG_ MAIN_ON : 4|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ CRUISE_CONTROL_STATE : 11|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ DISTANCE_LINES : 14|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ UI_SET_SPEED : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 951 ESP_CONTROL: 8 ESP
|
||||
SG_ TC_DISABLED : 13|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 1041 ACC_HUD: 8 DSU
|
||||
SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ SET_ME_X20 : 15|8@0+ (1,0) [0|1] "" XXX
|
||||
SG_ SET_ME_X10 : 39|8@0+ (1,0) [0|1] "" XXX
|
||||
SG_ SET_ME_X80 : 55|8@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 1042 LKAS_HUD: 8 XXX
|
||||
SG_ BARRIERS : 1|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ RIGHT_LINE : 3|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ LEFT_LINE : 5|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ SET_ME_X01 : 7|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ SET_ME_X01_2 : 11|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ LDA_ALERT : 9|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ TWO_BEEPS : 12|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ ADJUSTING_CAMERA : 13|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ LDA_MALFUNCTION : 15|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ REPEATED_BEEPS : 32|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ SET_ME_X0C : 23|8@0+ (1,0) [0|1] "" XXX
|
||||
SG_ SET_ME_X2C : 47|8@0+ (1,0) [0|1] "" XXX
|
||||
SG_ SET_ME_X38 : 55|8@0+ (1,0) [0|1] "" XXX
|
||||
SG_ SET_ME_X02 : 63|8@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 1553 UI_SEETING: 8 XXX
|
||||
SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX
|
||||
|
||||
BO_ 1556 STEERING_LEVERS: 8 XXX
|
||||
SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX
|
||||
|
||||
BO_ 1568 SEATS_DOORS: 8 XXX
|
||||
SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DOOR_OPEN_RR : 43|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DOOR_OPEN_FR : 44|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 1570 LIGHT_STALK: 8 SCM
|
||||
SG_ AUTO_HIGH_BEAM : 37|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 1161 RSA1: 8 FCM
|
||||
SG_ TSGN1 : 7|8@0+ (1,0) [0|0] "" XXX
|
||||
SG_ TSGNGRY1 : 12|3@0+ (1,0) [0|0] "" XXX
|
||||
SG_ TSGNHLT1 : 9|2@0+ (1,0) [0|0] "" XXX
|
||||
SG_ SPDVAL1 : 23|8@0+ (1,0) [0|0] "kph" XXX
|
||||
SG_ SPLSGN1 : 31|4@0+ (1,0) [0|0] "" XXX
|
||||
SG_ SPLSGN2 : 27|4@0+ (1,0) [0|0] "" XXX
|
||||
SG_ TSGN2 : 39|8@0+ (1,0) [0|0] "" XXX
|
||||
SG_ TSGNGRY2 : 44|3@0+ (1,0) [0|0] "" XXX
|
||||
SG_ TSGNHLT2 : 41|2@0+ (1,0) [0|0] "" XXX
|
||||
SG_ SPDVAL2 : 55|8@0+ (1,0) [0|0] "" XXX
|
||||
SG_ BZRRQ_P : 63|2@0+ (1,0) [0|0] "" XXX
|
||||
SG_ BZRRQ_A : 61|2@0+ (1,0) [0|0] "" XXX
|
||||
SG_ SYNCID1 : 59|4@0+ (1,0) [0|0] "" XXX
|
||||
|
||||
BO_ 1162 RSA2: 8 FCM
|
||||
SG_ TSGN3 : 7|8@0+ (1,0) [0|0] "" XXX
|
||||
SG_ TSGNGRY3 : 12|3@0+ (1,0) [0|0] "" XXX
|
||||
SG_ TSGNHLT3 : 9|2@0+ (1,0) [0|0] "" XXX
|
||||
SG_ SPLSGN3 : 31|4@0+ (1,0) [0|0] "" XXX
|
||||
SG_ SPLSGN4 : 27|4@0+ (1,0) [0|0] "" XXX
|
||||
SG_ TSGN4 : 39|8@0+ (1,0) [0|0] "" XXX
|
||||
SG_ TSGNGRY4 : 44|3@0+ (1,0) [0|0] "" XXX
|
||||
SG_ TSGNHLT4 : 41|2@0+ (1,0) [0|0] "" XXX
|
||||
SG_ DPSGNREQ : 54|1@0+ (1,0) [0|0] "" XXX
|
||||
SG_ SGNNUMP : 53|3@0+ (1,0) [0|0] "" XXX
|
||||
SG_ SGNNUMA : 50|3@0+ (1,0) [0|0] "" XXX
|
||||
SG_ SPDUNT : 63|2@0+ (1,0) [0|0] "" XXX
|
||||
SG_ TSRWMSG : 61|2@0+ (1,0) [0|0] "" XXX
|
||||
SG_ SYNCID2 : 59|4@0+ (1,0) [0|0] "" XXX
|
||||
|
||||
BO_ 1163 RSA3: 8 FCM
|
||||
SG_ TSREQPD : 7|1@0+ (1,0) [0|0] "" XXX
|
||||
SG_ TSRMSW : 6|1@0+ (1,0) [0|0] "" XXX
|
||||
SG_ OTSGNNTM : 5|2@0+ (1,0) [0|0] "" XXX
|
||||
SG_ NTLVLSPD : 3|2@0+ (1,0) [0|0] "" XXX
|
||||
SG_ OVSPNTM : 1|2@0+ (1,0) [0|0] "" XXX
|
||||
SG_ OVSPVALL : 11|4@0+ (1,-5) [0|0] "" XXX
|
||||
SG_ OVSPVALM : 19|4@0+ (1,-5) [0|0] "" XXX
|
||||
SG_ OVSPVALH : 27|4@0+ (1,-5) [0|0] "" XXX
|
||||
SG_ TSRSPU : 33|2@0+ (1,0) [0|0] "" XXX
|
||||
|
||||
CM_ SG_ 36 ACCEL_Y "unit is tbd";
|
||||
CM_ SG_ 36 YAW_RATE "verify";
|
||||
CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd";
|
||||
CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set";
|
||||
CM_ SG_ 37 STEER_RATE "factor is tbd";
|
||||
CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors";
|
||||
CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isnt perfect";
|
||||
CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph";
|
||||
CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?";
|
||||
CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque";
|
||||
CM_ SG_ 608 STEER_OVERRIDE "set when driver torque exceeds a certain value";
|
||||
CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active";
|
||||
CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit";
|
||||
CM_ SG_ 951 BRAKE_LIGHTS_ACC "brake lights when ACC commands decel";
|
||||
CM_ SG_ 1042 SET_ME_1 "unclear what this is, but it's always 1 in drive traces";
|
||||
CM_ SG_ 1042 REPEATED_BEEPS "recommended for fcw and other important alerts";
|
||||
CM_ SG_ 1161 SPDVAL1 "Numbers 0-199 is displayed, 200-254 displays circle without number and 255 is for no limit.";
|
||||
CM_ SG_ 1161 SYNCID1 "counter from 1 to f at 1 Hz";
|
||||
CM_ SG_ 1161 SPDVAL2 "conditional speed value 70"
|
||||
CM_ SG_ 1162 SGNNUMP "1 if SPDVAL1 is set, otherwise 0";
|
||||
CM_ SG_ 1162 SYNCID2 "counter from 1 to f at 1 Hz";
|
||||
CM_ SG_ 1163 TSREQPD "always 1";
|
||||
CM_ SG_ 1163 TSRMSW "always 1";
|
||||
CM_ SG_ 1163 OTSGNNTM "always 3";
|
||||
CM_ SG_ 1163 NTLVLSPD "always 3";
|
||||
CM_ SG_ 1163 OVSPNTM "always 3";
|
||||
CM_ SG_ 1163 OVSPVALL "-5 at start then 2 after 2 seconds";
|
||||
CM_ SG_ 1163 OVSPVALM "-5 at start then 5 after 2 seconds";
|
||||
CM_ SG_ 1163 OVSPVALH "-5 at start then 10 after 2 seconds";
|
||||
CM_ SG_ 1163 TSRSPU "always 1";
|
||||
|
||||
VAL_ 466 CRUISE_STATE 8 "active" 7 "standstill" 1 "off";
|
||||
VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok";
|
||||
VAL_ 614 STATE 3 "enabled" 1 "disabled";
|
||||
VAL_ 614 DIRECTION_CMD 3 "right" 2 "center" 1 "left";
|
||||
VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted";
|
||||
VAL_ 1042 LDA_ALERT 3 "hold with continuous beep" 2 "LDA unavailable" 1 "hold" 0 "none";
|
||||
VAL_ 1042 BARRIERS 3 "both" 2 "right" 1 "left" 0 "none";
|
||||
VAL_ 1042 RIGHT_LINE 3 "orange" 2 "double" 1 "solid" 0 "none";
|
||||
VAL_ 1042 LEFT_LINE 3 "orange" 2 "double" 1 "solid" 0 "none";
|
||||
VAL_ 1553 UNITS 1 "km" 2 "miles";
|
||||
VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left";
|
||||
VAL_ 1161 TSGN1 1 "speed sign" 0 "none";
|
||||
VAL_ 1161 TSGN2 1 "speed sign" 0 "none";
|
||||
VAL_ 1161 SPLSGN2 15 "conditional blank" 5 "rain" 0 "none";
|
||||
VAL_ 1162 TSGN3 0 "none" 1 "speed sign" 2 "0 unlimited" 7 "unlimited" 16 "highway" 17 "no highway" 18 "motorway" 19 "no motorway" 20 "in city" 21 "outside city" 22 "pedestrian area" 23 "no pedestrian area" 65 "no overtaking left" 66 "no overtaking right" 67 "overtaking allowed again" 65 "no overtake" 129 "no entry";
|
||||
VAL_ 1162 SPLSGN3 15 "conditional blank" 5 "rain" 0 "none";
|
||||
|
||||
|
||||
CM_ "CHFFR_METRIC 37 STEER_ANGLE STEER_ANGLE 0.36 180";
|
||||
|
||||
CM_ "lexus_is_hybrid_2017_pt.dbc starts here"
|
||||
|
||||
|
||||
|
||||
BO_ 581 GAS_PEDAL: 5 XXX
|
||||
SG_ GAS_PEDAL : 23|8@0+ (0.005,0) [0|1] "" XXX
|
||||
|
||||
BO_ 550 BRAKE_MODULE: 8 XXX
|
||||
SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|511] "" XXX
|
||||
SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|511] "" XXX
|
||||
SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 608 STEER_TORQUE_SENSOR: 8 XXX
|
||||
SG_ STEER_TORQUE_EPS : 47|16@0- (0.66,0) [-20000|20000] "" XXX
|
||||
SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX
|
||||
SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 610 EPS_STATUS: 5 EPS
|
||||
SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX
|
||||
SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 956 GEAR_PACKET: 8 XXX
|
||||
SG_ GEAR : 13|6@0+ (1,0) [0|63] "" XXX
|
||||
|
||||
BO_ 1009 PCM_CRUISE_ISH: 8 XXX
|
||||
SG_ MAIN_ON : 13|1@0+ (1,0) [0|3] "" XXX
|
||||
SG_ CRUISE_STATE : 10|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "mph" XXX
|
||||
|
||||
BO_ 1599 LIGHT_STALK_ISH: 8 SCM
|
||||
SG_ AUTO_HIGH_BEAM : 19|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
CM_ SG_ 550 BRAKE_PRESSURE "seems prop to pedal force";
|
||||
CM_ SG_ 550 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8";
|
||||
CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others";
|
||||
CM_ SG_ 1009 SET_SPEED "units seem to be whatever the car is set to";
|
||||
VAL_ 956 GEAR 0 "D" 1 "S" 8 "N" 16 "R" 32 "P";
|
||||
VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled";
|
||||
VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby";
|
|
@ -18,13 +18,15 @@ CM BO_ STEERING_IPAS_COMMA "Copy of msg 614 so we can do angle control while the
|
|||
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_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" 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|8@0+ (1,0) [0|255] "" EON
|
||||
SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" 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" ;
|
||||
|
||||
|
|
|
@ -0,0 +1,694 @@
|
|||
VERSION ""
|
||||
|
||||
|
||||
NS_ :
|
||||
NS_DESC_
|
||||
CM_
|
||||
BA_DEF_
|
||||
BA_
|
||||
VAL_
|
||||
CAT_DEF_
|
||||
CAT_
|
||||
FILTER
|
||||
BA_DEF_DEF_
|
||||
EV_DATA_
|
||||
ENVVAR_DATA_
|
||||
SGTYPE_
|
||||
SGTYPE_VAL_
|
||||
BA_DEF_SGTYPE_
|
||||
BA_SGTYPE_
|
||||
SIG_TYPE_REF_
|
||||
VAL_TABLE_
|
||||
SIG_GROUP_
|
||||
SIG_VALTYPE_
|
||||
SIGTYPE_VALTYPE_
|
||||
BO_TX_BU_
|
||||
BA_DEF_REL_
|
||||
BA_REL_
|
||||
BA_DEF_DEF_REL_
|
||||
BU_SG_REL_
|
||||
BU_EV_REL_
|
||||
BU_BO_REL_
|
||||
SG_MUL_VAL_
|
||||
|
||||
BS_:
|
||||
|
||||
BU_: XXX
|
||||
|
||||
|
||||
BO_ 117 STEER_RELATED: 8 XXX
|
||||
SG_ CTR : 7|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_1 : 48|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NEW_SIGNAL_2 : 49|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NEW_SIGNAL_3 : 55|1@0+ (1,0) [0|63] "" XXX
|
||||
SG_ NEW_SIGNAL_4 : 54|4@0+ (1,0) [0|31] "" XXX
|
||||
SG_ NEW_SIGNAL_5 : 50|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ STEER_TORQUE : 19|12@0+ (1,0) [0|255] "" XXX
|
||||
SG_ STEER_ANGLE_2 : 39|16@0+ (1,0) [0|131071] "" XXX
|
||||
|
||||
BO_ 118 RPM_RELATED: 8 XXX
|
||||
SG_ CTR : 7|8@0+ (1,0) [0|127] "" XXX
|
||||
SG_ NEW_SIGNAL_2 : 19|12@0+ (1,0) [0|4095] "" XXX
|
||||
|
||||
BO_ 514 ENGINE_DATA: 8 XXX
|
||||
SG_ RPM : 7|16@0+ (1,0) [0|65535] "" XXX
|
||||
SG_ CHKSUM : 56|8@1+ (1,0) [0|127] "" XXX
|
||||
SG_ SPEED : 23|16@0+ (0.01,0) [0|32767] "KPH" XXX
|
||||
SG_ PEDAL_GAS : 39|12@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 357 PEDALS: 8 XXX
|
||||
SG_ NEW_SIGNAL_6 : 31|4@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NEW_SIGNAL_7 : 8|3@1+ (1,0) [0|7] "" XXX
|
||||
SG_ ACC_ACTIVE : 3|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ ACC_OFF : 2|1@1+ (1,0) [0|15] "" XXX
|
||||
SG_ CHKSUM : 63|8@0+ (1,0) [0|15] "" XXX
|
||||
SG_ STANDSTILL : 26|1@0+ (1,0) [0|16777215] "" XXX
|
||||
SG_ NEW_SIGNAL_3 : 23|8@0+ (1,0) [0|3] "" XXX
|
||||
SG_ GEAR : 48|5@1+ (1,0) [0|255] "" XXX
|
||||
SG_ BRAKE_ON : 4|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NO_BRAKE : 6|1@0+ (1,0) [0|7] "" XXX
|
||||
SG_ BRAKE_ON_2 : 7|1@1+ (1,0) [0|255] "" XXX
|
||||
SG_ NO_BRAKE_2 : 15|1@0+ (1,0) [0|7] "" XXX
|
||||
|
||||
BO_ 533 WHEEL_SPEEDS: 8 XXX
|
||||
SG_ FL : 7|16@0+ (0.01,-100) [0|16383] "" XXX
|
||||
SG_ RL : 39|16@0+ (0.01,-100) [0|15] "" XXX
|
||||
SG_ RR : 55|16@0+ (0.01,-100) [0|65535] "" XXX
|
||||
SG_ FR : 23|16@0+ (0.01,-100) [0|65535] "" XXX
|
||||
|
||||
BO_ 134 STEER2: 8 XXX
|
||||
SG_ NEW_SIGNAL_2 : 48|3@1+ (1,0) [0|7] "" XXX
|
||||
SG_ CTR : 22|4@0+ (1,0) [0|7] "" XXX
|
||||
SG_ NEW_SIGNAL_4 : 23|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NEW_SIGNAL_5 : 18|3@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NEW_SIGNAL_7 : 24|3@1+ (1,0) [0|7] "" XXX
|
||||
SG_ CTR_2 : 28|3@1+ (1,0) [0|7] "" XXX
|
||||
SG_ NEW_SIGNAL_1 : 63|2@0+ (1,0) [0|255] "" XXX
|
||||
SG_ STEER_ANGLE : 7|16@0+ (0.1,-1600) [-500|500] "deg" XXX
|
||||
SG_ STEER_ANGLE_ROUGH : 39|8@0- (1,0) [0|15] "" XXX
|
||||
|
||||
BO_ 576 STEER_TORQUE: 8 XXX
|
||||
SG_ NEW_SIGNAL_2 : 39|8@0+ (1,0) [0|127] "" XXX
|
||||
SG_ NEW_SIGNAL_1 : 20|4@1+ (1,0) [0|255] "" XXX
|
||||
SG_ STEER_TORQUE_SENSOR : 7|16@0+ (0.5,-15000) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_3 : 47|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ STEER_TORQUE_MOTOR : 46|20@0- (0.01,0) [-3000|3000] "deg/s" XXX
|
||||
|
||||
BO_ 577 STEER_RATE: 8 XXX
|
||||
SG_ STEER_ANGLE_RATE : 23|16@0+ (0.25,-8192) [0|1] "deg/s" XXX
|
||||
SG_ CTR : 7|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ LKAS_REQUEST : 3|12@0+ (1,-2048) [0|15] "" XXX
|
||||
SG_ LKAS_EFFECTIVE : 39|12@0+ (1,-2048) [0|255] "" XXX
|
||||
SG_ HANDS_OFF_5_SECONDS : 51|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ LKAS_BLOCK : 50|1@1+ (1,0) [0|3] "" XXX
|
||||
SG_ LKAS_TRACK_STATE : 52|1@0+ (1,0) [0|3] "" XXX
|
||||
SG_ CHKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 582 CAM_LANEMAYBE: 8 XXX
|
||||
SG_ NEW_SIGNAL_4 : 40|8@1+ (1,0) [0|127] "" XXX
|
||||
SG_ NEW_SIGNAL_1 : 31|16@0- (1,0) [0|65535] "" XXX
|
||||
SG_ NEW_SIGNAL_2 : 55|16@0+ (1,0) [0|65535] "" XXX
|
||||
SG_ CTR : 7|2@0+ (1,0) [0|3] "" XXX
|
||||
|
||||
BO_ 541 CAM_EMPTY: 8 XXX
|
||||
|
||||
BO_ 605 CAM_PEDESTRIAN: 8 XXX
|
||||
SG_ CTR : 17|4@0+ (1,0) [0|255] "" XXX
|
||||
SG_ AEB_NOT_ENGAGED : 13|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ PED_WARNING : 9|1@0+ (1,0) [0|255] "" XXX
|
||||
SG_ PED_BRAKE : 3|3@0+ (1,0) [0|7] "" XXX
|
||||
SG_ RST_CTR : 23|6@0+ (1,0) [0|63] "" XXX
|
||||
SG_ S1 : 29|4@0+ (1,0) [0|31] "" XXX
|
||||
|
||||
BO_ 578 CAM_LANETRACK: 8 XXX
|
||||
SG_ CHKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ ZERO : 53|6@0+ (1,0) [0|63] "" XXX
|
||||
SG_ CTR : 7|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ LINE2 : 9|10@0+ (1,-686) [0|255] "" XXX
|
||||
SG_ LANE_CURVE : 31|8@0+ (1,-127) [0|255] "" XXX
|
||||
SG_ SIG1 : 39|8@0+ (1,-128) [0|255] "" XXX
|
||||
SG_ SIG2 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SIG3 : 55|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ LINE1 : 3|10@0+ (1,-686) [0|1] "" XXX
|
||||
|
||||
BO_ 579 CAM_LKAS: 8 XXX
|
||||
SG_ LKAS_REQUEST : 3|12@0+ (1,-2048) [0|2048] "" XXX
|
||||
SG_ CTR : 7|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ ERR_BIT_1 : 16|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ CHKSUM : 63|8@0+ (1,0) [0|15] "" XXX
|
||||
SG_ LINE_NOT_VISIBLE : 19|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ BIT_1 : 29|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ BIT_2 : 33|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ ERR_BIT_2 : 30|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 580 CAM_DISTANCE: 8 XXX
|
||||
SG_ S1 : 0|8@1+ (1,0) [0|127] "" XXX
|
||||
SG_ S2 : 15|8@0+ (1,0) [0|1] "" XXX
|
||||
SG_ S3 : 16|8@1+ (1,0) [0|3] "" XXX
|
||||
SG_ S4 : 24|8@1+ (1,0) [0|31] "" XXX
|
||||
SG_ S5 : 32|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ DISTANCE : 47|8@0+ (1,0) [0|65535] "" XXX
|
||||
SG_ S6 : 55|16@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 581 CAM_IDK3: 8 XXX
|
||||
SG_ S1 : 0|8@1+ (1,0) [0|15] "" XXX
|
||||
SG_ S2 : 8|6@1+ (1,0) [0|255] "" XXX
|
||||
SG_ S3 : 15|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ S4 : 16|8@1+ (1,0) [0|15] "" XXX
|
||||
SG_ S5 : 24|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ S6 : 32|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ S7 : 40|8@1+ (1,0) [0|3] "" XXX
|
||||
SG_ S8 : 48|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ S9 : 56|8@1+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 863 CAM_STATUS: 8 XXX
|
||||
SG_ NEW_SIGNAL_1 : 32|1@0+ (1,0) [0|32767] "" XXX
|
||||
SG_ NEW_SIGNAL_5 : 4|2@0+ (1,0) [0|32767] "" XXX
|
||||
SG_ NEW_SIGNAL_4 : 15|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ STOP_SIGN : 31|4@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NEW_SIGNAL_3 : 55|1@0+ (1,0) [0|127] "" XXX
|
||||
SG_ NEW_SIGNAL_6 : 0|3@1+ (1,0) [0|7] "" XXX
|
||||
SG_ FORWARD_COLLISION : 40|8@1+ (1,0) [0|7] "" XXX
|
||||
|
||||
BO_ 1157 CAM_Empty2: 8 XXX
|
||||
|
||||
BO_ 1160 CAM_Empty3: 8 XXX
|
||||
SG_ NEW_SIGNAL_1 : 47|24@0+ (1,0) [0|16777215] "" XXX
|
||||
|
||||
BO_ 1088 CAM_LANEINFO: 8 XXX
|
||||
SG_ BIT3 : 62|1@0+ (1,0) [0|3] "" XXX
|
||||
SG_ HANDS_ON_STEER_WARN_2 : 59|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ HANDS_ON_STEER_WARN : 56|1@0+ (1,0) [0|3] "" XXX
|
||||
SG_ S1_NOT : 54|1@0+ (1,0) [0|31] "" XXX
|
||||
SG_ S1 : 52|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ HANDS_WARN_3_BITS : 51|3@0+ (1,0) [0|7] "" XXX
|
||||
SG_ ERR_BIT : 40|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NO_ERR_BIT : 14|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ BIT2 : 13|1@0+ (1,0) [0|15] "" XXX
|
||||
SG_ LANE_LINES : 10|3@0+ (1,0) [0|3] "" XXX
|
||||
SG_ BIT1 : 6|1@0+ (1,0) [0|65535] "" XXX
|
||||
SG_ LINE_NOT_VISIBLE : 1|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ LINE_VISIBLE : 0|1@0+ (1,0) [0|3] "" XXX
|
||||
|
||||
BO_ 1479 NEW_MSG_470: 8 XXX
|
||||
|
||||
BO_ 1456 NEW_MSG_300: 8 XXX
|
||||
|
||||
BO_ 1446 NEW_MSG_a600: 8 XXX
|
||||
|
||||
BO_ 1416 MSG_18: 8 XXX
|
||||
|
||||
BO_ 1086 DOORS: 8 XXX
|
||||
SG_ DOOR_OPEN : 30|1@0+ (1,0) [0|255] "" XXX
|
||||
SG_ LEFTGATE : 32|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NEW_SIGNAL_3 : 53|1@0+ (1,0) [0|255] "" XXX
|
||||
SG_ KEYFOB_HORN : 2|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ KEYFOB_LOCK : 3|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ KEYFOB_UNLOCK : 4|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ CTR1 : 8|4@1+ (1,0) [0|3] "" XXX
|
||||
SG_ CTR2 : 16|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ BR : 34|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ BL : 35|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ FR : 36|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ FL : 37|1@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 977 TWO_STATES: 8 XXX
|
||||
SG_ NEW_SIGNAL_1 : 50|1@1+ (1,0) [0|7] "" XXX
|
||||
SG_ NEW_SIGNAL_2 : 56|4@1+ (1,0) [0|7] "" XXX
|
||||
SG_ NEW_SIGNAL_3 : 28|1@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_4 : 24|4@1+ (1,0) [0|3] "" XXX
|
||||
SG_ NEW_SIGNAL_5 : 39|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NEW_SIGNAL_6 : 36|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NEW_SIGNAL_7 : 47|8@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NEW_SIGNAL_8 : 51|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 1085 MSG_12: 8 XXX
|
||||
SG_ NEW_SIGNAL_3 : 36|1@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_1 : 16|8@1+ (1,0) [0|15] "" XXX
|
||||
SG_ NEW_SIGNAL_2 : 48|8@1+ (1,0) [0|65535] "" XXX
|
||||
SG_ NEW_SIGNAL_4 : 31|1@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_5 : 24|1@0+ (1,0) [0|127] "" XXX
|
||||
SG_ NEW_SIGNAL_6 : 40|3@1+ (1,0) [0|7] "" XXX
|
||||
|
||||
BO_ 159 MSG_11: 8 XXX
|
||||
SG_ NEW_SIGNAL_1 : 50|4@1+ (1,0) [0|15] "" XXX
|
||||
|
||||
BO_ 1278 NEW_MSG_3: 8 XXX
|
||||
SG_ NEW_SIGNAL_2 : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_3 : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_4 : 39|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_5 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_6 : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_7 : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ MILAGE_MAYBE : 7|16@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 1277 NEW_MSG_10: 8 XXX
|
||||
SG_ NEW_SIGNAL_3 : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_2 : 15|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ counter : 7|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 1275 2017_5: 8 XXX
|
||||
SG_ counter : 4|5@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 1274 NEW_MSG_12: 8 XXX
|
||||
SG_ NEW_SIGNAL_1 : 24|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ CTR : 55|4@0+ (1,0) [0|63] "" XXX
|
||||
SG_ NEW_SIGNAL_2 : 35|1@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_3 : 32|3@1+ (1,0) [0|3] "" XXX
|
||||
SG_ NEW_SIGNAL_4 : 48|4@1+ (1,0) [0|7] "" XXX
|
||||
|
||||
BO_ 1180 last_byte_roughRPM: 8 XXX
|
||||
SG_ NEW_SIGNAL_1 : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 1078 HVAC: 8 XXX
|
||||
SG_ NEW_SIGNAL_1 : 2|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NEW_SIGNAL_2 : 8|1@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_3 : 23|1@0+ (1,0) [0|65535] "" XXX
|
||||
SG_ NEW_SIGNAL_4 : 56|5@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 1056 NEW_MSG_13: 8 XXX
|
||||
SG_ BIG_COUNTER_MAYBE : 55|16@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_1 : 29|6@0+ (1,0) [0|255] "" XXX
|
||||
SG_ counter_or_GEAR : 15|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ INCREASING : 7|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CTR : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ STANDSTILL : 32|1@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 1045 MOVING: 8 XXX
|
||||
SG_ NEW_SIGNAL_2 : 20|1@0+ (1,0) [0|3] "" XXX
|
||||
SG_ CTR2 : 19|4@0+ (1,0) [0|31] "" XXX
|
||||
SG_ CTR3 : 8|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ IS_MOVING : 12|1@0+ (1,0) [0|3] "" XXX
|
||||
SG_ CTR1 : 53|6@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_1 : 54|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ BRAKE : 55|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 1034 MSG_07: 8 XXX
|
||||
SG_ NEW_SIGNAL_1 : 6|3@0+ (1,0) [0|3] "" XXX
|
||||
SG_ NEW_SIGNAL_2 : 0|4@1+ (1,0) [0|3] "" XXX
|
||||
SG_ NEW_SIGNAL_3 : 15|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ NEW_SIGNAL_4 : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_5 : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_6 : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_7 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_8 : 39|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_9 : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 870 NEW_MSG_16: 8 XXX
|
||||
SG_ NEW_SIGNAL_1 : 7|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_2 : 15|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_3 : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_4 : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_5 : 39|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_6 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_7 : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 867 NEW_MSG_17: 8 XXX
|
||||
SG_ NEW_SIGNAL_1 : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_2 : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_3 : 15|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_4 : 7|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_5 : 39|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_6 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CTR : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 130 STEER: 8 XXX
|
||||
SG_ NEW_SIGNAL_5 : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_6 : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CTR : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CTR_2 : 35|4@0+ (1,0) [0|255] "" XXX
|
||||
SG_ STEER_ANGLE : 23|16@0+ (0.05,-1600) [500|-500] "deg" XXX
|
||||
|
||||
BO_ 120 NEW_MSG_18: 8 XXX
|
||||
SG_ NEW_SIGNAL_1 : 7|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_2 : 15|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_3 : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_4 : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_5 : 39|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CTR : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 304 GEAR_RELATED: 8 XXX
|
||||
SG_ NEW_SIGNAL_1 : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_2 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 865 NEW_MSG_5: 8 XXX
|
||||
SG_ SPEED_INVERSE : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_1 : 47|1@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_3 : 40|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ IS_MOVING : 43|3@0+ (1,0) [0|127] "" XXX
|
||||
SG_ NEW_SIGNAL_2 : 46|1@0+ (1,0) [0|7] "" XXX
|
||||
SG_ NEW_SIGNAL_4 : 44|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NEW_SIGNAL_7 : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_8 : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_10 : 39|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_6 : 15|3@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_5 : 7|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CTR : 56|4@1+ (1,0) [0|15] "" XXX
|
||||
|
||||
BO_ 836 NEW_MSG_19: 8 XXX
|
||||
SG_ CTR : 48|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ CTR2 : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 832 SEATBELT: 8 XXX
|
||||
SG_ NEW_SIGNAL_1 : 7|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ PASSENGER_SEATBELT : 26|1@1+ (1,0) [0|7] "" XXX
|
||||
SG_ CTR1 : 15|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ CTR2 : 23|4@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_4 : 8|4@1+ (1,0) [0|3] "" XXX
|
||||
SG_ DRIVER_SEATBELT : 27|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 866 NEW_MSG_21: 8 XXX
|
||||
SG_ NEW_SIGNAL_2 : 7|8@0+ (1,0) [0|131071] "" XXX
|
||||
SG_ NEW_SIGNAL_1 : 15|8@0+ (1,0) [0|15] "" XXX
|
||||
SG_ NEW_SIGNAL_3 : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_4 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_5 : 39|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_6 : 27|4@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_7 : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CTR : 59|4@0+ (1,0) [0|15] "" XXX
|
||||
|
||||
BO_ 158 MSG_05: 8 XXX
|
||||
SG_ NEW_SIGNAL_1 : 23|8@0+ (1,0) [0|15] "" XXX
|
||||
SG_ NEW_SIGNAL_2 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_3 : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 157 CRZ_BTNS: 8 XXX
|
||||
SG_ SET_P_INV : 21|1@0+ (1,0) [0|3] "" XXX
|
||||
SG_ CAN_OFF_INV : 17|1@1+ (1,0) [0|3] "" XXX
|
||||
SG_ CAN_OFF : 0|1@1+ (1,0) [0|3] "" XXX
|
||||
SG_ SET_M_INV : 22|1@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_M : 5|1@0+ (1,0) [0|3] "" XXX
|
||||
SG_ SET_P : 4|1@0+ (1,0) [0|3] "" XXX
|
||||
SG_ RES_INV : 19|1@1+ (1,0) [0|3] "" XXX
|
||||
SG_ RES : 2|1@1+ (1,0) [0|3] "" XXX
|
||||
SG_ DISTANCE_LESS : 7|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DISTANCE_LESS_INV : 8|1@0+ (1,0) [0|31] "" XXX
|
||||
SG_ DISTANCE_MORE : 6|1@0+ (1,0) [0|3] "" XXX
|
||||
SG_ DISTANCE_MORE_INV : 23|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ MODE_Y : 13|1@1+ (1,0) [0|3] "" XXX
|
||||
SG_ MODE_X : 14|1@0+ (1,0) [0|255] "" XXX
|
||||
SG_ MODE_Y_INV : 30|1@0+ (1,0) [0|3] "" XXX
|
||||
SG_ MODE_X_INV : 31|1@0+ (1,0) [0|3] "" XXX
|
||||
SG_ CTR : 29|4@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 154 BLINK_INFO: 8 XXX
|
||||
SG_ LEFT_BLINK : 18|1@1+ (1,0) [0|3] "" XXX
|
||||
SG_ RIGHT_BLINK : 19|1@0+ (1,0) [0|255] "" XXX
|
||||
SG_ REAR_WIPER_ON : 0|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ WIPER_LO : 33|1@1+ (1,0) [0|31] "" XXX
|
||||
SG_ WIPER_HI : 34|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 145 TURN_SWITCH: 8 XXX
|
||||
SG_ NEW_SIGNAL_1 : 37|1@0+ (1,0) [0|3] "" XXX
|
||||
SG_ NEW_SIGNAL_2 : 36|1@0+ (1,0) [0|3] "" XXX
|
||||
SG_ TURN : 38|1@0+ (1,0) [0|3] "" XXX
|
||||
SG_ TURN_LEFT_SWITCH : 13|1@0+ (1,0) [0|255] "" XXX
|
||||
SG_ TURN_RIGHT_SWITCH : 12|1@1+ (1,0) [0|3] "" XXX
|
||||
SG_ HAZARD : 10|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ CTR : 27|4@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 80 MSG_04: 8 XXX
|
||||
SG_ NEW_SIGNAL_1 : 25|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ SIGNAL : 24|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 978 MSG_03: 8 XXX
|
||||
SG_ NEW_SIGNAL_1 : 7|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_2 : 15|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_3 : 23|8@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NEW_SIGNAL_4 : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_5 : 39|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_6 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_7 : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_8 : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 607 NEW_MSG_25: 8 XXX
|
||||
|
||||
BO_ 1115 MSG_02: 8 XXX
|
||||
SG_ NEW_SIGNAL_2 : 15|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_1 : 47|16@0+ (1,0) [0|65535] "" XXX
|
||||
SG_ NEW_SIGNAL_3 : 63|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NEW_SIGNAL_4 : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_5 : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_6 : 39|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CTR : 2|3@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 1067 NEW_MSG_27: 8 XXX
|
||||
SG_ NEW_SIGNAL_2 : 3|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NEW_SIGNAL_4 : 0|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NEW_SIGNAL_1 : 2|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NEW_SIGNAL_5 : 1|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NEW_SIGNAL_3 : 12|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NEW_SIGNAL_6 : 11|1@1+ (1,0) [0|3] "" XXX
|
||||
SG_ NEW_SIGNAL_7 : 10|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NEW_SIGNAL_8 : 9|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NEW_SIGNAL_9 : 8|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 358 NEW_MSG_28: 8 XXX
|
||||
|
||||
BO_ 608 NEW_MSG_29: 8 XXX
|
||||
SG_ NEW_SIGNAL_1 : 8|5@1+ (1,0) [0|7] "" XXX
|
||||
|
||||
BO_ 606 SPEED_TBD: 8 XXX
|
||||
SG_ SPEED_TBD : 7|12@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_1 : 23|12@0- (1,0) [0|65535] "" XXX
|
||||
|
||||
BO_ 552 GEAR: 8 XXX
|
||||
SG_ NEW_SIGNAL_2 : 8|1@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_3 : 11|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NEW_SIGNAL_4 : 18|3@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_5 : 26|3@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_6 : 31|5@0+ (1,0) [0|31] "" XXX
|
||||
SG_ NEW_SIGNAL_7 : 39|1@0+ (1,0) [0|255] "" XXX
|
||||
SG_ GEAR : 35|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ MORE_GEAR : 7|4@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 543 CRZ_EVENTS: 8 XXX
|
||||
SG_ NEW_SIGNAL_3 : 34|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ CHKSUM : 63|8@0+ (1,0) [0|15] "" XXX
|
||||
SG_ NEW_SIGNAL_1 : 55|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ NEW_SIGNAL_5 : 47|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ NEW_SIGNAL_6 : 6|1@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_8 : 0|1@0+ (1,0) [0|31] "" XXX
|
||||
SG_ NEW_SIGNAL_9 : 1|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NEW_SIGNAL_10 : 2|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NEW_SIGNAL_12 : 10|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NEW_SIGNAL_13 : 9|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NEW_SIGNAL_18 : 12|1@0+ (1,0) [0|15] "" XXX
|
||||
SG_ NEW_SIGNAL_19 : 14|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NEW_SIGNAL_20 : 15|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NEW_SIGNAL_21 : 23|1@0+ (1,0) [0|15] "" XXX
|
||||
SG_ NEW_SIGNAL_24 : 31|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ GAS_PEDAL_PRESSED : 32|1@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CRZ_STARTED : 18|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ PLUS_ONE_CRZ : 17|1@0+ (1,0) [0|255] "" XXX
|
||||
SG_ PLUS_ONE_CRZ_2 : 19|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ GAS_MAYBE : 22|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NONACC_ACTIVE : 5|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ CRUISE_ACTIVE_CAR_MOVING : 16|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NONACC_RELATED : 11|1@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CTR : 51|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ CAS_CMD_MAYBE : 30|7@0- (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_4 : 43|4@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 542 NEW_MSG_33: 8 XXX
|
||||
SG_ CTR : 48|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ CTR2 : 56|4@1+ (1,0) [0|15] "" XXX
|
||||
|
||||
BO_ 868 NEW_MSG_34: 8 XXX
|
||||
SG_ CTR : 59|4@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 869 NEW_MSG_35: 8 XXX
|
||||
SG_ NEW_SIGNAL_1 : 7|4@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_3 : 23|16@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_2 : 39|16@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_4 : 55|2@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_5 : 50|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ CTR : 59|4@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 1114 NEW_MSG_4: 8 XXX
|
||||
|
||||
BO_ 535 CURVE_CTRS: 8 XXX
|
||||
SG_ CTR_A_1 : 4|3@0+ (1,0) [0|31] "" XXX
|
||||
SG_ CTR_A_2 : 7|3@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CTR_B_1 : 12|3@0+ (1,0) [0|7] "" XXX
|
||||
SG_ CTR_B_2 : 15|3@0+ (1,0) [0|7] "" XXX
|
||||
SG_ CTR_C_1 : 20|3@0+ (1,0) [0|7] "" XXX
|
||||
SG_ CTR_C_2 : 23|3@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CTR_D_2 : 31|3@0+ (1,0) [0|7] "" XXX
|
||||
SG_ CTR_D_1 : 28|3@0+ (1,0) [0|7] "" XXX
|
||||
SG_ CURVE : 39|16@0+ (1,0) [0|7] "" XXX
|
||||
SG_ CTR : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CHK_MAYBE : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_1 : 0|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NEW_SIGNAL_2 : 1|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NEW_SIGNAL_6 : 17|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NEW_SIGNAL_7 : 24|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NEW_SIGNAL_8 : 25|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ SEATBELT_MAYBE : 8|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NO_SEATBELT_MAYBE : 16|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NEW_SIGNAL_4 : 9|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 540 CRZ_CTRL: 8 XXX
|
||||
SG_ NEW_SIGNAL_3 : 1|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NEW_SIGNAL_4 : 8|1@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_5 : 9|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NEW_SIGNAL_6 : 10|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NEW_SIGNAL_7 : 18|3@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_9 : 31|1@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_10 : 30|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ ACC_GAS_MAYBE : 23|1@0+ (1,0) [0|31] "" XXX
|
||||
SG_ ACC_GAS_MAYBE2 : 29|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ CRZ_ACTIVE : 3|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 539 CRZ_INFO: 8 XXX
|
||||
SG_ NEW_SIGNAL_1 : 17|1@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_2 : 16|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NEW_SIGNAL_5 : 34|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NEW_SIGNAL_7 : 47|1@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CTR1 : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CTR2 : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_3 : 37|1@0+ (1,0) [0|255] "" XXX
|
||||
SG_ ACC_ACTIVE : 33|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ ACCEL_CMD : 31|10@0- (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 121 EPB: 8 XXX
|
||||
SG_ NEW_SIGNAL_1 : 4|4@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_2 : 0|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NEW_SIGNAL_3 : 15|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_4 : 25|2@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_6 : 39|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CTR : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_7 : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_8 : 41|2@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_9 : 47|1@0+ (1,0) [0|63] "" XXX
|
||||
SG_ NEW_SIGNAL_10 : 46|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NEW_SIGNAL_11 : 45|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ EPB_ACTIVE : 29|1@0+ (1,0) [0|15] "" XXX
|
||||
|
||||
BO_ 1070 2017_1: 8 XXX
|
||||
|
||||
BO_ 1183 2017_2: 8 XXX
|
||||
|
||||
BO_ 1243 2017_3: 8 XXX
|
||||
SG_ NEW_SIGNAL_1 : 7|64@0+ (1,0) [0|18446744073709552000] "" XXX
|
||||
|
||||
BO_ 1269 MSG_2017_4: 8 XXX
|
||||
SG_ NEW_SIGNAL_1 : 55|16@0+ (1,0) [0|18446744073709552000] "" XXX
|
||||
|
||||
BO_ 1178 2017_6: 8 XXX
|
||||
SG_ NEW_SIGNAL_1 : 7|64@0+ (1,0) [0|18446744073709552000] "" XXX
|
||||
|
||||
BO_ 1179 2017_7: 8 XXX
|
||||
SG_ NEW_SIGNAL_1 : 7|64@0+ (1,0) [0|18446744073709552000] "" XXX
|
||||
|
||||
BO_ 1435 2017_8: 8 XXX
|
||||
|
||||
BO_ 253 NEW_MSG_7: 8 XXX
|
||||
SG_ NEW_SIGNAL_1 : 16|1@0+ (1,0) [0|65535] "" XXX
|
||||
SG_ NEW_SIGNAL_2 : 41|1@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CTR : 23|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ NEW_SIGNAL_3 : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_4 : 61|1@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 359 NEW_MSG_11: 8 XXX
|
||||
SG_ NEW_SIGNAL_1 : 15|1@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_2 : 7|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CTR : 31|4@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_3 : 36|5@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_4 : 38|1@1+ (1,0) [0|3] "" XXX
|
||||
SG_ NEW_SIGNAL_5 : 37|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NEW_SIGNAL_6 : 47|4@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 512 NEW_MSG_30: 8 XXX
|
||||
SG_ NEW_SIGNAL_1 : 6|7@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_2 : 7|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NEW_SIGNAL_3 : 15|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_4 : 23|1@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_5 : 22|7@0+ (1,0) [0|127] "" XXX
|
||||
SG_ NEW_SIGNAL_6 : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_7 : 39|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NEW_SIGNAL_8 : 38|7@0+ (1,0) [0|127] "" XXX
|
||||
SG_ NEW_SIGNAL_9 : 40|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ NEW_SIGNAL_10 : 47|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ CTR : 51|3@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_11 : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 515 MSG_01: 8 XXX
|
||||
SG_ CTR : 39|8@0+ (1,0) [0|65535] "" XXX
|
||||
SG_ CTR_2 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 529 NEW_MSG_36: 8 XXX
|
||||
SG_ NEW_SIGNAL_1 : 22|5@0+ (1,0) [0|65535] "" XXX
|
||||
SG_ NEW_SIGNAL_2 : 31|8@0+ (1,0) [0|15] "" XXX
|
||||
SG_ NEW_SIGNAL_3 : 32|4@1+ (1,0) [0|3] "" XXX
|
||||
SG_ CTR : 39|4@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CTR_2 : 47|4@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_4 : 40|4@1+ (1,0) [0|3] "" XXX
|
||||
SG_ NEW_SIGNAL_5 : 53|1@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 1242 NEW_MSG_37: 8 XXX
|
||||
|
||||
BO_ 1266 MSG_09: 8 XXX
|
||||
SG_ NEW_SIGNAL_1 : 20|1@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_2 : 19|4@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NEW_SIGNAL_3 : 31|1@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 976 MSG_15: 8 XXX
|
||||
SG_ NEW_SIGNAL_1 : 55|1@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_2 : 61|6@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 155 MSG_14: 8 XXX
|
||||
|
||||
BO_ 1267 MSG_10: 8 XXX
|
||||
SG_ NEW_SIGNAL_1 : 40|1@0+ (1,0) [0|16777215] "" XXX
|
||||
SG_ NEW_SIGNAL_2 : 42|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 305 NEW_MSG_6: 8 XXX
|
||||
SG_ NEW_SIGNAL_1 : 8|1@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_2 : 9|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NEW_SIGNAL_3 : 10|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 1238 TEMPERATURE: 8 XXX
|
||||
SG_ TEMPERATURE_MAYBE : 47|8@0+ (1,0) [0|4294967295] "" XXX
|
||||
|
||||
BO_ 1087 NEW_MSG_1: 8 XXX
|
||||
SG_ NEW_SIGNAL_1 : 7|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 1143 BSM: 8 XXX
|
||||
SG_ BSM_OFF : 0|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ RIGHT_BS_3 : 37|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ STANDSTILL : 8|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ LEFT_BS1 : 12|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ LEFT_BS3 : 38|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ RIGHT_BS4 : 39|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ LEFT_BS_SIDE : 36|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ IS_MOVING : 9|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ LEFT_BS_BEHIND : 46|2@1+ (1,0) [0|16777215] "" XXX
|
||||
SG_ RIGHT_BS1 : 14|1@0+ (1,0) [0|63] "" XXX
|
||||
SG_ RIGHT_BS_DISTANCE : 35|3@0+ (1,0) [0|1] "" XXX
|
||||
SG_ NEW_SIGNAL_1 : 32|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 1361 KEY_POSITION: 8 XXX
|
||||
|
||||
BO_ 1283 KEY_POSITION2: 8 XXX
|
||||
|
||||
BO_ 628 MSG_06: 8 XXX
|
||||
|
||||
BO_ 1154 MSG_08: 8 XXX
|
||||
|
||||
BO_ 1139 MSG_13: 8 XXX
|
||||
|
||||
BO_ 1270 MSG_16: 8 XXX
|
||||
|
||||
BO_ 1272 MSG_17: 8 XXX
|
||||
|
||||
BO_ 1425 MSG_19: 8 XXX
|
||||
|
||||
|
||||
|
||||
|
||||
CM_ SG_ 605 PED_BRAKE "3: no brake, 4: brake";
|
||||
CM_ SG_ 1088 LANE_LINES "0 LKAS disabled, 1 no lines, 2 two lines, 3 left line, 4 right line";
|
||||
CM_ SG_ 157 CAN_OFF "Disengage Cruise if enabled, if already disabled TURN it OFF ";
|
||||
CM_ SG_ 552 GEAR "0 P/N, 12 R, 2 D M1, 4 M2, 14 Shift";
|
||||
CM_ SG_ 552 MORE_GEAR "";
|
|
@ -0,0 +1,363 @@
|
|||
VERSION ""
|
||||
|
||||
|
||||
NS_ :
|
||||
NS_DESC_
|
||||
CM_
|
||||
BA_DEF_
|
||||
BA_
|
||||
VAL_
|
||||
CAT_DEF_
|
||||
CAT_
|
||||
FILTER
|
||||
BA_DEF_DEF_
|
||||
EV_DATA_
|
||||
ENVVAR_DATA_
|
||||
SGTYPE_
|
||||
SGTYPE_VAL_
|
||||
BA_DEF_SGTYPE_
|
||||
BA_SGTYPE_
|
||||
SIG_TYPE_REF_
|
||||
VAL_TABLE_
|
||||
SIG_GROUP_
|
||||
SIG_VALTYPE_
|
||||
SIGTYPE_VALTYPE_
|
||||
BO_TX_BU_
|
||||
BA_DEF_REL_
|
||||
BA_REL_
|
||||
BA_DEF_DEF_REL_
|
||||
BU_SG_REL_
|
||||
BU_EV_REL_
|
||||
BU_BO_REL_
|
||||
SG_MUL_VAL_
|
||||
|
||||
BS_:
|
||||
|
||||
BU_: XXX X
|
||||
|
||||
|
||||
BO_ 2 Steering: 8 XXX
|
||||
SG_ Counter : 25|3@1+ (1,0) [0|7] "" XXX
|
||||
SG_ Checksum : 32|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ Steering_Angle : 7|16@0- (0.1,0) [0|65535] "" XXX
|
||||
|
||||
BO_ 64 Throttle: 8 XXX
|
||||
SG_ Checksum : 0|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ Counter : 8|4@1+ (1,0) [0|255] "" XXX
|
||||
SG_ Off_Accel : 60|4@1+ (1,0) [0|7] "" XXX
|
||||
SG_ NEW_SIGNAL_3 : 56|4@1+ (1,0) [0|255] "" XXX
|
||||
SG_ Engine_RPM : 16|12@1+ (1,0) [0|255] "" XXX
|
||||
SG_ Throttle_Cruise : 40|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ Throttle_Combo : 55|8@1+ (0.392157,0) [0|255] "" XXX
|
||||
SG_ Throttle_Pedal : 32|8@1+ (1,0) [0|255] "" XXX
|
||||
|
||||
|
||||
BO_ 65 NEW_MSG_1: 8 XXX
|
||||
SG_ Checksum : 0|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ Counter : 8|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ NEW_SIGNAL_4 : 32|12@1+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_3 : 16|12@1+ (1,0) [0|1] "" XXX
|
||||
SG_ NEW_SIGNAL_5 : 31|1@0+ (1,0) [0|15] "" XXX
|
||||
SG_ NEW_SIGNAL_6 : 48|8@1+ (1,0) [0|63] "" XXX
|
||||
SG_ NEW_SIGNAL_7 : 59|2@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 72 NEW_MSG_2: 8 XXX
|
||||
SG_ Checksum : 0|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ Counter : 8|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ NEW_SIGNAL_3 : 40|16@1+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_4 : 38|3@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_5 : 16|8@1+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 316 NEW_MSG_3: 8 XXX
|
||||
|
||||
BO_ 326 NEW_MSG_4: 8 XXX
|
||||
SG_ Checksum : 0|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ Counter : 8|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ NEW_SIGNAL_1 : 16|12@1+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_2 : 32|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_3 : 40|2@1+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 315 G_Sensor: 8 XXX
|
||||
SG_ longitudinal : 63|8@0- (1,0) [0|255] "" XXX
|
||||
SG_ Latitudinal : 48|8@1- (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 314 Wheel_Speeds: 8 XXX
|
||||
SG_ Checksum : 0|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ Counter : 8|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ FR : 12|13@1+ (0.057,0) [0|255] "kph" XXX
|
||||
SG_ RR : 25|13@1+ (0.057,0) [0|255] "kph" XXX
|
||||
SG_ FL : 51|13@1+ (0.057,0) [0|255] "kph" XXX
|
||||
SG_ RL : 38|13@1+ (0.057,0) [0|255] "kph" XXX
|
||||
|
||||
BO_ 73 NEW_MSG_5: 8 XXX
|
||||
SG_ Checksum : 0|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_1 : 32|8@1+ (1,0) [0|4095] "" XXX
|
||||
SG_ NEW_SIGNAL_2 : 24|8@1+ (1,0) [0|127] "" XXX
|
||||
|
||||
BO_ 280 NEW_MSG_6: 8 XXX
|
||||
SG_ NEW_SIGNAL_1 : 12|12@1- (1,0) [0|4095] "" XXX
|
||||
SG_ NEW_SIGNAL_2 : 48|8@1- (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_3 : 61|1@1+ (1,0) [0|7] "" XXX
|
||||
SG_ NEW_SIGNAL_4 : 40|4@1+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 281 Steering_Torque: 8 XXX
|
||||
SG_ checksum : 0|8@1+ (1,0) [0|3] "" XXX
|
||||
SG_ counter : 8|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ Steer_Torque_Sensor : 16|11@1- (-1,0) [0|3] "" XXX
|
||||
SG_ Steering_Angle : 32|16@1- (-0.0217,0) [0|255] "" X
|
||||
SG_ Steer_Torque_Output : 48|11@1- (-1,0) [0|31] "" XXX
|
||||
|
||||
BO_ 312 Brake_Pressure_L_R: 8 XXX
|
||||
SG_ Checksum : 0|8@1+ (1,0) [0|31] "" XXX
|
||||
SG_ Counter : 8|4@1+ (1,0) [0|3] "" XXX
|
||||
SG_ Brake_2 : 56|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ Brake_1 : 48|8@1+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 313 Brake_Pedal: 8 XXX
|
||||
SG_ Brake_Pedal_On : 34|1@1+ (1,0) [0|7] "" XXX
|
||||
SG_ Brake_Pedal : 36|12@1+ (1,0) [0|65535] "" XXX
|
||||
|
||||
BO_ 290 ES_LKAS: 8 XXX
|
||||
SG_ Checksum : 0|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ Counter : 8|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ LKAS_Output : 16|13@1- (-1,0) [0|3] "" XXX
|
||||
SG_ LKAS_Request : 29|1@0+ (1,0) [0|3] "" XXX
|
||||
SG_ SET_1 : 12|1@0+ (1,0) [0|3] "" XXX
|
||||
|
||||
BO_ 722 NEW_MSG_10: 8 XXX
|
||||
SG_ Checksum : 0|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ Counter : 8|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ NEW_SIGNAL_1 : 27|3@1+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_4 : 56|2@1+ (1,0) [0|3] "" XXX
|
||||
SG_ NEW_SIGNAL_5 : 45|2@0+ (1,0) [0|3] "" XXX
|
||||
|
||||
BO_ 544 ES_Brake: 8 XXX
|
||||
SG_ Checksum : 0|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ Counter : 8|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ Brake_Pressure : 16|16@1+ (1,0) [0|255] "" XXX
|
||||
SG_ __Status : 36|4@1+ (1,0) [0|63] "" XXX
|
||||
|
||||
BO_ 545 ES_Distance: 8 XXX
|
||||
SG_ Checksum : 0|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ Counter : 8|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ Close_Distance : 40|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ Distance_Swap : 37|1@1+ (1,0) [0|3] "" XXX
|
||||
SG_ NEW_SIGNAL_5 : 39|1@1+ (1,0) [0|31] "" XXX
|
||||
SG_ NEW_SIGNAL_9 : 38|1@1+ (1,0) [0|3] "" XXX
|
||||
SG_ NEW_SIGNAL_4 : 34|1@1+ (1,0) [0|3] "" XXX
|
||||
SG_ Brake_Pedal : 33|1@1+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_10 : 35|1@1+ (1,0) [0|3] "" XXX
|
||||
SG_ Throttle : 16|12@1+ (1,0) [0|65535] "" XXX
|
||||
SG_ NEW_SIGNAL_1 : 31|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ SET_1 : 12|1@0+ (1,0) [0|3] "" XXX
|
||||
SG_ ACC_ENABLE_BTN : 56|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ Car_Follow : 32|1@1+ (1,0) [0|3] "" XXX
|
||||
SG_ Brake : 36|1@0+ (1,0) [0|3] "" XXX
|
||||
|
||||
BO_ 546 ES_Status: 8 XXX
|
||||
SG_ Checksum : 0|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ Counter : 8|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ RPM : 16|12@1+ (1,0) [0|255] "" XXX
|
||||
SG_ Cruise_Activated : 29|1@0+ (1,0) [0|3] "" XXX
|
||||
SG_ Cruise_Brake : 30|1@1+ (1,0) [0|3] "" XXX
|
||||
|
||||
BO_ 554 ES_Blank: 8 XXX
|
||||
SG_ Checksum : 0|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ Counter : 8|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ SET_65535 : 39|16@1+ (1,0) [0|16777215] "" XXX
|
||||
SG_ SET_1 : 13|1@1+ (1,0) [0|7] "" XXX
|
||||
|
||||
BO_ 557 NEW_MSG_14: 8 XXX
|
||||
SG_ Checksum : 0|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ Counter : 8|4@1+ (1,0) [0|15] "" XXX
|
||||
|
||||
BO_ 576 CruiseControl: 8 XXX
|
||||
SG_ Checksum : 0|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ Counter : 8|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ NEW_SIGNAL_5 : 42|1@1+ (1,0) [0|3] "" XXX
|
||||
SG_ Cruise_On : 40|1@1+ (1,0) [0|3] "" XXX
|
||||
SG_ Cruise_Activated : 41|1@1+ (1,0) [0|3] "" XXX
|
||||
|
||||
BO_ 577 NEW_MSG_16: 8 XXX
|
||||
SG_ Checksum : 0|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ Counter : 8|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ NEW_SIGNAL_1 : 16|12@1+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 552 NEW_MSG_17: 8 XXX
|
||||
SG_ Checksum : 0|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ Counter : 8|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ NEW_SIGNAL_1 : 48|1@1+ (1,0) [0|3] "" XXX
|
||||
|
||||
BO_ 912 Dashlights: 8 XXX
|
||||
SG_ NEW_SIGNAL_1 : 32|1@1+ (1,0) [0|3] "" XXX
|
||||
SG_ NEW_SIGNAL_2 : 8|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ Checksum : 0|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ RIGHT_BLINKER : 51|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ LEFT_BLINKER : 50|1@1+ (1,0) [0|3] "" XXX
|
||||
SG_ SEATBELT_FL : 48|1@1+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 940 BodyInfo: 8 XXX
|
||||
SG_ DASH_BTN_LIGHTS : 56|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DOOR_OPEN_FL : 32|1@1+ (1,0) [0|255] "" XXX
|
||||
SG_ DOOR_OPEN_FR : 33|1@1+ (1,0) [0|3] "" 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_ FOG_LIGHTS2 : 60|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ Highbeam : 58|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ Lowbeam : 57|1@1+ (1,0) [0|3] "" 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|7] "" XXX
|
||||
SG_ NEW_SIGNAL_9 : 60|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ NEW_SIGNAL_10 : 49|2@1+ (1,0) [0|3] "" XXX
|
||||
SG_ Brake_Pedal : 51|1@1+ (1,0) [0|3] "" XXX
|
||||
SG_ Cruise_Set_Speed : 40|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ Cruise_Activated : 36|1@1+ (1,0) [0|3] "" XXX
|
||||
SG_ Cruise_Disengaged : 35|1@1+ (1,0) [0|3] "" XXX
|
||||
SG_ Far_Distance : 56|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ Car_Follow : 52|1@1+ (1,0) [0|3] "" XXX
|
||||
SG_ ACC_Distance : 28|3@1+ (1,0) [0|3] "" 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_ LKAS_ACTIVE : 17|1@1+ (1,0) [0|3] "" 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_ENABLE_2 : 26|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ NEW_SIGNAL_7 : 28|1@1+ (1,0) [0|3] "" XXX
|
||||
SG_ NEW_SIGNAL_2 : 30|1@1+ (1,0) [0|3] "" XXX
|
||||
SG_ FCW_Cont_Beep : 32|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ FCW_Repeated_Beep : 33|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ Throttle_Management_Activated : 34|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ Traffic_light_Ahead : 35|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ Right_Depart : 36|1@1+ (1,0) [0|3] "" XXX
|
||||
SG_ NEW_SIGNAL_4 : 44|1@1+ (1,0) [0|3] "" XXX
|
||||
SG_ NEW_SIGNAL_5 : 56|2@1+ (1,0) [0|3] "" XXX
|
||||
|
||||
BO_ 805 ES_NEW_MSG_22: 8 XXX
|
||||
SG_ Checksum : 0|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ Counter : 8|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ NEW_SIGNAL_3 : 22|2@1+ (1,0) [0|3] "" XXX
|
||||
SG_ NEW_SIGNAL_1 : 14|1@1+ (1,0) [0|3] "" XXX
|
||||
SG_ NEW_SIGNAL_4 : 15|1@1+ (1,0) [0|3] "" XXX
|
||||
|
||||
BO_ 808 NEW_MSG_23: 8 XXX
|
||||
SG_ Checksum : 0|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ Counter : 8|4@1+ (1,0) [0|15] "" XXX
|
||||
|
||||
BO_ 837 NEW_MSG_24: 8 XXX
|
||||
SG_ Checksum : 0|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ Counter : 8|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ NEW_SIGNAL_3 : 40|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_4 : 32|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ NEW_SIGNAL_5 : 24|8@1+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 838 NEW_MSG_25: 8 XXX
|
||||
SG_ Checksum : 0|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ Counter : 8|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ NEW_SIGNAL_3 : 16|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_4 : 40|1@1+ (1,0) [0|3] "" XXX
|
||||
|
||||
BO_ 842 NEW_MSG_26: 8 XXX
|
||||
SG_ Checksum : 0|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ Counter : 8|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ NEW_SIGNAL_3 : 32|8@1+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 915 NEW_MSG_27: 8 XXX
|
||||
SG_ Checksum : 0|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ Counter : 8|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ NEW_SIGNAL_3 : 16|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_4 : 32|9@1+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 1788 NEW_MSG_28: 8 XXX
|
||||
SG_ Checksum : 0|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ Counter : 8|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ NEW_SIGNAL_3 : 40|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ NEW_SIGNAL_4 : 48|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_5 : 16|8@1+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 816 NEW_MSG_29: 8 XXX
|
||||
SG_ Checksum : 0|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ Counter : 8|4@1+ (1,0) [0|15] "" XXX
|
||||
|
||||
BO_ 826 NEW_MSG_30: 8 XXX
|
||||
SG_ Checksum : 0|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ Counter : 8|4@1+ (1,0) [0|15] "" XXX
|
||||
|
||||
BO_ 839 NEW_MSG_31: 8 XXX
|
||||
SG_ Checksum : 0|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ Counter : 8|4@1+ (1,0) [0|15] "" XXX
|
||||
|
||||
BO_ 2015 NEW_MSG_32: 8 XXX
|
||||
SG_ NEW_SIGNAL_2 : 16|8@1+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 2024 NEW_MSG_33: 8 XXX
|
||||
SG_ NEW_SIGNAL_1 : 24|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_2 : 0|3@1+ (1,0) [0|15] "" XXX
|
||||
SG_ NEW_SIGNAL_3 : 16|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_4 : 32|8@1+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 1614 NEW_MSG_34: 8 XXX
|
||||
SG_ Checksum : 0|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ Counter : 8|4@1+ (1,0) [0|15] "" XXX
|
||||
|
||||
BO_ 1617 NEW_MSG_35: 8 XXX
|
||||
SG_ Checksum : 0|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ Counter : 8|4@1+ (1,0) [0|15] "" XXX
|
||||
|
||||
BO_ 1632 NEW_MSG_36: 8 XXX
|
||||
SG_ NEW_SIGNAL_1 : 55|16@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 1650 NEW_MSG_37: 8 XXX
|
||||
SG_ Checksum : 0|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ Counter : 8|4@1+ (1,0) [0|15] "" XXX
|
||||
|
||||
BO_ 1657 NEW_MSG_38: 8 XXX
|
||||
SG_ Checksum : 0|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ Counter : 8|4@1+ (1,0) [0|15] "" XXX
|
||||
|
||||
BO_ 1658 NEW_MSG_39: 8 XXX
|
||||
SG_ Checksum : 0|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ Counter : 8|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ NEW_SIGNAL_3 : 33|1@1+ (1,0) [0|3] "" XXX
|
||||
SG_ NEW_SIGNAL_4 : 31|1@0+ (1,0) [0|3] "" XXX
|
||||
|
||||
BO_ 1677 NEW_MSG_40: 8 XXX
|
||||
SG_ Checksum : 0|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ Counter : 8|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ NEW_SIGNAL_3 : 16|4@1+ (1,0) [0|15] "" XXX
|
||||
|
||||
BO_ 1743 NEW_MSG_41: 8 XXX
|
||||
SG_ Checksum : 0|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ Counter : 8|4@1+ (1,0) [0|15] "" XXX
|
||||
|
||||
BO_ 1785 NEW_MSG_42: 8 XXX
|
||||
SG_ NEW_SIGNAL_1 : 0|4@1+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_2 : 21|1@1+ (1,0) [0|31] "" XXX
|
||||
SG_ NEW_SIGNAL_3 : 17|1@1+ (1,0) [0|7] "" XXX
|
||||
|
||||
BO_ 1759 NEW_MSG_43: 8 XXX
|
||||
SG_ NEW_SIGNAL_1 : 17|1@1+ (1,0) [0|3] "" XXX
|
||||
|
||||
BO_ 1786 NEW_MSG_44: 8 XXX
|
||||
SG_ NEW_SIGNAL_1 : 0|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ NEW_SIGNAL_2 : 16|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_3 : 8|8@1+ (1,0) [0|15] "" XXX
|
||||
|
||||
BO_ 1787 NEW_MSG_45: 8 XXX
|
||||
SG_ NEW_SIGNAL_1 : 0|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ NEW_SIGNAL_2 : 8|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_3 : 16|8@1+ (1,0) [0|255] "" XXX
|
||||
|
||||
|
||||
|
||||
|
||||
CM_ SG_ 940 FOG_LIGHTS2 "yellow fog light in the dash";
|
||||
CM_ SG_ 940 Highbeam "01 = low beam, 11 = high beam";
|
||||
CM_ SG_ 805 NEW_SIGNAL_3 "always 3";
|
||||
CM_ SG_ 805 NEW_SIGNAL_4 "always 1";
|
|
@ -191,10 +191,10 @@ BO_ 354 ES_RPM: 8 XXX
|
|||
SG_ Brake : 8|1@1+ (1,0) [0|7] "" XXX
|
||||
|
||||
BO_ 356 ES_LKAS: 8 XXX
|
||||
SG_ Checksum : 56|8@1+ (1,0) [0|15] "" XXX
|
||||
SG_ Counter : 0|3@1+ (1,0) [0|15] "" XXX
|
||||
SG_ LKAS_Active : 24|1@1+ (1,0) [0|7] "" XXX
|
||||
SG_ LKAS_Output : 8|13@1- (-1,0) [0|127] "" XXX
|
||||
SG_ Checksum : 56|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ Counter : 0|3@1+ (1,0) [0|8] "" XXX
|
||||
SG_ LKAS_Active : 24|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ LKAS_Command : 8|13@1- (-1,0) [-4096|4095] "" XXX
|
||||
|
||||
BO_ 358 ES_Status: 8 XXX
|
||||
SG_ Counter : 39|3@0+ (1,0) [0|7] "" XXX
|
||||
|
|
|
@ -18,13 +18,15 @@ CM BO_ STEERING_IPAS_COMMA "Copy of msg 614 so we can do angle control while the
|
|||
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_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" 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|8@0+ (1,0) [0|255] "" EON
|
||||
SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" 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" ;
|
||||
|
||||
|
|
|
@ -18,13 +18,15 @@ CM BO_ STEERING_IPAS_COMMA "Copy of msg 614 so we can do angle control while the
|
|||
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_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" 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|8@0+ (1,0) [0|255] "" EON
|
||||
SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" 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" ;
|
||||
|
||||
|
@ -316,6 +318,7 @@ BO_ 608 STEER_TORQUE_SENSOR: 8 XXX
|
|||
SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX
|
||||
SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ STEER_ANGLE : 31|16@0- (0.05527,0) [-500|500] "" XXX
|
||||
|
||||
BO_ 610 EPS_STATUS: 8 EPS
|
||||
SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX
|
||||
|
|
|
@ -18,13 +18,15 @@ CM BO_ STEERING_IPAS_COMMA "Copy of msg 614 so we can do angle control while the
|
|||
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_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" 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|8@0+ (1,0) [0|255] "" EON
|
||||
SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" 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" ;
|
||||
|
||||
|
|
|
@ -18,13 +18,15 @@ CM BO_ STEERING_IPAS_COMMA "Copy of msg 614 so we can do angle control while the
|
|||
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_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" 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|8@0+ (1,0) [0|255] "" EON
|
||||
SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" 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" ;
|
||||
|
||||
|
|
|
@ -18,13 +18,15 @@ CM BO_ STEERING_IPAS_COMMA "Copy of msg 614 so we can do angle control while the
|
|||
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_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" 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|8@0+ (1,0) [0|255] "" EON
|
||||
SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" 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" ;
|
||||
|
||||
|
|
|
@ -18,13 +18,15 @@ CM BO_ STEERING_IPAS_COMMA "Copy of msg 614 so we can do angle control while the
|
|||
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_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" 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|8@0+ (1,0) [0|255] "" EON
|
||||
SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" 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" ;
|
||||
|
||||
|
|
|
@ -18,13 +18,15 @@ CM BO_ STEERING_IPAS_COMMA "Copy of msg 614 so we can do angle control while the
|
|||
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_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" 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|8@0+ (1,0) [0|255] "" EON
|
||||
SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" 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" ;
|
||||
|
||||
|
|
|
@ -18,13 +18,15 @@ CM BO_ STEERING_IPAS_COMMA "Copy of msg 614 so we can do angle control while the
|
|||
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_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" 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|8@0+ (1,0) [0|255] "" EON
|
||||
SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" 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" ;
|
||||
|
||||
|
|
|
@ -18,13 +18,15 @@ CM BO_ STEERING_IPAS_COMMA "Copy of msg 614 so we can do angle control while the
|
|||
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_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" 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|8@0+ (1,0) [0|255] "" EON
|
||||
SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" 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" ;
|
||||
|
||||
|
|
|
@ -18,13 +18,15 @@ CM BO_ STEERING_IPAS_COMMA "Copy of msg 614 so we can do angle control while the
|
|||
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_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" 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|8@0+ (1,0) [0|255] "" EON
|
||||
SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" 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" ;
|
||||
|
||||
|
|
|
@ -18,13 +18,15 @@ CM BO_ STEERING_IPAS_COMMA "Copy of msg 614 so we can do angle control while the
|
|||
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_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" 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|8@0+ (1,0) [0|255] "" EON
|
||||
SG_ CHECKSUM : 47|8@0+ (1,0) [0|3] "" 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" ;
|
||||
|
||||
|
|
|
@ -29,13 +29,17 @@ jobs:
|
|||
command: |
|
||||
docker run panda_build /bin/bash -c "cd /panda/board; make bin"
|
||||
- run:
|
||||
name: Build Honda Pedal STM image
|
||||
name: Build Panda STM bootstub image
|
||||
command: |
|
||||
docker run panda_build /bin/bash -c "cd /panda/board/pedal_honda; make obj/comma.bin"
|
||||
docker run panda_build /bin/bash -c "cd /panda/board; make obj/bootstub.panda.bin"
|
||||
- run:
|
||||
name: Build Toyota Pedal STM image
|
||||
name: Build Pedal STM image
|
||||
command: |
|
||||
docker run panda_build /bin/bash -c "cd /panda/board/pedal_toyota; make obj/comma.bin"
|
||||
docker run panda_build /bin/bash -c "cd /panda/board/pedal; make obj/comma.bin"
|
||||
- run:
|
||||
name: Build Pedal STM bootstub image
|
||||
command: |
|
||||
docker run panda_build /bin/bash -c "cd /panda/board/pedal; make obj/bootstub.bin"
|
||||
- run:
|
||||
name: Build NEO STM image
|
||||
command: |
|
||||
|
|
|
@ -2,6 +2,14 @@ CFLAGS += -I inc -I ../ -nostdlib -fno-builtin -std=gnu11 -Os
|
|||
|
||||
CFLAGS += -Tstm32_flash.ld
|
||||
|
||||
# Compile fast charge (DCP) only not on EON
|
||||
ifeq (,$(wildcard /EON))
|
||||
BUILDER = DEV
|
||||
else
|
||||
CFLAGS += "-DEON"
|
||||
BUILDER = EON
|
||||
endif
|
||||
|
||||
CC = arm-none-eabi-gcc
|
||||
OBJCOPY = arm-none-eabi-objcopy
|
||||
OBJDUMP = arm-none-eabi-objdump
|
||||
|
|
|
@ -454,6 +454,7 @@ void early() {
|
|||
#ifdef PANDA
|
||||
// enable the ESP, disable ESP boot mode
|
||||
// unless we are on a giant panda, then there's no ESP
|
||||
// dont disable on grey panda
|
||||
if (is_giant_panda) {
|
||||
set_esp_mode(ESP_DISABLED);
|
||||
} else {
|
||||
|
|
|
@ -539,6 +539,9 @@ int main() {
|
|||
} else {
|
||||
// enable ESP uart
|
||||
uart_init(USART1, 115200);
|
||||
#ifdef EON
|
||||
set_esp_mode(ESP_DISABLED);
|
||||
#endif
|
||||
}
|
||||
// enable LIN
|
||||
uart_init(UART5, 10400);
|
||||
|
@ -590,8 +593,6 @@ int main() {
|
|||
uint64_t marker = 0;
|
||||
#define CURRENT_THRESHOLD 0xF00
|
||||
#define CLICKS 8
|
||||
// Enough clicks to ensure that enumeration happened. Should be longer than bootup time of the device connected to EON
|
||||
#define CLICKS_BOOTUP 30
|
||||
#endif
|
||||
|
||||
for (cnt=0;;cnt++) {
|
||||
|
@ -618,8 +619,9 @@ int main() {
|
|||
}
|
||||
break;
|
||||
case USB_POWER_CDP:
|
||||
// been CLICKS_BOOTUP clicks since we switched to CDP
|
||||
if ((cnt-marker) >= CLICKS_BOOTUP ) {
|
||||
#ifndef EON
|
||||
// been CLICKS clicks since we switched to CDP
|
||||
if ((cnt-marker) >= CLICKS) {
|
||||
// measure current draw, if positive and no enumeration, switch to DCP
|
||||
if (!is_enumerated && current < CURRENT_THRESHOLD) {
|
||||
puts("USBP: no enumeration with current draw, switching to DCP mode\n");
|
||||
|
@ -631,6 +633,7 @@ int main() {
|
|||
if (current >= CURRENT_THRESHOLD) {
|
||||
marker = cnt;
|
||||
}
|
||||
#endif
|
||||
break;
|
||||
case USB_POWER_DCP:
|
||||
// been at least CLICKS clicks since we switched to DCP
|
||||
|
|
|
@ -30,12 +30,20 @@ recover: obj/bootstub.bin obj/$(PROJ_NAME).bin
|
|||
$(DFU_UTIL) -d 0483:df11 -a 0 -s 0x08004000 -D obj/$(PROJ_NAME).bin
|
||||
$(DFU_UTIL) -d 0483:df11 -a 0 -s 0x08000000:leave -D obj/bootstub.bin
|
||||
|
||||
include ../../common/version.mk
|
||||
|
||||
obj/cert.h: ../../crypto/getcertheader.py
|
||||
../../crypto/getcertheader.py ../../certs/debug.pub ../../certs/release.pub > $@
|
||||
|
||||
obj/main.o: main.c ../*.h
|
||||
mkdir -p obj
|
||||
$(CC) $(CFLAGS) -o $@ -c $<
|
||||
|
||||
obj/bootstub.o: ../bootstub.c ../*.h
|
||||
obj/bootstub.o: ../bootstub.c ../*.h obj/gitversion.h obj/cert.h
|
||||
mkdir -p obj
|
||||
mkdir -p ../obj
|
||||
cp obj/gitversion.h ../obj/gitversion.h
|
||||
cp obj/cert.h ../obj/cert.h
|
||||
$(CC) $(CFLAGS) -o $@ -c $<
|
||||
|
||||
obj/$(STARTUP_FILE).o: ../$(STARTUP_FILE).s
|
|
@ -70,21 +70,24 @@ int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, int hardwired) {
|
|||
|
||||
#endif
|
||||
|
||||
// ***************************** honda can checksum *****************************
|
||||
// ***************************** pedal can checksum *****************************
|
||||
|
||||
int can_cksum(uint8_t *dat, int len, int addr, int idx) {
|
||||
int i;
|
||||
int s = 0;
|
||||
for (i = 0; i < len; i++) {
|
||||
s += (dat[i] >> 4);
|
||||
s += dat[i] & 0xF;
|
||||
uint8_t pedal_checksum(uint8_t *dat, int len) {
|
||||
uint8_t crc = 0xFF;
|
||||
uint8_t poly = 0xD5; // standard crc8
|
||||
int i, j;
|
||||
for (i = len - 1; i >= 0; i--) {
|
||||
crc ^= dat[i];
|
||||
for (j = 0; j < 8; j++) {
|
||||
if ((crc & 0x80) != 0) {
|
||||
crc = (uint8_t)((crc << 1) ^ poly);
|
||||
}
|
||||
else {
|
||||
crc <<= 1;
|
||||
}
|
||||
}
|
||||
}
|
||||
s += (addr>>0)&0xF;
|
||||
s += (addr>>4)&0xF;
|
||||
s += (addr>>8)&0xF;
|
||||
s += idx;
|
||||
s = 8-s;
|
||||
return s&0xF;
|
||||
return crc;
|
||||
}
|
||||
|
||||
// ***************************** can port *****************************
|
||||
|
@ -92,6 +95,8 @@ int can_cksum(uint8_t *dat, int len, int addr, int idx) {
|
|||
// addresses to be used on CAN
|
||||
#define CAN_GAS_INPUT 0x200
|
||||
#define CAN_GAS_OUTPUT 0x201
|
||||
#define CAN_GAS_SIZE 6
|
||||
#define COUNTER_CYCLE 0xF
|
||||
|
||||
void CAN1_TX_IRQHandler() {
|
||||
// clear interrupt
|
||||
|
@ -134,14 +139,19 @@ void CAN1_RX0_IRQHandler() {
|
|||
}
|
||||
|
||||
// normal packet
|
||||
uint8_t *dat = (uint8_t *)&CAN->sFIFOMailBox[0].RDLR;
|
||||
uint8_t *dat2 = (uint8_t *)&CAN->sFIFOMailBox[0].RDHR;
|
||||
uint8_t dat[8];
|
||||
uint8_t *rdlr = (uint8_t *)&CAN->sFIFOMailBox[0].RDLR;
|
||||
uint8_t *rdhr = (uint8_t *)&CAN->sFIFOMailBox[0].RDHR;
|
||||
for (int i=0; i<4; i++) {
|
||||
dat[i] = rdlr[i];
|
||||
dat[i+4] = rdhr[i];
|
||||
}
|
||||
uint16_t value_0 = (dat[0] << 8) | dat[1];
|
||||
uint16_t value_1 = (dat[2] << 8) | dat[3];
|
||||
uint8_t enable = (dat2[0] >> 7) & 1;
|
||||
uint8_t index = (dat2[1] >> 4) & 3;
|
||||
if (can_cksum(dat, 5, CAN_GAS_INPUT, index) == (dat2[1] & 0xF)) {
|
||||
if (((current_index+1)&3) == index) {
|
||||
uint8_t enable = (dat[4] >> 7) & 1;
|
||||
uint8_t index = dat[4] & COUNTER_CYCLE;
|
||||
if (pedal_checksum(dat, CAN_GAS_SIZE - 1) == dat[5]) {
|
||||
if (((current_index + 1) & COUNTER_CYCLE) == index) {
|
||||
#ifdef DEBUG
|
||||
puts("setting gas ");
|
||||
puth(value);
|
||||
|
@ -196,18 +206,18 @@ void TIM3_IRQHandler() {
|
|||
// check timer for sending the user pedal and clearing the CAN
|
||||
if ((CAN->TSR & CAN_TSR_TME0) == CAN_TSR_TME0) {
|
||||
uint8_t dat[8];
|
||||
dat[0] = (pdl0>>8)&0xFF;
|
||||
dat[1] = (pdl0>>0)&0xFF;
|
||||
dat[2] = (pdl1>>8)&0xFF;
|
||||
dat[3] = (pdl1>>0)&0xFF;
|
||||
dat[4] = state;
|
||||
dat[5] = can_cksum(dat, 5, CAN_GAS_OUTPUT, pkt_idx) | (pkt_idx<<4);
|
||||
dat[0] = (pdl0>>8) & 0xFF;
|
||||
dat[1] = (pdl0>>0) & 0xFF;
|
||||
dat[2] = (pdl1>>8) & 0xFF;
|
||||
dat[3] = (pdl1>>0) & 0xFF;
|
||||
dat[4] = (state & 0xF) << 4 | pkt_idx;
|
||||
dat[5] = pedal_checksum(dat, CAN_GAS_SIZE - 1);
|
||||
CAN->sTxMailBox[0].TDLR = dat[0] | (dat[1]<<8) | (dat[2]<<16) | (dat[3]<<24);
|
||||
CAN->sTxMailBox[0].TDHR = dat[4] | (dat[5]<<8);
|
||||
CAN->sTxMailBox[0].TDTR = 6; // len of packet is 5
|
||||
CAN->sTxMailBox[0].TIR = (CAN_GAS_OUTPUT << 21) | 1;
|
||||
++pkt_idx;
|
||||
pkt_idx &= 3;
|
||||
pkt_idx &= COUNTER_CYCLE;
|
||||
} else {
|
||||
// old can packet hasn't sent!
|
||||
state = FAULT_SEND;
|
|
@ -1 +0,0 @@
|
|||
obj/*
|
|
@ -1,58 +0,0 @@
|
|||
# :set noet
|
||||
PROJ_NAME = comma
|
||||
|
||||
CFLAGS = -O2 -Wall -std=gnu11 -DPEDAL
|
||||
CFLAGS += -mlittle-endian -mthumb -mcpu=cortex-m3
|
||||
CFLAGS += -msoft-float -DSTM32F2 -DSTM32F205xx
|
||||
CFLAGS += -I ../inc -I ../ -I ../../ -nostdlib
|
||||
CFLAGS += -T../stm32_flash.ld
|
||||
|
||||
STARTUP_FILE = startup_stm32f205xx
|
||||
|
||||
CC = arm-none-eabi-gcc
|
||||
OBJCOPY = arm-none-eabi-objcopy
|
||||
OBJDUMP = arm-none-eabi-objdump
|
||||
DFU_UTIL = "dfu-util"
|
||||
|
||||
# pedal only uses the debug cert
|
||||
CERT = ../../certs/debug
|
||||
CFLAGS += "-DALLOW_DEBUG"
|
||||
|
||||
canflash: obj/$(PROJ_NAME).bin
|
||||
../../tests/pedal/enter_canloader.py $<
|
||||
|
||||
usbflash: obj/$(PROJ_NAME).bin
|
||||
../../tests/pedal/enter_canloader.py; sleep 0.5
|
||||
PYTHONPATH=../../ python -c "from python import Panda; p = [x for x in [Panda(x) for x in Panda.list()] if x.bootstub]; assert(len(p)==1); p[0].flash('obj/$(PROJ_NAME).bin', reconnect=False)"
|
||||
|
||||
recover: obj/bootstub.bin obj/$(PROJ_NAME).bin
|
||||
../../tests/pedal/enter_canloader.py --recover; sleep 0.5
|
||||
$(DFU_UTIL) -d 0483:df11 -a 0 -s 0x08004000 -D obj/$(PROJ_NAME).bin
|
||||
$(DFU_UTIL) -d 0483:df11 -a 0 -s 0x08000000:leave -D obj/bootstub.bin
|
||||
|
||||
obj/main.o: main.c ../*.h
|
||||
mkdir -p obj
|
||||
$(CC) $(CFLAGS) -o $@ -c $<
|
||||
|
||||
obj/bootstub.o: ../bootstub.c ../*.h
|
||||
mkdir -p obj
|
||||
$(CC) $(CFLAGS) -o $@ -c $<
|
||||
|
||||
obj/$(STARTUP_FILE).o: ../$(STARTUP_FILE).s
|
||||
$(CC) $(CFLAGS) -o $@ -c $<
|
||||
|
||||
obj/%.o: ../../crypto/%.c
|
||||
$(CC) $(CFLAGS) -o $@ -c $<
|
||||
|
||||
obj/$(PROJ_NAME).bin: obj/$(STARTUP_FILE).o obj/main.o
|
||||
# hack
|
||||
$(CC) -Wl,--section-start,.isr_vector=0x8004000 $(CFLAGS) -o obj/$(PROJ_NAME).elf $^
|
||||
$(OBJCOPY) -v -O binary obj/$(PROJ_NAME).elf obj/code.bin
|
||||
SETLEN=1 ../../crypto/sign.py obj/code.bin $@ $(CERT)
|
||||
|
||||
obj/bootstub.bin: obj/$(STARTUP_FILE).o obj/bootstub.o obj/sha.o obj/rsa.o
|
||||
$(CC) $(CFLAGS) -o obj/bootstub.$(PROJ_NAME).elf $^
|
||||
$(OBJCOPY) -v -O binary obj/bootstub.$(PROJ_NAME).elf $@
|
||||
|
||||
clean:
|
||||
rm -f obj/*
|
|
@ -1,30 +0,0 @@
|
|||
MOVE ALL FILES TO board/pedal TO FLASH
|
||||
|
||||
|
||||
This is the firmware for the comma pedal. It borrows a lot from panda.
|
||||
|
||||
The comma pedal is a gas pedal interceptor for Honda/Acura. It allows you to "virtually" press the pedal.
|
||||
|
||||
This is the open source software. Note that it is not ready to use yet.
|
||||
|
||||
== Test Plan ==
|
||||
|
||||
* Startup
|
||||
** Confirm STATE_FAULT_STARTUP
|
||||
* Timeout
|
||||
** Send value
|
||||
** Confirm value is output
|
||||
** Stop sending messages
|
||||
** Confirm value is passthru after 100ms
|
||||
** Confirm STATE_FAULT_TIMEOUT
|
||||
* Random values
|
||||
** Send random 6 byte messages
|
||||
** Confirm random values cause passthru
|
||||
** Confirm STATE_FAULT_BAD_CHECKSUM
|
||||
* Same message lockout
|
||||
** Send same message repeated
|
||||
** Confirm timeout behavior
|
||||
* Don't set enable
|
||||
** Confirm no output
|
||||
* Set enable and values
|
||||
** Confirm output
|
|
@ -1,291 +0,0 @@
|
|||
//#define DEBUG
|
||||
//#define CAN_LOOPBACK_MODE
|
||||
//#define USE_INTERNAL_OSC
|
||||
|
||||
#include "../config.h"
|
||||
|
||||
#include "drivers/drivers.h"
|
||||
#include "drivers/llgpio.h"
|
||||
#include "gpio.h"
|
||||
|
||||
#define CUSTOM_CAN_INTERRUPTS
|
||||
|
||||
#include "libc.h"
|
||||
#include "safety.h"
|
||||
#include "drivers/adc.h"
|
||||
#include "drivers/uart.h"
|
||||
#include "drivers/dac.h"
|
||||
#include "drivers/can.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
#define CAN CAN1
|
||||
|
||||
//#define PEDAL_USB
|
||||
|
||||
#ifdef PEDAL_USB
|
||||
#include "drivers/usb.h"
|
||||
#endif
|
||||
|
||||
#define ENTER_BOOTLOADER_MAGIC 0xdeadbeef
|
||||
uint32_t enter_bootloader_mode;
|
||||
|
||||
void __initialize_hardware_early() {
|
||||
early();
|
||||
}
|
||||
|
||||
// ********************* serial debugging *********************
|
||||
|
||||
void debug_ring_callback(uart_ring *ring) {
|
||||
char rcv;
|
||||
while (getc(ring, &rcv)) {
|
||||
putc(ring, rcv);
|
||||
}
|
||||
}
|
||||
|
||||
#ifdef PEDAL_USB
|
||||
|
||||
int usb_cb_ep1_in(uint8_t *usbdata, int len, int hardwired) { return 0; }
|
||||
void usb_cb_ep2_out(uint8_t *usbdata, int len, int hardwired) {}
|
||||
void usb_cb_ep3_out(uint8_t *usbdata, int len, int hardwired) {}
|
||||
void usb_cb_enumeration_complete() {}
|
||||
|
||||
int usb_cb_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp, int hardwired) {
|
||||
int resp_len = 0;
|
||||
uart_ring *ur = NULL;
|
||||
switch (setup->b.bRequest) {
|
||||
// **** 0xe0: uart read
|
||||
case 0xe0:
|
||||
ur = get_ring_by_number(setup->b.wValue.w);
|
||||
if (!ur) break;
|
||||
if (ur == &esp_ring) uart_dma_drain();
|
||||
// read
|
||||
while ((resp_len < min(setup->b.wLength.w, MAX_RESP_LEN)) &&
|
||||
getc(ur, (char*)&resp[resp_len])) {
|
||||
++resp_len;
|
||||
}
|
||||
break;
|
||||
}
|
||||
return resp_len;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
// ***************************** toyota can checksum ****************************
|
||||
|
||||
int can_cksum(uint8_t *dat, uint8_t len, uint16_t addr)
|
||||
{
|
||||
uint8_t checksum = 0;
|
||||
checksum =((addr & 0xFF00) >> 8) + (addr & 0x00FF) + len + 1;
|
||||
//uint16_t temp_msg = msg;
|
||||
|
||||
for (int ii = 0; ii < len; ii++)
|
||||
{
|
||||
checksum += (dat[ii]);
|
||||
//temp_msg = temp_msg >> 8;
|
||||
}
|
||||
//return ((msg & ~0xFF) & (checksum & 0xFF));
|
||||
return checksum;
|
||||
}
|
||||
|
||||
// ***************************** can port *****************************
|
||||
|
||||
// addresses to be used on CAN
|
||||
#define CAN_GAS_INPUT 0x200
|
||||
#define CAN_GAS_OUTPUT 0x201
|
||||
|
||||
void CAN1_TX_IRQHandler() {
|
||||
// clear interrupt
|
||||
CAN->TSR |= CAN_TSR_RQCP0;
|
||||
}
|
||||
|
||||
// two independent values
|
||||
uint16_t gas_set_0 = 0;
|
||||
uint16_t gas_set_1 = 0;
|
||||
|
||||
#define MAX_TIMEOUT 10
|
||||
uint32_t timeout = 0;
|
||||
|
||||
#define NO_FAULT 0
|
||||
#define FAULT_BAD_CHECKSUM 1
|
||||
#define FAULT_SEND 2
|
||||
#define FAULT_SCE 3
|
||||
#define FAULT_STARTUP 4
|
||||
#define FAULT_TIMEOUT 5
|
||||
#define FAULT_INVALID 6
|
||||
uint8_t state = FAULT_STARTUP;
|
||||
|
||||
void CAN1_RX0_IRQHandler() {
|
||||
while (CAN->RF0R & CAN_RF0R_FMP0) {
|
||||
#ifdef DEBUG
|
||||
puts("CAN RX\n");
|
||||
#endif
|
||||
uint32_t address = CAN->sFIFOMailBox[0].RIR>>21;
|
||||
if (address == CAN_GAS_INPUT) {
|
||||
// softloader entry
|
||||
if (CAN->sFIFOMailBox[0].RDLR == 0xdeadface) {
|
||||
if (CAN->sFIFOMailBox[0].RDHR == 0x0ab00b1e) {
|
||||
enter_bootloader_mode = ENTER_SOFTLOADER_MAGIC;
|
||||
NVIC_SystemReset();
|
||||
} else if (CAN->sFIFOMailBox[0].RDHR == 0x02b00b1e) {
|
||||
enter_bootloader_mode = ENTER_BOOTLOADER_MAGIC;
|
||||
NVIC_SystemReset();
|
||||
}
|
||||
}
|
||||
|
||||
// normal packet
|
||||
uint8_t *dat = (uint8_t *)&CAN->sFIFOMailBox[0].RDLR;
|
||||
uint8_t *dat2 = (uint8_t *)&CAN->sFIFOMailBox[0].RDHR;
|
||||
uint16_t value_0 = (dat[0] << 8) | dat[1];
|
||||
uint16_t value_1 = (dat[2] << 8) | dat[3];
|
||||
uint8_t enable = (dat2[0] >> 7) & 1;
|
||||
uint8_t index = 0;
|
||||
if (can_cksum(dat, 5, CAN_GAS_INPUT) == dat2[1]) {
|
||||
if (index == 0) {
|
||||
#ifdef DEBUG
|
||||
puts("setting gas ");
|
||||
puth(value);
|
||||
puts("\n");
|
||||
#endif
|
||||
if (enable) {
|
||||
gas_set_0 = value_0;
|
||||
gas_set_1 = value_1;
|
||||
} else {
|
||||
// clear the fault state if values are 0
|
||||
if (value_0 == 0 && value_1 == 0) {
|
||||
state = NO_FAULT;
|
||||
} else {
|
||||
state = FAULT_INVALID;
|
||||
}
|
||||
gas_set_0 = gas_set_1 = 0;
|
||||
}
|
||||
// clear the timeout
|
||||
timeout = 0;
|
||||
}
|
||||
|
||||
} else {
|
||||
// wrong checksum = fault
|
||||
state = FAULT_BAD_CHECKSUM;
|
||||
}
|
||||
}
|
||||
// next
|
||||
CAN->RF0R |= CAN_RF0R_RFOM0;
|
||||
}
|
||||
}
|
||||
|
||||
void CAN1_SCE_IRQHandler() {
|
||||
state = FAULT_SCE;
|
||||
can_sce(CAN);
|
||||
}
|
||||
|
||||
int pdl0 = 0, pdl1 = 0;
|
||||
|
||||
|
||||
int led_value = 0;
|
||||
|
||||
void TIM3_IRQHandler() {
|
||||
#ifdef DEBUG
|
||||
puth(TIM3->CNT);
|
||||
puts(" ");
|
||||
puth(pdl0);
|
||||
puts(" ");
|
||||
puth(pdl1);
|
||||
puts("\n");
|
||||
#endif
|
||||
|
||||
// check timer for sending the user pedal and clearing the CAN
|
||||
if ((CAN->TSR & CAN_TSR_TME0) == CAN_TSR_TME0) {
|
||||
uint8_t dat[8];
|
||||
dat[0] = (pdl0>>8)&0xFF;
|
||||
dat[1] = (pdl0>>0)&0xFF;
|
||||
dat[2] = (pdl1>>8)&0xFF;
|
||||
dat[3] = (pdl1>>0)&0xFF;
|
||||
dat[4] = state;
|
||||
dat[5] = can_cksum(dat, 5, CAN_GAS_OUTPUT);
|
||||
CAN->sTxMailBox[0].TDLR = dat[0] | (dat[1]<<8) | (dat[2]<<16) | (dat[3]<<24);
|
||||
CAN->sTxMailBox[0].TDHR = dat[4] | (dat[5]<<8);
|
||||
CAN->sTxMailBox[0].TDTR = 6; // len of packet is 5
|
||||
CAN->sTxMailBox[0].TIR = (CAN_GAS_OUTPUT << 21) | 1;
|
||||
} else {
|
||||
// old can packet hasn't sent!
|
||||
state = FAULT_SEND;
|
||||
#ifdef DEBUG
|
||||
puts("CAN MISS\n");
|
||||
#endif
|
||||
}
|
||||
|
||||
// blink the LED
|
||||
set_led(LED_GREEN, led_value);
|
||||
led_value = !led_value;
|
||||
|
||||
TIM3->SR = 0;
|
||||
|
||||
// up timeout for gas set
|
||||
if (timeout == MAX_TIMEOUT) {
|
||||
state = FAULT_TIMEOUT;
|
||||
} else {
|
||||
timeout += 1;
|
||||
}
|
||||
}
|
||||
|
||||
// ***************************** main code *****************************
|
||||
|
||||
void pedal() {
|
||||
// read/write
|
||||
pdl0 = adc_get(ADCCHAN_ACCEL0);
|
||||
pdl1 = adc_get(ADCCHAN_ACCEL1);
|
||||
|
||||
// write the pedal to the DAC
|
||||
if (state == NO_FAULT) {
|
||||
dac_set(0, max(gas_set_0, pdl0));
|
||||
dac_set(1, max(gas_set_1, pdl1));
|
||||
} else {
|
||||
dac_set(0, pdl0);
|
||||
dac_set(1, pdl1);
|
||||
}
|
||||
|
||||
// feed the watchdog
|
||||
IWDG->KR = 0xAAAA;
|
||||
}
|
||||
|
||||
int main() {
|
||||
__disable_irq();
|
||||
|
||||
// init devices
|
||||
clock_init();
|
||||
periph_init();
|
||||
gpio_init();
|
||||
|
||||
#ifdef PEDAL_USB
|
||||
// enable USB
|
||||
usb_init();
|
||||
#endif
|
||||
|
||||
// pedal stuff
|
||||
dac_init();
|
||||
adc_init();
|
||||
|
||||
// init can
|
||||
can_silent = ALL_CAN_LIVE;
|
||||
can_init(0);
|
||||
|
||||
// 48mhz / 65536 ~= 732
|
||||
timer_init(TIM3, 15);
|
||||
NVIC_EnableIRQ(TIM3_IRQn);
|
||||
|
||||
// setup watchdog
|
||||
IWDG->KR = 0x5555;
|
||||
IWDG->PR = 0; // divider /4
|
||||
// 0 = 0.125 ms, let's have a 50ms watchdog
|
||||
IWDG->RLR = 400 - 1;
|
||||
IWDG->KR = 0xCCCC;
|
||||
|
||||
puts("**** INTERRUPTS ON ****\n");
|
||||
__enable_irq();
|
||||
|
||||
// main pedal loop
|
||||
while (1) {
|
||||
pedal();
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
|
@ -1,28 +1,110 @@
|
|||
void subaru_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {}
|
||||
const int SUBARU_MAX_STEER = 2047; // 1s
|
||||
// real time torque limit to prevent controls spamming
|
||||
// the real time limit is 1500/sec
|
||||
const int SUBARU_MAX_RT_DELTA = 940; // max delta torque allowed for real time checks
|
||||
const int32_t SUBARU_RT_INTERVAL = 250000; // 250ms between real time checks
|
||||
const int SUBARU_MAX_RATE_UP = 50;
|
||||
const int SUBARU_MAX_RATE_DOWN = 70;
|
||||
const int SUBARU_DRIVER_TORQUE_ALLOWANCE = 60;
|
||||
const int SUBARU_DRIVER_TORQUE_FACTOR = 10;
|
||||
|
||||
// FIXME
|
||||
// *** all output safety mode ***
|
||||
int subaru_cruise_engaged_last = 0;
|
||||
int subaru_rt_torque_last = 0;
|
||||
int subaru_desired_torque_last = 0;
|
||||
uint32_t subaru_ts_last = 0;
|
||||
struct sample_t subaru_torque_driver; // last few driver torques measured
|
||||
|
||||
static void subaru_init(int16_t param) {
|
||||
controls_allowed = 1;
|
||||
|
||||
static void subaru_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
|
||||
int bus_number = (to_push->RDTR >> 4) & 0xFF;
|
||||
uint32_t addr = to_push->RIR >> 21;
|
||||
|
||||
if ((addr == 0x119) && (bus_number == 0)){
|
||||
int torque_driver_new = ((to_push->RDLR >> 16) & 0x7FF);
|
||||
torque_driver_new = to_signed(torque_driver_new, 11);
|
||||
// update array of samples
|
||||
update_sample(&subaru_torque_driver, torque_driver_new);
|
||||
}
|
||||
|
||||
// enter controls on rising edge of ACC, exit controls on ACC off
|
||||
if ((addr == 0x240) && (bus_number == 0)) {
|
||||
int cruise_engaged = (to_push->RDHR >> 9) & 1;
|
||||
if (cruise_engaged && !subaru_cruise_engaged_last) {
|
||||
controls_allowed = 1;
|
||||
} else if (!cruise_engaged) {
|
||||
controls_allowed = 0;
|
||||
}
|
||||
subaru_cruise_engaged_last = cruise_engaged;
|
||||
}
|
||||
}
|
||||
|
||||
static int subaru_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) {
|
||||
uint32_t addr = to_send->RIR >> 21;
|
||||
|
||||
// steer cmd checks
|
||||
if (addr == 0x122) {
|
||||
int desired_torque = ((to_send->RDLR >> 16) & 0x1FFF);
|
||||
int violation = 0;
|
||||
uint32_t ts = TIM2->CNT;
|
||||
desired_torque = to_signed(desired_torque, 13);
|
||||
|
||||
if (controls_allowed) {
|
||||
|
||||
// *** global torque limit check ***
|
||||
violation |= max_limit_check(desired_torque, SUBARU_MAX_STEER, -SUBARU_MAX_STEER);
|
||||
|
||||
// *** torque rate limit check ***
|
||||
int desired_torque_last = subaru_desired_torque_last;
|
||||
violation |= driver_limit_check(desired_torque, desired_torque_last, &subaru_torque_driver,
|
||||
SUBARU_MAX_STEER, SUBARU_MAX_RATE_UP, SUBARU_MAX_RATE_DOWN,
|
||||
SUBARU_DRIVER_TORQUE_ALLOWANCE, SUBARU_DRIVER_TORQUE_FACTOR);
|
||||
|
||||
// used next time
|
||||
subaru_desired_torque_last = desired_torque;
|
||||
|
||||
// *** torque real time rate limit check ***
|
||||
violation |= rt_rate_limit_check(desired_torque, subaru_rt_torque_last, SUBARU_MAX_RT_DELTA);
|
||||
|
||||
// every RT_INTERVAL set the new limits
|
||||
uint32_t ts_elapsed = get_ts_elapsed(ts, subaru_ts_last);
|
||||
if (ts_elapsed > SUBARU_RT_INTERVAL) {
|
||||
subaru_rt_torque_last = desired_torque;
|
||||
subaru_ts_last = ts;
|
||||
}
|
||||
}
|
||||
|
||||
// no torque if controls is not allowed
|
||||
if (!controls_allowed && (desired_torque != 0)) {
|
||||
violation = 1;
|
||||
}
|
||||
|
||||
// reset to 0 if either controls is not allowed or there's a violation
|
||||
if (violation || !controls_allowed) {
|
||||
subaru_desired_torque_last = 0;
|
||||
subaru_rt_torque_last = 0;
|
||||
subaru_ts_last = ts;
|
||||
}
|
||||
|
||||
if (violation) {
|
||||
return false;
|
||||
}
|
||||
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
static int subaru_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) {
|
||||
|
||||
|
||||
// shifts bits 29 > 11
|
||||
int32_t addr = to_fwd->RIR >> 21;
|
||||
|
||||
// forward CAN 0 > 1
|
||||
if (bus_num == 0) {
|
||||
return 1; // ES CAN
|
||||
return 2; // ES CAN
|
||||
}
|
||||
// forward CAN 1 > 0, except ES_LKAS
|
||||
else if (bus_num == 1) {
|
||||
|
||||
else if (bus_num == 2) {
|
||||
|
||||
// outback 2015
|
||||
if (addr == 0x164) {
|
||||
return -1;
|
||||
|
@ -40,10 +122,10 @@ static int subaru_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) {
|
|||
}
|
||||
|
||||
const safety_hooks subaru_hooks = {
|
||||
.init = subaru_init,
|
||||
.init = nooutput_init,
|
||||
.rx = subaru_rx_hook,
|
||||
.tx = subaru_tx_hook,
|
||||
.tx_lin = nooutput_tx_lin_hook,
|
||||
.ignition = default_ign_hook,
|
||||
.fwd = subaru_fwd_hook,
|
||||
};
|
||||
};
|
||||
|
|
|
@ -79,6 +79,15 @@ static int toyota_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) {
|
|||
// no IPAS in non IPAS mode
|
||||
if (((to_send->RIR>>21) == 0x266) || ((to_send->RIR>>21) == 0x167)) return false;
|
||||
|
||||
// GAS PEDAL: safety check
|
||||
if ((to_send->RIR>>21) == 0x200) {
|
||||
if (controls_allowed && toyota_actuation_limits) {
|
||||
// all messages are fine here
|
||||
} else {
|
||||
if ((to_send->RDLR & 0xFFFF0000) != to_send->RDLR) return 0;
|
||||
}
|
||||
}
|
||||
|
||||
// ACCEL: safety check on byte 1-2
|
||||
if ((to_send->RIR>>21) == 0x343) {
|
||||
int desired_accel = ((to_send->RDLR & 0xFF) << 8) | ((to_send->RDLR >> 8) & 0xFF);
|
||||
|
|
|
@ -1,18 +1,20 @@
|
|||
ifeq ($(RELEASE),1)
|
||||
BUILD_TYPE = "RELEASE"
|
||||
BUILD_TYPE = "RELEASE"
|
||||
else
|
||||
BUILD_TYPE = "DEBUG"
|
||||
BUILD_TYPE = "DEBUG"
|
||||
endif
|
||||
|
||||
ifneq ($(wildcard ../.git/HEAD),)
|
||||
obj/gitversion.h: ../VERSION ../.git/HEAD ../.git/index
|
||||
echo "const uint8_t gitversion[] = \"$(shell cat ../VERSION)-$(shell git rev-parse --short=8 HEAD)-$(BUILD_TYPE)\";" > $@
|
||||
SELF_DIR := $(dir $(lastword $(MAKEFILE_LIST)))
|
||||
|
||||
ifneq ($(wildcard $(SELF_DIR)/../.git/HEAD),)
|
||||
obj/gitversion.h: $(SELF_DIR)/../VERSION $(SELF_DIR)/../.git/HEAD $(SELF_DIR)/../.git/index
|
||||
echo "const uint8_t gitversion[] = \"$(shell cat $(SELF_DIR)/../VERSION)-$(BUILDER)-$(shell git rev-parse --short=8 HEAD)-$(BUILD_TYPE)\";" > $@
|
||||
else
|
||||
ifneq ($(wildcard ../../.git/modules/panda/HEAD),)
|
||||
obj/gitversion.h: ../VERSION ../../.git/modules/panda/HEAD ../../.git/modules/panda/index
|
||||
echo "const uint8_t gitversion[] = \"$(shell cat ../VERSION)-$(shell git rev-parse --short=8 HEAD)-$(BUILD_TYPE)\";" > $@
|
||||
ifneq ($(wildcard $(SELF_DIR)/../../.git/modules/panda/HEAD),)
|
||||
obj/gitversion.h: $(SELF_DIR)/../VERSION $(SELF_DIR)/../../.git/modules/panda/HEAD $(SELF_DIR)/../../.git/modules/panda/index
|
||||
echo "const uint8_t gitversion[] = \"$(shell cat $(SELF_DIR)/../VERSION)-$(BUILDER)-$(shell git rev-parse --short=8 HEAD)-$(BUILD_TYPE)\";" > $@
|
||||
else
|
||||
obj/gitversion.h: ../VERSION
|
||||
echo "const uint8_t gitversion[] = \"$(shell cat ../VERSION)-unknown-$(BUILD_TYPE)\";" > $@
|
||||
obj/gitversion.h: $(SELF_DIR)/../VERSION
|
||||
echo "const uint8_t gitversion[] = \"$(shell cat $(SELF_DIR)/../VERSION)-$(BUILDER)-unknown-$(BUILD_TYPE)\";" > $@
|
||||
endif
|
||||
endif
|
||||
|
|
|
@ -250,6 +250,7 @@ class Panda(object):
|
|||
pass
|
||||
|
||||
def flash(self, fn=None, code=None, reconnect=True):
|
||||
print("flash: main version is " + self.get_version())
|
||||
if not self.bootstub:
|
||||
self.reset(enter_bootstub=True)
|
||||
assert(self.bootstub)
|
||||
|
@ -270,7 +271,7 @@ class Panda(object):
|
|||
code = f.read()
|
||||
|
||||
# get version
|
||||
print("flash: version is "+self.get_version())
|
||||
print("flash: bootstub version is " + self.get_version())
|
||||
|
||||
# do flash
|
||||
Panda.flash_static(self._handle, code)
|
||||
|
|
|
@ -8,6 +8,8 @@ def ensure_st_up_to_date():
|
|||
with open(os.path.join(BASEDIR, "VERSION")) as f:
|
||||
repo_version = f.read()
|
||||
|
||||
repo_version += "-EON" if os.path.isfile('/EON') else "-DEV"
|
||||
|
||||
panda = None
|
||||
panda_dfu = None
|
||||
should_flash_recover = False
|
||||
|
@ -24,7 +26,7 @@ def ensure_st_up_to_date():
|
|||
if len(panda_dfu) > 0:
|
||||
panda_dfu = PandaDFU(panda_dfu[0])
|
||||
panda_dfu.recover()
|
||||
|
||||
|
||||
print "waiting for board..."
|
||||
time.sleep(1)
|
||||
|
||||
|
|
|
@ -30,25 +30,20 @@ typedef struct
|
|||
uint32_t CNT;
|
||||
} TIM_TypeDef;
|
||||
|
||||
void set_controls_allowed(int c);
|
||||
int get_controls_allowed(void);
|
||||
void set_timer(int t);
|
||||
void reset_angle_control(void);
|
||||
|
||||
void init_tests_toyota(void);
|
||||
void toyota_rx_hook(CAN_FIFOMailBox_TypeDef *to_push);
|
||||
int toyota_tx_hook(CAN_FIFOMailBox_TypeDef *to_send);
|
||||
void toyota_init(int16_t param);
|
||||
void set_controls_allowed(int c);
|
||||
void reset_angle_control(void);
|
||||
int get_controls_allowed(void);
|
||||
void init_tests_toyota(void);
|
||||
void set_timer(int t);
|
||||
void set_toyota_torque_meas(int min, int max);
|
||||
void set_cadillac_torque_driver(int min, int max);
|
||||
void set_gm_torque_driver(int min, int max);
|
||||
void set_hyundai_torque_driver(int min, int max);
|
||||
void set_chrysler_torque_meas(int min, int max);
|
||||
void set_toyota_rt_torque_last(int t);
|
||||
void set_toyota_desired_torque_last(int t);
|
||||
int get_toyota_torque_meas_min(void);
|
||||
int get_toyota_torque_meas_max(void);
|
||||
int get_chrysler_torque_meas_min(void);
|
||||
int get_chrysler_torque_meas_max(void);
|
||||
void set_toyota_torque_meas(int min, int max);
|
||||
void set_toyota_desired_torque_last(int t);
|
||||
void set_toyota_rt_torque_last(int t);
|
||||
|
||||
void init_tests_honda(void);
|
||||
int get_ego_speed(void);
|
||||
|
@ -66,6 +61,7 @@ void cadillac_rx_hook(CAN_FIFOMailBox_TypeDef *to_push);
|
|||
int cadillac_tx_hook(CAN_FIFOMailBox_TypeDef *to_send);
|
||||
void set_cadillac_desired_torque_last(int t);
|
||||
void set_cadillac_rt_torque_last(int t);
|
||||
void set_cadillac_torque_driver(int min, int max);
|
||||
|
||||
void init_tests_gm(void);
|
||||
void gm_init(int16_t param);
|
||||
|
@ -73,6 +69,7 @@ void gm_rx_hook(CAN_FIFOMailBox_TypeDef *to_push);
|
|||
int gm_tx_hook(CAN_FIFOMailBox_TypeDef *to_send);
|
||||
void set_gm_desired_torque_last(int t);
|
||||
void set_gm_rt_torque_last(int t);
|
||||
void set_gm_torque_driver(int min, int max);
|
||||
|
||||
void init_tests_hyundai(void);
|
||||
void nooutput_init(int16_t param);
|
||||
|
@ -80,6 +77,7 @@ void hyundai_rx_hook(CAN_FIFOMailBox_TypeDef *to_push);
|
|||
int hyundai_tx_hook(CAN_FIFOMailBox_TypeDef *to_send);
|
||||
void set_hyundai_desired_torque_last(int t);
|
||||
void set_hyundai_rt_torque_last(int t);
|
||||
void set_hyundai_torque_driver(int min, int max);
|
||||
|
||||
void toyota_ipas_rx_hook(CAN_FIFOMailBox_TypeDef *to_push);
|
||||
int toyota_ipas_tx_hook(CAN_FIFOMailBox_TypeDef *to_send);
|
||||
|
@ -89,6 +87,16 @@ void chrysler_rx_hook(CAN_FIFOMailBox_TypeDef *to_push);
|
|||
int chrysler_tx_hook(CAN_FIFOMailBox_TypeDef *to_send);
|
||||
void set_chrysler_desired_torque_last(int t);
|
||||
void set_chrysler_rt_torque_last(int t);
|
||||
int get_chrysler_torque_meas_min(void);
|
||||
int get_chrysler_torque_meas_max(void);
|
||||
void set_chrysler_torque_meas(int min, int max);
|
||||
|
||||
void init_tests_subaru(void);
|
||||
void subaru_rx_hook(CAN_FIFOMailBox_TypeDef *to_push);
|
||||
int subaru_tx_hook(CAN_FIFOMailBox_TypeDef *to_send);
|
||||
void set_subaru_desired_torque_last(int t);
|
||||
void set_subaru_rt_torque_last(int t);
|
||||
void set_subaru_torque_driver(int min, int max);
|
||||
|
||||
|
||||
""")
|
||||
|
|
|
@ -26,7 +26,8 @@ struct sample_t toyota_torque_meas;
|
|||
struct sample_t cadillac_torque_driver;
|
||||
struct sample_t gm_torque_driver;
|
||||
struct sample_t hyundai_torque_driver;
|
||||
struct sample_t chrysler_torque_driver;
|
||||
struct sample_t chrysler_torque_meas;
|
||||
struct sample_t subaru_torque_driver;
|
||||
|
||||
TIM_TypeDef timer;
|
||||
TIM_TypeDef *TIM2 = &timer;
|
||||
|
@ -87,6 +88,11 @@ void set_chrysler_torque_meas(int min, int max){
|
|||
chrysler_torque_meas.max = max;
|
||||
}
|
||||
|
||||
void set_subaru_torque_driver(int min, int max){
|
||||
subaru_torque_driver.min = min;
|
||||
subaru_torque_driver.max = max;
|
||||
}
|
||||
|
||||
int get_chrysler_torque_meas_min(void){
|
||||
return chrysler_torque_meas.min;
|
||||
}
|
||||
|
@ -123,6 +129,10 @@ void set_chrysler_rt_torque_last(int t){
|
|||
chrysler_rt_torque_last = t;
|
||||
}
|
||||
|
||||
void set_subaru_rt_torque_last(int t){
|
||||
subaru_rt_torque_last = t;
|
||||
}
|
||||
|
||||
void set_toyota_desired_torque_last(int t){
|
||||
toyota_desired_torque_last = t;
|
||||
}
|
||||
|
@ -143,6 +153,10 @@ void set_chrysler_desired_torque_last(int t){
|
|||
chrysler_desired_torque_last = t;
|
||||
}
|
||||
|
||||
void set_subaru_desired_torque_last(int t){
|
||||
subaru_desired_torque_last = t;
|
||||
}
|
||||
|
||||
int get_ego_speed(void){
|
||||
return ego_speed;
|
||||
}
|
||||
|
@ -200,14 +214,23 @@ void init_tests_hyundai(void){
|
|||
}
|
||||
|
||||
void init_tests_chrysler(void){
|
||||
chrysler_torque_driver.min = 0;
|
||||
chrysler_torque_driver.max = 0;
|
||||
chrysler_torque_meas.min = 0;
|
||||
chrysler_torque_meas.max = 0;
|
||||
chrysler_desired_torque_last = 0;
|
||||
chrysler_rt_torque_last = 0;
|
||||
chrysler_ts_last = 0;
|
||||
set_timer(0);
|
||||
}
|
||||
|
||||
void init_tests_subaru(void){
|
||||
subaru_torque_driver.min = 0;
|
||||
subaru_torque_driver.max = 0;
|
||||
subaru_desired_torque_last = 0;
|
||||
subaru_rt_torque_last = 0;
|
||||
subaru_ts_last = 0;
|
||||
set_timer(0);
|
||||
}
|
||||
|
||||
void init_tests_honda(void){
|
||||
ego_speed = 0;
|
||||
gas_interceptor_detected = 0;
|
||||
|
|
|
@ -1,4 +1,6 @@
|
|||
#!/usr/bin/env python2
|
||||
import csv
|
||||
import glob
|
||||
import unittest
|
||||
import numpy as np
|
||||
import libpandasafety_py
|
||||
|
@ -24,6 +26,11 @@ def sign(a):
|
|||
else:
|
||||
return -1
|
||||
|
||||
def swap_bytes(data_str):
|
||||
"""Accepts string with hex, returns integer with order swapped for CAN."""
|
||||
a = int(data_str, 16)
|
||||
return ((a & 0xff) << 24) + ((a & 0xff00) << 8) + ((a & 0x00ff0000) >> 8) + ((a & 0xff000000) >> 24)
|
||||
|
||||
class TestChryslerSafety(unittest.TestCase):
|
||||
@classmethod
|
||||
def setUp(cls):
|
||||
|
@ -166,6 +173,33 @@ class TestChryslerSafety(unittest.TestCase):
|
|||
self.assertEqual(0, self.safety.get_chrysler_torque_meas_max())
|
||||
self.assertEqual(0, self.safety.get_chrysler_torque_meas_min())
|
||||
|
||||
def _replay_drive(self, csv_reader):
|
||||
for row in csv_reader:
|
||||
if len(row) != 4: # sometimes truncated at end of the file
|
||||
continue
|
||||
if row[0] == 'time': # skip CSV header
|
||||
continue
|
||||
addr = int(row[1])
|
||||
bus = int(row[2])
|
||||
data_str = row[3] # Example '081407ff0806e06f'
|
||||
to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *')
|
||||
to_send[0].RIR = addr << 21
|
||||
to_send[0].RDHR = swap_bytes(data_str[8:])
|
||||
to_send[0].RDLR = swap_bytes(data_str[:8])
|
||||
if (bus == 128):
|
||||
self.assertTrue(self.safety.chrysler_tx_hook(to_send), msg=row)
|
||||
else:
|
||||
self.safety.chrysler_rx_hook(to_send)
|
||||
|
||||
def test_replay_drive(self):
|
||||
# In Cabana, click "Save Log" and then put the downloaded CSV in this directory.
|
||||
test_files = glob.glob('chrysler_*.csv')
|
||||
for filename in test_files:
|
||||
print 'testing %s' % filename
|
||||
with open(filename) as csvfile:
|
||||
reader = csv.reader(csvfile)
|
||||
self._replay_drive(reader)
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
unittest.main()
|
||||
|
|
|
@ -0,0 +1,170 @@
|
|||
#!/usr/bin/env python2
|
||||
import unittest
|
||||
import numpy as np
|
||||
import libpandasafety_py
|
||||
|
||||
MAX_RATE_UP = 50
|
||||
MAX_RATE_DOWN = 70
|
||||
MAX_STEER = 2047
|
||||
|
||||
MAX_RT_DELTA = 940
|
||||
RT_INTERVAL = 250000
|
||||
|
||||
DRIVER_TORQUE_ALLOWANCE = 60;
|
||||
DRIVER_TORQUE_FACTOR = 10;
|
||||
|
||||
def twos_comp(val, bits):
|
||||
if val >= 0:
|
||||
return val
|
||||
else:
|
||||
return (2**bits) + val
|
||||
|
||||
def sign(a):
|
||||
if a > 0:
|
||||
return 1
|
||||
else:
|
||||
return -1
|
||||
|
||||
class TestSubaruSafety(unittest.TestCase):
|
||||
@classmethod
|
||||
def setUp(cls):
|
||||
cls.safety = libpandasafety_py.libpandasafety
|
||||
cls.safety.nooutput_init(0)
|
||||
cls.safety.init_tests_subaru()
|
||||
|
||||
def _set_prev_torque(self, t):
|
||||
self.safety.set_subaru_desired_torque_last(t)
|
||||
self.safety.set_subaru_rt_torque_last(t)
|
||||
|
||||
def _torque_driver_msg(self, torque):
|
||||
to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *')
|
||||
to_send[0].RIR = 0x119 << 21
|
||||
|
||||
t = twos_comp(torque, 11)
|
||||
to_send[0].RDLR = ((t & 0x7FF) << 16)
|
||||
return to_send
|
||||
|
||||
def _torque_msg(self, torque):
|
||||
to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *')
|
||||
to_send[0].RIR = 0x122 << 21
|
||||
|
||||
t = twos_comp(torque, 13)
|
||||
to_send[0].RDLR = (t << 16)
|
||||
return to_send
|
||||
|
||||
def test_default_controls_not_allowed(self):
|
||||
self.assertFalse(self.safety.get_controls_allowed())
|
||||
|
||||
def test_enable_control_allowed_from_cruise(self):
|
||||
to_push = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *')
|
||||
to_push[0].RIR = 0x240 << 21
|
||||
to_push[0].RDHR = 1 << 9
|
||||
|
||||
self.safety.subaru_rx_hook(to_push)
|
||||
self.assertTrue(self.safety.get_controls_allowed())
|
||||
|
||||
def test_disable_control_allowed_from_cruise(self):
|
||||
to_push = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *')
|
||||
to_push[0].RIR = 0x240 << 21
|
||||
to_push[0].RDHR = 0
|
||||
|
||||
self.safety.set_controls_allowed(1)
|
||||
self.safety.subaru_rx_hook(to_push)
|
||||
self.assertFalse(self.safety.get_controls_allowed())
|
||||
|
||||
def test_steer_safety_check(self):
|
||||
for enabled in [0, 1]:
|
||||
for t in range(-3000, 3000):
|
||||
self.safety.set_controls_allowed(enabled)
|
||||
self._set_prev_torque(t)
|
||||
if abs(t) > MAX_STEER or (not enabled and abs(t) > 0):
|
||||
self.assertFalse(self.safety.subaru_tx_hook(self._torque_msg(t)))
|
||||
else:
|
||||
self.assertTrue(self.safety.subaru_tx_hook(self._torque_msg(t)))
|
||||
|
||||
def test_manually_enable_controls_allowed(self):
|
||||
self.safety.set_controls_allowed(1)
|
||||
self.assertTrue(self.safety.get_controls_allowed())
|
||||
self.safety.set_controls_allowed(0)
|
||||
self.assertFalse(self.safety.get_controls_allowed())
|
||||
|
||||
def test_non_realtime_limit_up(self):
|
||||
self.safety.set_subaru_torque_driver(0, 0)
|
||||
self.safety.set_controls_allowed(True)
|
||||
|
||||
self._set_prev_torque(0)
|
||||
self.assertTrue(self.safety.subaru_tx_hook(self._torque_msg(MAX_RATE_UP)))
|
||||
self._set_prev_torque(0)
|
||||
self.assertTrue(self.safety.subaru_tx_hook(self._torque_msg(-MAX_RATE_UP)))
|
||||
|
||||
self._set_prev_torque(0)
|
||||
self.assertFalse(self.safety.subaru_tx_hook(self._torque_msg(MAX_RATE_UP + 1)))
|
||||
self.safety.set_controls_allowed(True)
|
||||
self._set_prev_torque(0)
|
||||
self.assertFalse(self.safety.subaru_tx_hook(self._torque_msg(-MAX_RATE_UP - 1)))
|
||||
|
||||
def test_non_realtime_limit_down(self):
|
||||
self.safety.set_subaru_torque_driver(0, 0)
|
||||
self.safety.set_controls_allowed(True)
|
||||
|
||||
def test_against_torque_driver(self):
|
||||
self.safety.set_controls_allowed(True)
|
||||
|
||||
for sign in [-1, 1]:
|
||||
for t in np.arange(0, DRIVER_TORQUE_ALLOWANCE + 1, 1):
|
||||
t *= -sign
|
||||
self.safety.set_subaru_torque_driver(t, t)
|
||||
self._set_prev_torque(MAX_STEER * sign)
|
||||
self.assertTrue(self.safety.subaru_tx_hook(self._torque_msg(MAX_STEER * sign)))
|
||||
|
||||
self.safety.set_subaru_torque_driver(DRIVER_TORQUE_ALLOWANCE + 1, DRIVER_TORQUE_ALLOWANCE + 1)
|
||||
self.assertFalse(self.safety.subaru_tx_hook(self._torque_msg(-MAX_STEER)))
|
||||
|
||||
# spot check some individual cases
|
||||
for sign in [-1, 1]:
|
||||
driver_torque = (DRIVER_TORQUE_ALLOWANCE + 10) * sign
|
||||
torque_desired = (MAX_STEER - 10 * DRIVER_TORQUE_FACTOR) * sign
|
||||
delta = 1 * sign
|
||||
self._set_prev_torque(torque_desired)
|
||||
self.safety.set_subaru_torque_driver(-driver_torque, -driver_torque)
|
||||
self.assertTrue(self.safety.subaru_tx_hook(self._torque_msg(torque_desired)))
|
||||
self._set_prev_torque(torque_desired + delta)
|
||||
self.safety.set_subaru_torque_driver(-driver_torque, -driver_torque)
|
||||
self.assertFalse(self.safety.subaru_tx_hook(self._torque_msg(torque_desired + delta)))
|
||||
|
||||
self._set_prev_torque(MAX_STEER * sign)
|
||||
self.safety.set_subaru_torque_driver(-MAX_STEER * sign, -MAX_STEER * sign)
|
||||
self.assertTrue(self.safety.subaru_tx_hook(self._torque_msg((MAX_STEER - MAX_RATE_DOWN) * sign)))
|
||||
self._set_prev_torque(MAX_STEER * sign)
|
||||
self.safety.set_subaru_torque_driver(-MAX_STEER * sign, -MAX_STEER * sign)
|
||||
self.assertTrue(self.safety.subaru_tx_hook(self._torque_msg(0)))
|
||||
self._set_prev_torque(MAX_STEER * sign)
|
||||
self.safety.set_subaru_torque_driver(-MAX_STEER * sign, -MAX_STEER * sign)
|
||||
self.assertFalse(self.safety.subaru_tx_hook(self._torque_msg((MAX_STEER - MAX_RATE_DOWN + 1) * sign)))
|
||||
|
||||
|
||||
def test_realtime_limits(self):
|
||||
self.safety.set_controls_allowed(True)
|
||||
|
||||
for sign in [-1, 1]:
|
||||
self.safety.init_tests_subaru()
|
||||
self._set_prev_torque(0)
|
||||
self.safety.set_subaru_torque_driver(0, 0)
|
||||
for t in np.arange(0, MAX_RT_DELTA, 1):
|
||||
t *= sign
|
||||
self.assertTrue(self.safety.subaru_tx_hook(self._torque_msg(t)))
|
||||
self.assertFalse(self.safety.subaru_tx_hook(self._torque_msg(sign * (MAX_RT_DELTA + 1))))
|
||||
|
||||
self._set_prev_torque(0)
|
||||
for t in np.arange(0, MAX_RT_DELTA, 1):
|
||||
t *= sign
|
||||
self.assertTrue(self.safety.subaru_tx_hook(self._torque_msg(t)))
|
||||
|
||||
# Increase timer to update rt_torque_last
|
||||
self.safety.set_timer(RT_INTERVAL + 1)
|
||||
self.assertTrue(self.safety.subaru_tx_hook(self._torque_msg(sign * (MAX_RT_DELTA - 1))))
|
||||
self.assertTrue(self.safety.subaru_tx_hook(self._torque_msg(sign * (MAX_RT_DELTA + 1))))
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
unittest.main()
|
|
@ -119,6 +119,13 @@ class TestToyotaSafety(unittest.TestCase):
|
|||
to_send[0].RDLR = (a & 0xFF) << 8 | (a >> 8)
|
||||
return to_send
|
||||
|
||||
def _gas_msg(self, gas):
|
||||
to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *')
|
||||
to_send[0].RIR = 0x200 << 21
|
||||
to_send[0].RDLR = gas
|
||||
|
||||
return to_send
|
||||
|
||||
def test_default_controls_not_allowed(self):
|
||||
self.assertFalse(self.safety.get_controls_allowed())
|
||||
|
||||
|
@ -409,6 +416,13 @@ class TestToyotaSafety(unittest.TestCase):
|
|||
# reset no angle control at the end of the test
|
||||
self.safety.reset_angle_control()
|
||||
|
||||
def test_gas_safety_check(self):
|
||||
self.safety.set_controls_allowed(0)
|
||||
self.assertTrue(self.safety.honda_tx_hook(self._gas_msg(0x0000)))
|
||||
self.assertFalse(self.safety.honda_tx_hook(self._gas_msg(0x1000)))
|
||||
self.safety.set_controls_allowed(1)
|
||||
self.assertTrue(self.safety.honda_tx_hook(self._gas_msg(0x1000)))
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
unittest.main()
|
||||
|
|
|
@ -0,0 +1,21 @@
|
|||
#!/usr/bin/env python2
|
||||
|
||||
# This trims CAN message CSV files to just the messages relevant for Panda testing.
|
||||
# Usage:
|
||||
# cat input.csv | ./trim_csv.py > output.csv
|
||||
import fileinput
|
||||
|
||||
addr_to_keep = [544, 0x1f4, 0x292] # For Chrysler, update to the addresses that matter for you.
|
||||
|
||||
for line in fileinput.input():
|
||||
line = line.strip()
|
||||
cols = line.split(',')
|
||||
if len(cols) != 4:
|
||||
continue # malformed, such as at the end or every 60s.
|
||||
(_, addr, bus, _) = cols
|
||||
if (addr == 'addr'):
|
||||
continue
|
||||
if (int(bus) == 128): # Keep all messages sent by OpenPilot.
|
||||
print line
|
||||
elif (int(addr) in addr_to_keep):
|
||||
print line
|
|
@ -0,0 +1,89 @@
|
|||
Metadata-Version: 1.1
|
||||
Name: backports.ssl-match-hostname
|
||||
Version: 3.7.0.1
|
||||
Summary: The ssl.match_hostname() function from Python 3.5
|
||||
Home-page: http://bitbucket.org/brandon/backports.ssl_match_hostname
|
||||
Author: Toshio Kuratomi
|
||||
Author-email: toshio@fedoraproject.org
|
||||
License: Python Software Foundation License
|
||||
Description:
|
||||
The ssl.match_hostname() function from Python 3.7
|
||||
=================================================
|
||||
|
||||
The Secure Sockets Layer is only actually *secure*
|
||||
if you check the hostname in the certificate returned
|
||||
by the server to which you are connecting,
|
||||
and verify that it matches to hostname
|
||||
that you are trying to reach.
|
||||
|
||||
But the matching logic, defined in `RFC2818`_,
|
||||
can be a bit tricky to implement on your own.
|
||||
So the ``ssl`` package in the Standard Library of Python 3.2
|
||||
and greater now includes a ``match_hostname()`` function
|
||||
for performing this check instead of requiring every application
|
||||
to implement the check separately.
|
||||
|
||||
This backport brings ``match_hostname()`` to users
|
||||
of earlier versions of Python.
|
||||
Simply make this distribution a dependency of your package,
|
||||
and then use it like this::
|
||||
|
||||
from backports.ssl_match_hostname import match_hostname, CertificateError
|
||||
[...]
|
||||
sslsock = ssl.wrap_socket(sock, ssl_version=ssl.PROTOCOL_SSLv23,
|
||||
cert_reqs=ssl.CERT_REQUIRED, ca_certs=...)
|
||||
try:
|
||||
match_hostname(sslsock.getpeercert(), hostname)
|
||||
except CertificateError, ce:
|
||||
...
|
||||
|
||||
Brandon Craig Rhodes is merely the packager of this distribution;
|
||||
the actual code inside comes from Python 3.7 with small changes for
|
||||
portability.
|
||||
|
||||
|
||||
Requirements
|
||||
------------
|
||||
|
||||
* If you need to use this on Python versions earlier than 2.6 you will need to
|
||||
install the `ssl module`_. From Python 2.6 upwards ``ssl`` is included in
|
||||
the Python Standard Library so you do not need to install it separately.
|
||||
|
||||
.. _`ssl module`:: https://pypi.python.org/pypi/ssl
|
||||
|
||||
History
|
||||
-------
|
||||
|
||||
* This function was introduced in python-3.2
|
||||
* It was updated for python-3.4a1 for a CVE
|
||||
(backports-ssl_match_hostname-3.4.0.1)
|
||||
* It was updated from RFC2818 to RFC 6125 compliance in order to fix another
|
||||
security flaw for python-3.3.3 and python-3.4a5
|
||||
(backports-ssl_match_hostname-3.4.0.2)
|
||||
* It was updated in python-3.5 to handle IPAddresses in ServerAltName fields
|
||||
(something that backports.ssl_match_hostname will do if you also install the
|
||||
ipaddress library from pypi).
|
||||
* It was updated in python-3.7 to handle IPAddresses without the ipaddress library and dropped
|
||||
support for partial wildcards
|
||||
|
||||
.. _`ipaddress module`:: https://pypi.python.org/pypi/ipaddress
|
||||
|
||||
.. _RFC2818: http://tools.ietf.org/html/rfc2818.html
|
||||
|
||||
Platform: UNKNOWN
|
||||
Classifier: Development Status :: 5 - Production/Stable
|
||||
Classifier: License :: OSI Approved :: Python Software Foundation License
|
||||
Classifier: Programming Language :: Python :: 2.4
|
||||
Classifier: Programming Language :: Python :: 2.5
|
||||
Classifier: Programming Language :: Python :: 2.6
|
||||
Classifier: Programming Language :: Python :: 2.7
|
||||
Classifier: Programming Language :: Python :: 3
|
||||
Classifier: Programming Language :: Python :: 3.0
|
||||
Classifier: Programming Language :: Python :: 3.1
|
||||
Classifier: Programming Language :: Python :: 3.2
|
||||
Classifier: Programming Language :: Python :: 3.3
|
||||
Classifier: Programming Language :: Python :: 3.4
|
||||
Classifier: Programming Language :: Python :: 3.5
|
||||
Classifier: Programming Language :: Python :: 3.6
|
||||
Classifier: Programming Language :: Python :: 3.7
|
||||
Classifier: Topic :: Security :: Cryptography
|
|
@ -0,0 +1,8 @@
|
|||
README.txt
|
||||
setup.cfg
|
||||
backports/__init__.py
|
||||
backports.ssl_match_hostname.egg-info/PKG-INFO
|
||||
backports.ssl_match_hostname.egg-info/SOURCES.txt
|
||||
backports.ssl_match_hostname.egg-info/dependency_links.txt
|
||||
backports.ssl_match_hostname.egg-info/top_level.txt
|
||||
backports/ssl_match_hostname/__init__.py
|
|
@ -0,0 +1 @@
|
|||
|
|
@ -0,0 +1,8 @@
|
|||
../backports/__init__.py
|
||||
../backports/__init__.pyc
|
||||
../backports/ssl_match_hostname/__init__.py
|
||||
../backports/ssl_match_hostname/__init__.pyc
|
||||
PKG-INFO
|
||||
SOURCES.txt
|
||||
dependency_links.txt
|
||||
top_level.txt
|
|
@ -0,0 +1 @@
|
|||
backports
|
|
@ -0,0 +1,3 @@
|
|||
# This is a Python "namespace package" http://www.python.org/dev/peps/pep-0382/
|
||||
from pkgutil import extend_path
|
||||
__path__ = extend_path(__path__, __name__)
|
|
@ -0,0 +1,204 @@
|
|||
"""The match_hostname() function from Python 3.7.0, essential when using SSL."""
|
||||
|
||||
import sys
|
||||
import socket as _socket
|
||||
|
||||
try:
|
||||
# Divergence: Python-3.7+'s _ssl has this exception type but older Pythons do not
|
||||
from _ssl import SSLCertVerificationError
|
||||
CertificateError = SSLCertVerificationError
|
||||
except:
|
||||
class CertificateError(ValueError):
|
||||
pass
|
||||
|
||||
|
||||
__version__ = '3.7.0.1'
|
||||
|
||||
|
||||
# Divergence: Added to deal with ipaddess as bytes on python2
|
||||
def _to_text(obj):
|
||||
if isinstance(obj, str) and sys.version_info < (3,):
|
||||
obj = unicode(obj, encoding='ascii', errors='strict')
|
||||
elif sys.version_info >= (3,) and isinstance(obj, bytes):
|
||||
obj = str(obj, encoding='ascii', errors='strict')
|
||||
return obj
|
||||
|
||||
|
||||
def _to_bytes(obj):
|
||||
if isinstance(obj, str) and sys.version_info >= (3,):
|
||||
obj = bytes(obj, encoding='ascii', errors='strict')
|
||||
elif sys.version_info < (3,) and isinstance(obj, unicode):
|
||||
obj = obj.encode('ascii', 'strict')
|
||||
return obj
|
||||
|
||||
|
||||
def _dnsname_match(dn, hostname):
|
||||
"""Matching according to RFC 6125, section 6.4.3
|
||||
|
||||
- Hostnames are compared lower case.
|
||||
- For IDNA, both dn and hostname must be encoded as IDN A-label (ACE).
|
||||
- Partial wildcards like 'www*.example.org', multiple wildcards, sole
|
||||
wildcard or wildcards in labels other then the left-most label are not
|
||||
supported and a CertificateError is raised.
|
||||
- A wildcard must match at least one character.
|
||||
"""
|
||||
if not dn:
|
||||
return False
|
||||
|
||||
wildcards = dn.count('*')
|
||||
# speed up common case w/o wildcards
|
||||
if not wildcards:
|
||||
return dn.lower() == hostname.lower()
|
||||
|
||||
if wildcards > 1:
|
||||
# Divergence .format() to percent formatting for Python < 2.6
|
||||
raise CertificateError(
|
||||
"too many wildcards in certificate DNS name: %s" % repr(dn))
|
||||
|
||||
dn_leftmost, sep, dn_remainder = dn.partition('.')
|
||||
|
||||
if '*' in dn_remainder:
|
||||
# Only match wildcard in leftmost segment.
|
||||
# Divergence .format() to percent formatting for Python < 2.6
|
||||
raise CertificateError(
|
||||
"wildcard can only be present in the leftmost label: "
|
||||
"%s." % repr(dn))
|
||||
|
||||
if not sep:
|
||||
# no right side
|
||||
# Divergence .format() to percent formatting for Python < 2.6
|
||||
raise CertificateError(
|
||||
"sole wildcard without additional labels are not support: "
|
||||
"%s." % repr(dn))
|
||||
|
||||
if dn_leftmost != '*':
|
||||
# no partial wildcard matching
|
||||
# Divergence .format() to percent formatting for Python < 2.6
|
||||
raise CertificateError(
|
||||
"partial wildcards in leftmost label are not supported: "
|
||||
"%s." % repr(dn))
|
||||
|
||||
hostname_leftmost, sep, hostname_remainder = hostname.partition('.')
|
||||
if not hostname_leftmost or not sep:
|
||||
# wildcard must match at least one char
|
||||
return False
|
||||
return dn_remainder.lower() == hostname_remainder.lower()
|
||||
|
||||
|
||||
def _inet_paton(ipname):
|
||||
"""Try to convert an IP address to packed binary form
|
||||
|
||||
Supports IPv4 addresses on all platforms and IPv6 on platforms with IPv6
|
||||
support.
|
||||
"""
|
||||
# inet_aton() also accepts strings like '1'
|
||||
# Divergence: We make sure we have native string type for all python versions
|
||||
try:
|
||||
b_ipname = _to_bytes(ipname)
|
||||
except UnicodeError:
|
||||
raise ValueError("%s must be an all-ascii string." % repr(ipname))
|
||||
|
||||
# Set ipname in native string format
|
||||
if sys.version_info < (3,):
|
||||
n_ipname = b_ipname
|
||||
else:
|
||||
n_ipname = ipname
|
||||
|
||||
if n_ipname.count('.') == 3:
|
||||
try:
|
||||
return _socket.inet_aton(n_ipname)
|
||||
# Divergence: OSError on late python3. socket.error earlier.
|
||||
# Null bytes generate ValueError on python3(we want to raise
|
||||
# ValueError anyway), TypeError # earlier
|
||||
except (OSError, _socket.error, TypeError):
|
||||
pass
|
||||
|
||||
try:
|
||||
return _socket.inet_pton(_socket.AF_INET6, n_ipname)
|
||||
# Divergence: OSError on late python3. socket.error earlier.
|
||||
# Null bytes generate ValueError on python3(we want to raise
|
||||
# ValueError anyway), TypeError # earlier
|
||||
except (OSError, _socket.error, TypeError):
|
||||
# Divergence .format() to percent formatting for Python < 2.6
|
||||
raise ValueError("%s is neither an IPv4 nor an IP6 "
|
||||
"address." % repr(ipname))
|
||||
except AttributeError:
|
||||
# AF_INET6 not available
|
||||
pass
|
||||
|
||||
# Divergence .format() to percent formatting for Python < 2.6
|
||||
raise ValueError("%s is not an IPv4 address." % repr(ipname))
|
||||
|
||||
|
||||
def _ipaddress_match(ipname, host_ip):
|
||||
"""Exact matching of IP addresses.
|
||||
|
||||
RFC 6125 explicitly doesn't define an algorithm for this
|
||||
(section 1.7.2 - "Out of Scope").
|
||||
"""
|
||||
# OpenSSL may add a trailing newline to a subjectAltName's IP address
|
||||
ip = _inet_paton(ipname.rstrip())
|
||||
return ip == host_ip
|
||||
|
||||
|
||||
def match_hostname(cert, hostname):
|
||||
"""Verify that *cert* (in decoded format as returned by
|
||||
SSLSocket.getpeercert()) matches the *hostname*. RFC 2818 and RFC 6125
|
||||
rules are followed.
|
||||
|
||||
The function matches IP addresses rather than dNSNames if hostname is a
|
||||
valid ipaddress string. IPv4 addresses are supported on all platforms.
|
||||
IPv6 addresses are supported on platforms with IPv6 support (AF_INET6
|
||||
and inet_pton).
|
||||
|
||||
CertificateError is raised on failure. On success, the function
|
||||
returns nothing.
|
||||
"""
|
||||
if not cert:
|
||||
raise ValueError("empty or no certificate, match_hostname needs a "
|
||||
"SSL socket or SSL context with either "
|
||||
"CERT_OPTIONAL or CERT_REQUIRED")
|
||||
try:
|
||||
# Divergence: Deal with hostname as bytes
|
||||
host_ip = _inet_paton(_to_text(hostname))
|
||||
except ValueError:
|
||||
# Not an IP address (common case)
|
||||
host_ip = None
|
||||
except UnicodeError:
|
||||
# Divergence: Deal with hostname as byte strings.
|
||||
# IP addresses should be all ascii, so we consider it not
|
||||
# an IP address if this fails
|
||||
host_ip = None
|
||||
dnsnames = []
|
||||
san = cert.get('subjectAltName', ())
|
||||
for key, value in san:
|
||||
if key == 'DNS':
|
||||
if host_ip is None and _dnsname_match(value, hostname):
|
||||
return
|
||||
dnsnames.append(value)
|
||||
elif key == 'IP Address':
|
||||
if host_ip is not None and _ipaddress_match(value, host_ip):
|
||||
return
|
||||
dnsnames.append(value)
|
||||
if not dnsnames:
|
||||
# The subject is only checked when there is no dNSName entry
|
||||
# in subjectAltName
|
||||
for sub in cert.get('subject', ()):
|
||||
for key, value in sub:
|
||||
# XXX according to RFC 2818, the most specific Common Name
|
||||
# must be used.
|
||||
if key == 'commonName':
|
||||
if _dnsname_match(value, hostname):
|
||||
return
|
||||
dnsnames.append(value)
|
||||
if len(dnsnames) > 1:
|
||||
raise CertificateError("hostname %r "
|
||||
"doesn't match either of %s"
|
||||
% (hostname, ', '.join(map(repr, dnsnames))))
|
||||
elif len(dnsnames) == 1:
|
||||
raise CertificateError("hostname %r "
|
||||
"doesn't match %r"
|
||||
% (hostname, dnsnames[0]))
|
||||
else:
|
||||
raise CertificateError("no appropriate commonName or "
|
||||
"subjectAltName fields were found")
|
|
@ -0,0 +1,201 @@
|
|||
#!/usr/local/bin/python
|
||||
|
||||
import argparse
|
||||
import code
|
||||
import sys
|
||||
import threading
|
||||
import time
|
||||
import ssl
|
||||
|
||||
import six
|
||||
from six.moves.urllib.parse import urlparse
|
||||
|
||||
import websocket
|
||||
|
||||
try:
|
||||
import readline
|
||||
except ImportError:
|
||||
pass
|
||||
|
||||
|
||||
def get_encoding():
|
||||
encoding = getattr(sys.stdin, "encoding", "")
|
||||
if not encoding:
|
||||
return "utf-8"
|
||||
else:
|
||||
return encoding.lower()
|
||||
|
||||
|
||||
OPCODE_DATA = (websocket.ABNF.OPCODE_TEXT, websocket.ABNF.OPCODE_BINARY)
|
||||
ENCODING = get_encoding()
|
||||
|
||||
|
||||
class VAction(argparse.Action):
|
||||
|
||||
def __call__(self, parser, args, values, option_string=None):
|
||||
if values is None:
|
||||
values = "1"
|
||||
try:
|
||||
values = int(values)
|
||||
except ValueError:
|
||||
values = values.count("v") + 1
|
||||
setattr(args, self.dest, values)
|
||||
|
||||
|
||||
def parse_args():
|
||||
parser = argparse.ArgumentParser(description="WebSocket Simple Dump Tool")
|
||||
parser.add_argument("url", metavar="ws_url",
|
||||
help="websocket url. ex. ws://echo.websocket.org/")
|
||||
parser.add_argument("-p", "--proxy",
|
||||
help="proxy url. ex. http://127.0.0.1:8080")
|
||||
parser.add_argument("-v", "--verbose", default=0, nargs='?', action=VAction,
|
||||
dest="verbose",
|
||||
help="set verbose mode. If set to 1, show opcode. "
|
||||
"If set to 2, enable to trace websocket module")
|
||||
parser.add_argument("-n", "--nocert", action='store_true',
|
||||
help="Ignore invalid SSL cert")
|
||||
parser.add_argument("-r", "--raw", action="store_true",
|
||||
help="raw output")
|
||||
parser.add_argument("-s", "--subprotocols", nargs='*',
|
||||
help="Set subprotocols")
|
||||
parser.add_argument("-o", "--origin",
|
||||
help="Set origin")
|
||||
parser.add_argument("--eof-wait", default=0, type=int,
|
||||
help="wait time(second) after 'EOF' received.")
|
||||
parser.add_argument("-t", "--text",
|
||||
help="Send initial text")
|
||||
parser.add_argument("--timings", action="store_true",
|
||||
help="Print timings in seconds")
|
||||
parser.add_argument("--headers",
|
||||
help="Set custom headers. Use ',' as separator")
|
||||
|
||||
return parser.parse_args()
|
||||
|
||||
|
||||
class RawInput:
|
||||
|
||||
def raw_input(self, prompt):
|
||||
if six.PY3:
|
||||
line = input(prompt)
|
||||
else:
|
||||
line = raw_input(prompt)
|
||||
|
||||
if ENCODING and ENCODING != "utf-8" and not isinstance(line, six.text_type):
|
||||
line = line.decode(ENCODING).encode("utf-8")
|
||||
elif isinstance(line, six.text_type):
|
||||
line = line.encode("utf-8")
|
||||
|
||||
return line
|
||||
|
||||
|
||||
class InteractiveConsole(RawInput, code.InteractiveConsole):
|
||||
|
||||
def write(self, data):
|
||||
sys.stdout.write("\033[2K\033[E")
|
||||
# sys.stdout.write("\n")
|
||||
sys.stdout.write("\033[34m< " + data + "\033[39m")
|
||||
sys.stdout.write("\n> ")
|
||||
sys.stdout.flush()
|
||||
|
||||
def read(self):
|
||||
return self.raw_input("> ")
|
||||
|
||||
|
||||
class NonInteractive(RawInput):
|
||||
|
||||
def write(self, data):
|
||||
sys.stdout.write(data)
|
||||
sys.stdout.write("\n")
|
||||
sys.stdout.flush()
|
||||
|
||||
def read(self):
|
||||
return self.raw_input("")
|
||||
|
||||
|
||||
def main():
|
||||
start_time = time.time()
|
||||
args = parse_args()
|
||||
if args.verbose > 1:
|
||||
websocket.enableTrace(True)
|
||||
options = {}
|
||||
if args.proxy:
|
||||
p = urlparse(args.proxy)
|
||||
options["http_proxy_host"] = p.hostname
|
||||
options["http_proxy_port"] = p.port
|
||||
if args.origin:
|
||||
options["origin"] = args.origin
|
||||
if args.subprotocols:
|
||||
options["subprotocols"] = args.subprotocols
|
||||
opts = {}
|
||||
if args.nocert:
|
||||
opts = {"cert_reqs": ssl.CERT_NONE, "check_hostname": False}
|
||||
if args.headers:
|
||||
options['header'] = map(str.strip, args.headers.split(','))
|
||||
ws = websocket.create_connection(args.url, sslopt=opts, **options)
|
||||
if args.raw:
|
||||
console = NonInteractive()
|
||||
else:
|
||||
console = InteractiveConsole()
|
||||
print("Press Ctrl+C to quit")
|
||||
|
||||
def recv():
|
||||
try:
|
||||
frame = ws.recv_frame()
|
||||
except websocket.WebSocketException:
|
||||
return websocket.ABNF.OPCODE_CLOSE, None
|
||||
if not frame:
|
||||
raise websocket.WebSocketException("Not a valid frame %s" % frame)
|
||||
elif frame.opcode in OPCODE_DATA:
|
||||
return frame.opcode, frame.data
|
||||
elif frame.opcode == websocket.ABNF.OPCODE_CLOSE:
|
||||
ws.send_close()
|
||||
return frame.opcode, None
|
||||
elif frame.opcode == websocket.ABNF.OPCODE_PING:
|
||||
ws.pong(frame.data)
|
||||
return frame.opcode, frame.data
|
||||
|
||||
return frame.opcode, frame.data
|
||||
|
||||
def recv_ws():
|
||||
while True:
|
||||
opcode, data = recv()
|
||||
msg = None
|
||||
if six.PY3 and opcode == websocket.ABNF.OPCODE_TEXT and isinstance(data, bytes):
|
||||
data = str(data, "utf-8")
|
||||
if not args.verbose and opcode in OPCODE_DATA:
|
||||
msg = data
|
||||
elif args.verbose:
|
||||
msg = "%s: %s" % (websocket.ABNF.OPCODE_MAP.get(opcode), data)
|
||||
|
||||
if msg is not None:
|
||||
if args.timings:
|
||||
console.write(str(time.time() - start_time) + ": " + msg)
|
||||
else:
|
||||
console.write(msg)
|
||||
|
||||
if opcode == websocket.ABNF.OPCODE_CLOSE:
|
||||
break
|
||||
|
||||
thread = threading.Thread(target=recv_ws)
|
||||
thread.daemon = True
|
||||
thread.start()
|
||||
|
||||
if args.text:
|
||||
ws.send(args.text)
|
||||
|
||||
while True:
|
||||
try:
|
||||
message = console.read()
|
||||
ws.send(message)
|
||||
except KeyboardInterrupt:
|
||||
return
|
||||
except EOFError:
|
||||
time.sleep(args.eof_wait)
|
||||
return
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
try:
|
||||
main()
|
||||
except Exception as e:
|
||||
print(e)
|
|
@ -0,0 +1,187 @@
|
|||
Metadata-Version: 1.1
|
||||
Name: json-rpc
|
||||
Version: 1.12.1
|
||||
Summary: JSON-RPC transport implementation
|
||||
Home-page: https://github.com/pavlov99/json-rpc
|
||||
Author: Kirill Pavlov
|
||||
Author-email: k@p99.io
|
||||
License: MIT
|
||||
Description: json-rpc
|
||||
========
|
||||
|
||||
.. image:: https://circleci.com/gh/pavlov99/json-rpc/tree/master.svg?style=svg
|
||||
:target: https://circleci.com/gh/pavlov99/json-rpc/tree/master
|
||||
:alt: Build Status
|
||||
|
||||
.. image:: https://codecov.io/gh/pavlov99/json-rpc/branch/master/graph/badge.svg
|
||||
:target: https://codecov.io/gh/pavlov99/json-rpc
|
||||
:alt: Coverage Status
|
||||
|
||||
.. image:: https://readthedocs.org/projects/json-rpc/badge/?version=latest
|
||||
:target: http://json-rpc.readthedocs.io/en/latest/?badge=latest
|
||||
|
||||
.. image:: https://img.shields.io/pypi/v/json-rpc.svg
|
||||
:target: https://pypi.org/project/json-rpc/
|
||||
:alt: Latest PyPI version
|
||||
|
||||
.. image:: https://img.shields.io/pypi/pyversions/json-rpc.svg
|
||||
:target: https://pypi.org/project/json-rpc/
|
||||
:alt: Supported Python versions
|
||||
|
||||
.. image:: https://badges.gitter.im/pavlov99/json-rpc.svg
|
||||
:target: https://gitter.im/pavlov99/json-rpc
|
||||
:alt: Gitter
|
||||
|
||||
|
||||
.. image:: https://opencollective.com/json-rpc/tiers/backer/badge.svg?label=backer&color=brightgreen
|
||||
:target: https://opencollective.com/json-rpc
|
||||
:alt: Bakers
|
||||
|
||||
.. image:: https://opencollective.com/json-rpc/tiers/backer/badge.svg?label=sponsor&color=brightgreen
|
||||
:target: https://opencollective.com/json-rpc
|
||||
:alt: Sponsors
|
||||
|
||||
`JSON-RPC2.0 <http://www.jsonrpc.org/specification>`_ and `JSON-RPC1.0 <http://json-rpc.org/wiki/specification>`_ transport specification implementation.
|
||||
Supports Python 2.6+, Python 3.3+, PyPy. Has optional Django and Flask support. 200+ tests.
|
||||
|
||||
Features
|
||||
--------
|
||||
|
||||
This implementation does not have any transport functionality realization, only protocol.
|
||||
Any client or server implementation is easy based on current code, but requires transport libraries, such as requests, gevent or zmq, see `examples <https://github.com/pavlov99/json-rpc/tree/master/examples>`_.
|
||||
|
||||
- Vanilla Python, no dependencies.
|
||||
- 200+ tests for multiple edge cases.
|
||||
- Optional backend support for Django, Flask.
|
||||
- json-rpc 1.1 and 2.0 support.
|
||||
|
||||
Install
|
||||
-------
|
||||
|
||||
.. code-block:: python
|
||||
|
||||
pip install json-rpc
|
||||
|
||||
Tests
|
||||
-----
|
||||
|
||||
Quickstart
|
||||
^^^^^^^^^^
|
||||
This is an essential part of the library as there are a lot of edge cases in JSON-RPC standard. To manage a variety of supported python versions as well as optional backends json-rpc uses `tox`:
|
||||
|
||||
.. code-block:: bash
|
||||
|
||||
tox
|
||||
|
||||
.. TIP::
|
||||
During local development use your python version with tox runner. For example, if your are using Python 3.6 run `tox -e py36`. It is easier to develop functionality for specific version first and then expands it to all of the supported versions.
|
||||
|
||||
Continuous integration
|
||||
^^^^^^^^^^^^^^^^^^^^^^
|
||||
This project uses `CircleCI <https://circleci.com/>`_ for continuous integration. All of the python supported versions are managed via `tox.ini` and `.circleci/config.yml` files. Master branch test status is displayed on the badge in the beginning of this document.
|
||||
|
||||
Test matrix
|
||||
^^^^^^^^^^^
|
||||
json-rpc supports multiple python versions: 2.6+, 3.3+, pypy. This introduces difficulties with testing libraries and optional dependencies management. For example, python before version 3.3 does not support `mock` and there is a limited support for `unittest2`. Every dependency translates into *if-then* blocks in the source code and adds complexity to it. Hence, while cross-python support is a core feature of this library, cross-Django or cross-Flask support is limited. In general, json-rpc uses latest stable release which supports current python version. For example, python 2.6 is compatible with Django 1.6 and not compatible with any future versions.
|
||||
|
||||
Below is a testing matrix:
|
||||
|
||||
+--------+-------+-----------+--------+--------+
|
||||
| Python | mock | unittest | Django | Flask |
|
||||
+========+=======+===========+========+========+
|
||||
| 2.6 | 2.0.0 | unittest2 | 1.6 | 0.12.2 |
|
||||
+--------+-------+-----------+--------+--------+
|
||||
| 2.7 | 2.0.0 | | 1.11 | 0.12.2 |
|
||||
+--------+-------+-----------+--------+--------+
|
||||
| 3.3 | | | 1.11 | 0.12.2 |
|
||||
+--------+-------+-----------+--------+--------+
|
||||
| 3.4 | | | 1.11 | 0.12.2 |
|
||||
+--------+-------+-----------+--------+--------+
|
||||
| 3.5 | | | 1.11 | 0.12.2 |
|
||||
+--------+-------+-----------+--------+--------+
|
||||
| 3.6 | | | 1.11 | 0.12.2 |
|
||||
+--------+-------+-----------+--------+--------+
|
||||
| pypy | 2.0.0 | | 1.11 | 0.12.2 |
|
||||
+--------+-------+-----------+--------+--------+
|
||||
| pypy3 | | | 1.11 | 0.12.2 |
|
||||
+--------+-------+-----------+--------+--------+
|
||||
|
||||
Quickstart
|
||||
----------
|
||||
Server (uses `Werkzeug <http://werkzeug.pocoo.org/>`_)
|
||||
|
||||
.. code-block:: python
|
||||
|
||||
from werkzeug.wrappers import Request, Response
|
||||
from werkzeug.serving import run_simple
|
||||
|
||||
from jsonrpc import JSONRPCResponseManager, dispatcher
|
||||
|
||||
|
||||
@dispatcher.add_method
|
||||
def foobar(**kwargs):
|
||||
return kwargs["foo"] + kwargs["bar"]
|
||||
|
||||
|
||||
@Request.application
|
||||
def application(request):
|
||||
# Dispatcher is dictionary {<method_name>: callable}
|
||||
dispatcher["echo"] = lambda s: s
|
||||
dispatcher["add"] = lambda a, b: a + b
|
||||
|
||||
response = JSONRPCResponseManager.handle(
|
||||
request.data, dispatcher)
|
||||
return Response(response.json, mimetype='application/json')
|
||||
|
||||
|
||||
if __name__ == '__main__':
|
||||
run_simple('localhost', 4000, application)
|
||||
|
||||
Client (uses `requests <http://www.python-requests.org/en/latest/>`_)
|
||||
|
||||
.. code-block:: python
|
||||
|
||||
import requests
|
||||
import json
|
||||
|
||||
|
||||
def main():
|
||||
url = "http://localhost:4000/jsonrpc"
|
||||
headers = {'content-type': 'application/json'}
|
||||
|
||||
# Example echo method
|
||||
payload = {
|
||||
"method": "echo",
|
||||
"params": ["echome!"],
|
||||
"jsonrpc": "2.0",
|
||||
"id": 0,
|
||||
}
|
||||
response = requests.post(
|
||||
url, data=json.dumps(payload), headers=headers).json()
|
||||
|
||||
assert response["result"] == "echome!"
|
||||
assert response["jsonrpc"]
|
||||
assert response["id"] == 0
|
||||
|
||||
if __name__ == "__main__":
|
||||
main()
|
||||
|
||||
Competitors
|
||||
-----------
|
||||
There are `several libraries <http://en.wikipedia.org/wiki/JSON-RPC#Implementations>`_ implementing JSON-RPC protocol. List below represents python libraries, none of the supports python3. tinyrpc looks better than others.
|
||||
|
||||
Platform: UNKNOWN
|
||||
Classifier: Development Status :: 5 - Production/Stable
|
||||
Classifier: Environment :: Console
|
||||
Classifier: License :: OSI Approved :: MIT License
|
||||
Classifier: Natural Language :: English
|
||||
Classifier: Operating System :: OS Independent
|
||||
Classifier: Programming Language :: Python :: 2.6
|
||||
Classifier: Programming Language :: Python :: 2.7
|
||||
Classifier: Programming Language :: Python :: 3.3
|
||||
Classifier: Programming Language :: Python :: 3.4
|
||||
Classifier: Programming Language :: Python :: 3.5
|
||||
Classifier: Programming Language :: Python :: 3.6
|
||||
Classifier: Programming Language :: Python :: 3.7
|
||||
Classifier: Programming Language :: Python :: Implementation :: PyPy
|
||||
Classifier: Topic :: Software Development :: Libraries :: Python Modules
|
|
@ -0,0 +1,42 @@
|
|||
LICENSE.txt
|
||||
MANIFEST.in
|
||||
README.rst
|
||||
get-pip.py
|
||||
setup.cfg
|
||||
setup.py
|
||||
json_rpc.egg-info/PKG-INFO
|
||||
json_rpc.egg-info/SOURCES.txt
|
||||
json_rpc.egg-info/dependency_links.txt
|
||||
json_rpc.egg-info/top_level.txt
|
||||
jsonrpc/__init__.py
|
||||
jsonrpc/base.py
|
||||
jsonrpc/dispatcher.py
|
||||
jsonrpc/exceptions.py
|
||||
jsonrpc/jsonrpc.py
|
||||
jsonrpc/jsonrpc1.py
|
||||
jsonrpc/jsonrpc2.py
|
||||
jsonrpc/manager.py
|
||||
jsonrpc/six.py
|
||||
jsonrpc/utils.py
|
||||
jsonrpc/backend/__init__.py
|
||||
jsonrpc/backend/django.py
|
||||
jsonrpc/backend/flask.py
|
||||
jsonrpc/tests/__init__.py
|
||||
jsonrpc/tests/py35_utils.py
|
||||
jsonrpc/tests/test_base.py
|
||||
jsonrpc/tests/test_bug29.py
|
||||
jsonrpc/tests/test_dispatcher.py
|
||||
jsonrpc/tests/test_examples20.py
|
||||
jsonrpc/tests/test_jsonrpc.py
|
||||
jsonrpc/tests/test_jsonrpc1.py
|
||||
jsonrpc/tests/test_jsonrpc2.py
|
||||
jsonrpc/tests/test_jsonrpc_errors.py
|
||||
jsonrpc/tests/test_manager.py
|
||||
jsonrpc/tests/test_pep3107.py
|
||||
jsonrpc/tests/test_utils.py
|
||||
jsonrpc/tests/test_backend_django/__init__.py
|
||||
jsonrpc/tests/test_backend_django/settings.py
|
||||
jsonrpc/tests/test_backend_django/tests.py
|
||||
jsonrpc/tests/test_backend_django/urls.py
|
||||
jsonrpc/tests/test_backend_flask/__init__.py
|
||||
jsonrpc/tests/test_backend_flask/tests.py
|
|
@ -0,0 +1 @@
|
|||
|
|
@ -0,0 +1,68 @@
|
|||
../jsonrpc/__init__.py
|
||||
../jsonrpc/__init__.pyc
|
||||
../jsonrpc/backend/__init__.py
|
||||
../jsonrpc/backend/__init__.pyc
|
||||
../jsonrpc/backend/django.py
|
||||
../jsonrpc/backend/django.pyc
|
||||
../jsonrpc/backend/flask.py
|
||||
../jsonrpc/backend/flask.pyc
|
||||
../jsonrpc/base.py
|
||||
../jsonrpc/base.pyc
|
||||
../jsonrpc/dispatcher.py
|
||||
../jsonrpc/dispatcher.pyc
|
||||
../jsonrpc/exceptions.py
|
||||
../jsonrpc/exceptions.pyc
|
||||
../jsonrpc/jsonrpc.py
|
||||
../jsonrpc/jsonrpc.pyc
|
||||
../jsonrpc/jsonrpc1.py
|
||||
../jsonrpc/jsonrpc1.pyc
|
||||
../jsonrpc/jsonrpc2.py
|
||||
../jsonrpc/jsonrpc2.pyc
|
||||
../jsonrpc/manager.py
|
||||
../jsonrpc/manager.pyc
|
||||
../jsonrpc/six.py
|
||||
../jsonrpc/six.pyc
|
||||
../jsonrpc/tests/__init__.py
|
||||
../jsonrpc/tests/__init__.pyc
|
||||
../jsonrpc/tests/py35_utils.py
|
||||
../jsonrpc/tests/py35_utils.pyc
|
||||
../jsonrpc/tests/test_backend_django/__init__.py
|
||||
../jsonrpc/tests/test_backend_django/__init__.pyc
|
||||
../jsonrpc/tests/test_backend_django/settings.py
|
||||
../jsonrpc/tests/test_backend_django/settings.pyc
|
||||
../jsonrpc/tests/test_backend_django/tests.py
|
||||
../jsonrpc/tests/test_backend_django/tests.pyc
|
||||
../jsonrpc/tests/test_backend_django/urls.py
|
||||
../jsonrpc/tests/test_backend_django/urls.pyc
|
||||
../jsonrpc/tests/test_backend_flask/__init__.py
|
||||
../jsonrpc/tests/test_backend_flask/__init__.pyc
|
||||
../jsonrpc/tests/test_backend_flask/tests.py
|
||||
../jsonrpc/tests/test_backend_flask/tests.pyc
|
||||
../jsonrpc/tests/test_base.py
|
||||
../jsonrpc/tests/test_base.pyc
|
||||
../jsonrpc/tests/test_bug29.py
|
||||
../jsonrpc/tests/test_bug29.pyc
|
||||
../jsonrpc/tests/test_dispatcher.py
|
||||
../jsonrpc/tests/test_dispatcher.pyc
|
||||
../jsonrpc/tests/test_examples20.py
|
||||
../jsonrpc/tests/test_examples20.pyc
|
||||
../jsonrpc/tests/test_jsonrpc.py
|
||||
../jsonrpc/tests/test_jsonrpc.pyc
|
||||
../jsonrpc/tests/test_jsonrpc1.py
|
||||
../jsonrpc/tests/test_jsonrpc1.pyc
|
||||
../jsonrpc/tests/test_jsonrpc2.py
|
||||
../jsonrpc/tests/test_jsonrpc2.pyc
|
||||
../jsonrpc/tests/test_jsonrpc_errors.py
|
||||
../jsonrpc/tests/test_jsonrpc_errors.pyc
|
||||
../jsonrpc/tests/test_manager.py
|
||||
../jsonrpc/tests/test_manager.pyc
|
||||
../jsonrpc/tests/test_pep3107.py
|
||||
../jsonrpc/tests/test_pep3107.pyc
|
||||
../jsonrpc/tests/test_utils.py
|
||||
../jsonrpc/tests/test_utils.pyc
|
||||
../jsonrpc/utils.py
|
||||
../jsonrpc/utils.pyc
|
||||
PKG-INFO
|
||||
SOURCES.txt
|
||||
dependency_links.txt
|
||||
top_level.txt
|
|
@ -0,0 +1 @@
|
|||
jsonrpc
|
|
@ -0,0 +1,11 @@
|
|||
from .manager import JSONRPCResponseManager
|
||||
from .dispatcher import Dispatcher
|
||||
|
||||
__version = (1, 12, 1)
|
||||
|
||||
__version__ = version = '.'.join(map(str, __version))
|
||||
__project__ = PROJECT = __name__
|
||||
|
||||
dispatcher = Dispatcher()
|
||||
|
||||
# lint_ignore=W0611,W0401
|
|
@ -0,0 +1,89 @@
|
|||
from __future__ import absolute_import
|
||||
|
||||
from django.views.decorators.csrf import csrf_exempt
|
||||
from django.conf.urls import url
|
||||
from django.conf import settings
|
||||
from django.http import HttpResponse, HttpResponseNotAllowed
|
||||
import copy
|
||||
import json
|
||||
import logging
|
||||
import time
|
||||
|
||||
from ..exceptions import JSONRPCInvalidRequestException
|
||||
from ..jsonrpc import JSONRPCRequest
|
||||
from ..manager import JSONRPCResponseManager
|
||||
from ..utils import DatetimeDecimalEncoder
|
||||
from ..dispatcher import Dispatcher
|
||||
|
||||
|
||||
logger = logging.getLogger(__name__)
|
||||
|
||||
|
||||
def response_serialize(obj):
|
||||
""" Serializes response's data object to JSON. """
|
||||
return json.dumps(obj, cls=DatetimeDecimalEncoder)
|
||||
|
||||
|
||||
class JSONRPCAPI(object):
|
||||
def __init__(self, dispatcher=None):
|
||||
self.dispatcher = dispatcher if dispatcher is not None \
|
||||
else Dispatcher()
|
||||
|
||||
@property
|
||||
def urls(self):
|
||||
urls = [
|
||||
url(r'^$', self.jsonrpc, name='endpoint'),
|
||||
]
|
||||
|
||||
if getattr(settings, 'JSONRPC_MAP_VIEW_ENABLED', settings.DEBUG):
|
||||
urls.append(
|
||||
url(r'^map$', self.jsonrpc_map, name='map')
|
||||
)
|
||||
|
||||
return urls
|
||||
|
||||
@csrf_exempt
|
||||
def jsonrpc(self, request):
|
||||
""" JSON-RPC 2.0 handler."""
|
||||
if request.method != "POST":
|
||||
return HttpResponseNotAllowed(["POST"])
|
||||
|
||||
request_str = request.body.decode('utf8')
|
||||
try:
|
||||
jsonrpc_request = JSONRPCRequest.from_json(request_str)
|
||||
except (TypeError, ValueError, JSONRPCInvalidRequestException):
|
||||
response = JSONRPCResponseManager.handle(
|
||||
request_str, self.dispatcher)
|
||||
else:
|
||||
jsonrpc_request.params = jsonrpc_request.params or {}
|
||||
jsonrpc_request_params = copy.copy(jsonrpc_request.params)
|
||||
if isinstance(jsonrpc_request.params, dict):
|
||||
jsonrpc_request.params.update(request=request)
|
||||
|
||||
t1 = time.time()
|
||||
response = JSONRPCResponseManager.handle_request(
|
||||
jsonrpc_request, self.dispatcher)
|
||||
t2 = time.time()
|
||||
logger.info('{0}({1}) {2:.2f} sec'.format(
|
||||
jsonrpc_request.method, jsonrpc_request_params, t2 - t1))
|
||||
|
||||
if response:
|
||||
response.serialize = response_serialize
|
||||
response = response.json
|
||||
|
||||
return HttpResponse(response, content_type="application/json")
|
||||
|
||||
def jsonrpc_map(self, request):
|
||||
""" Map of json-rpc available calls.
|
||||
|
||||
:return str:
|
||||
|
||||
"""
|
||||
result = "<h1>JSON-RPC map</h1><pre>{0}</pre>".format("\n\n".join([
|
||||
"{0}: {1}".format(fname, f.__doc__)
|
||||
for fname, f in self.dispatcher.items()
|
||||
]))
|
||||
return HttpResponse(result)
|
||||
|
||||
|
||||
api = JSONRPCAPI()
|
|
@ -0,0 +1,85 @@
|
|||
from __future__ import absolute_import
|
||||
|
||||
import copy
|
||||
import json
|
||||
import logging
|
||||
import time
|
||||
from uuid import uuid4
|
||||
|
||||
from flask import Blueprint, request, Response
|
||||
|
||||
from ..exceptions import JSONRPCInvalidRequestException
|
||||
from ..jsonrpc import JSONRPCRequest
|
||||
from ..manager import JSONRPCResponseManager
|
||||
from ..utils import DatetimeDecimalEncoder
|
||||
from ..dispatcher import Dispatcher
|
||||
|
||||
|
||||
logger = logging.getLogger(__name__)
|
||||
|
||||
|
||||
class JSONRPCAPI(object):
|
||||
def __init__(self, dispatcher=None, check_content_type=True):
|
||||
"""
|
||||
|
||||
:param dispatcher: methods dispatcher
|
||||
:param check_content_type: if True - content-type must be
|
||||
"application/json"
|
||||
:return:
|
||||
|
||||
"""
|
||||
self.dispatcher = dispatcher if dispatcher is not None \
|
||||
else Dispatcher()
|
||||
self.check_content_type = check_content_type
|
||||
|
||||
def as_blueprint(self, name=None):
|
||||
blueprint = Blueprint(name if name else str(uuid4()), __name__)
|
||||
blueprint.add_url_rule(
|
||||
'/', view_func=self.jsonrpc, methods=['POST'])
|
||||
blueprint.add_url_rule(
|
||||
'/map', view_func=self.jsonrpc_map, methods=['GET'])
|
||||
return blueprint
|
||||
|
||||
def as_view(self):
|
||||
return self.jsonrpc
|
||||
|
||||
def jsonrpc(self):
|
||||
request_str = self._get_request_str()
|
||||
try:
|
||||
jsonrpc_request = JSONRPCRequest.from_json(request_str)
|
||||
except (TypeError, ValueError, JSONRPCInvalidRequestException):
|
||||
response = JSONRPCResponseManager.handle(
|
||||
request_str, self.dispatcher)
|
||||
else:
|
||||
response = JSONRPCResponseManager.handle_request(
|
||||
jsonrpc_request, self.dispatcher)
|
||||
|
||||
if response:
|
||||
response.serialize = self._serialize
|
||||
response = response.json
|
||||
|
||||
return Response(response, content_type="application/json")
|
||||
|
||||
def jsonrpc_map(self):
|
||||
""" Map of json-rpc available calls.
|
||||
|
||||
:return str:
|
||||
|
||||
"""
|
||||
result = "<h1>JSON-RPC map</h1><pre>{0}</pre>".format("\n\n".join([
|
||||
"{0}: {1}".format(fname, f.__doc__)
|
||||
for fname, f in self.dispatcher.items()
|
||||
]))
|
||||
return Response(result)
|
||||
|
||||
def _get_request_str(self):
|
||||
if self.check_content_type or request.data:
|
||||
return request.data
|
||||
return list(request.form.keys())[0]
|
||||
|
||||
@staticmethod
|
||||
def _serialize(s):
|
||||
return json.dumps(s, cls=DatetimeDecimalEncoder)
|
||||
|
||||
|
||||
api = JSONRPCAPI()
|
|
@ -0,0 +1,87 @@
|
|||
from .utils import JSONSerializable
|
||||
|
||||
|
||||
class JSONRPCBaseRequest(JSONSerializable):
|
||||
|
||||
""" Base class for JSON-RPC 1.0 and JSON-RPC 2.0 requests."""
|
||||
|
||||
def __init__(self, method=None, params=None, _id=None,
|
||||
is_notification=None):
|
||||
self.data = dict()
|
||||
self.method = method
|
||||
self.params = params
|
||||
self._id = _id
|
||||
self.is_notification = is_notification
|
||||
|
||||
@property
|
||||
def data(self):
|
||||
return self._data
|
||||
|
||||
@data.setter
|
||||
def data(self, value):
|
||||
if not isinstance(value, dict):
|
||||
raise ValueError("data should be dict")
|
||||
|
||||
self._data = value
|
||||
|
||||
@property
|
||||
def args(self):
|
||||
""" Method position arguments.
|
||||
|
||||
:return tuple args: method position arguments.
|
||||
|
||||
"""
|
||||
return tuple(self.params) if isinstance(self.params, list) else ()
|
||||
|
||||
@property
|
||||
def kwargs(self):
|
||||
""" Method named arguments.
|
||||
|
||||
:return dict kwargs: method named arguments.
|
||||
|
||||
"""
|
||||
return self.params if isinstance(self.params, dict) else {}
|
||||
|
||||
@property
|
||||
def json(self):
|
||||
return self.serialize(self.data)
|
||||
|
||||
|
||||
class JSONRPCBaseResponse(JSONSerializable):
|
||||
|
||||
""" Base class for JSON-RPC 1.0 and JSON-RPC 2.0 responses."""
|
||||
|
||||
def __init__(self, **kwargs):
|
||||
self.data = dict()
|
||||
|
||||
try:
|
||||
self.result = kwargs['result']
|
||||
except KeyError:
|
||||
pass
|
||||
|
||||
try:
|
||||
self.error = kwargs['error']
|
||||
except KeyError:
|
||||
pass
|
||||
|
||||
self._id = kwargs.get('_id')
|
||||
|
||||
if 'result' not in kwargs and 'error' not in kwargs:
|
||||
raise ValueError("Either result or error should be used")
|
||||
|
||||
self.request = None # type: JSONRPCBaseRequest
|
||||
|
||||
@property
|
||||
def data(self):
|
||||
return self._data
|
||||
|
||||
@data.setter
|
||||
def data(self, value):
|
||||
if not isinstance(value, dict):
|
||||
raise ValueError("data should be dict")
|
||||
|
||||
self._data = value
|
||||
|
||||
@property
|
||||
def json(self):
|
||||
return self.serialize(self.data)
|
|
@ -0,0 +1,132 @@
|
|||
""" Dispatcher is used to add methods (functions) to the server.
|
||||
|
||||
For usage examples see :meth:`Dispatcher.add_method`
|
||||
|
||||
"""
|
||||
import functools
|
||||
import collections
|
||||
|
||||
|
||||
class Dispatcher(collections.MutableMapping):
|
||||
|
||||
""" Dictionary like object which maps method_name to method."""
|
||||
|
||||
def __init__(self, prototype=None):
|
||||
""" Build method dispatcher.
|
||||
|
||||
Parameters
|
||||
----------
|
||||
prototype : object or dict, optional
|
||||
Initial method mapping.
|
||||
|
||||
Examples
|
||||
--------
|
||||
|
||||
Init object with method dictionary.
|
||||
|
||||
>>> Dispatcher({"sum": lambda a, b: a + b})
|
||||
None
|
||||
|
||||
"""
|
||||
self.method_map = dict()
|
||||
|
||||
if prototype is not None:
|
||||
self.build_method_map(prototype)
|
||||
|
||||
def __getitem__(self, key):
|
||||
return self.method_map[key]
|
||||
|
||||
def __setitem__(self, key, value):
|
||||
self.method_map[key] = value
|
||||
|
||||
def __delitem__(self, key):
|
||||
del self.method_map[key]
|
||||
|
||||
def __len__(self):
|
||||
return len(self.method_map)
|
||||
|
||||
def __iter__(self):
|
||||
return iter(self.method_map)
|
||||
|
||||
def __repr__(self):
|
||||
return repr(self.method_map)
|
||||
|
||||
def add_class(self, cls):
|
||||
prefix = cls.__name__.lower() + '.'
|
||||
self.build_method_map(cls(), prefix)
|
||||
|
||||
def add_object(self, obj):
|
||||
prefix = obj.__class__.__name__.lower() + '.'
|
||||
self.build_method_map(obj, prefix)
|
||||
|
||||
def add_dict(self, dict, prefix=''):
|
||||
if prefix:
|
||||
prefix += '.'
|
||||
self.build_method_map(dict, prefix)
|
||||
|
||||
def add_method(self, f=None, name=None):
|
||||
""" Add a method to the dispatcher.
|
||||
|
||||
Parameters
|
||||
----------
|
||||
f : callable
|
||||
Callable to be added.
|
||||
name : str, optional
|
||||
Name to register (the default is function **f** name)
|
||||
|
||||
Notes
|
||||
-----
|
||||
When used as a decorator keeps callable object unmodified.
|
||||
|
||||
Examples
|
||||
--------
|
||||
|
||||
Use as method
|
||||
|
||||
>>> d = Dispatcher()
|
||||
>>> d.add_method(lambda a, b: a + b, name="sum")
|
||||
<function __main__.<lambda>>
|
||||
|
||||
Or use as decorator
|
||||
|
||||
>>> d = Dispatcher()
|
||||
>>> @d.add_method
|
||||
def mymethod(*args, **kwargs):
|
||||
print(args, kwargs)
|
||||
|
||||
Or use as a decorator with a different function name
|
||||
>>> d = Dispatcher()
|
||||
>>> @d.add_method(name="my.method")
|
||||
def mymethod(*args, **kwargs):
|
||||
print(args, kwargs)
|
||||
|
||||
"""
|
||||
if name and not f:
|
||||
return functools.partial(self.add_method, name=name)
|
||||
|
||||
self.method_map[name or f.__name__] = f
|
||||
return f
|
||||
|
||||
def build_method_map(self, prototype, prefix=''):
|
||||
""" Add prototype methods to the dispatcher.
|
||||
|
||||
Parameters
|
||||
----------
|
||||
prototype : object or dict
|
||||
Initial method mapping.
|
||||
If given prototype is a dictionary then all callable objects will
|
||||
be added to dispatcher.
|
||||
If given prototype is an object then all public methods will
|
||||
be used.
|
||||
prefix: string, optional
|
||||
Prefix of methods
|
||||
|
||||
"""
|
||||
if not isinstance(prototype, dict):
|
||||
prototype = dict((method, getattr(prototype, method))
|
||||
for method in dir(prototype)
|
||||
if not method.startswith('_'))
|
||||
|
||||
for attr, method in prototype.items():
|
||||
if callable(method):
|
||||
self[prefix + attr] = method
|
|
@ -0,0 +1,185 @@
|
|||
""" JSON-RPC Exceptions."""
|
||||
from . import six
|
||||
import json
|
||||
|
||||
|
||||
class JSONRPCError(object):
|
||||
|
||||
""" Error for JSON-RPC communication.
|
||||
|
||||
When a rpc call encounters an error, the Response Object MUST contain the
|
||||
error member with a value that is a Object with the following members:
|
||||
|
||||
Parameters
|
||||
----------
|
||||
code: int
|
||||
A Number that indicates the error type that occurred.
|
||||
This MUST be an integer.
|
||||
The error codes from and including -32768 to -32000 are reserved for
|
||||
pre-defined errors. Any code within this range, but not defined
|
||||
explicitly below is reserved for future use. The error codes are nearly
|
||||
the same as those suggested for XML-RPC at the following
|
||||
url: http://xmlrpc-epi.sourceforge.net/specs/rfc.fault_codes.php
|
||||
|
||||
message: str
|
||||
A String providing a short description of the error.
|
||||
The message SHOULD be limited to a concise single sentence.
|
||||
|
||||
data: int or str or dict or list, optional
|
||||
A Primitive or Structured value that contains additional
|
||||
information about the error.
|
||||
This may be omitted.
|
||||
The value of this member is defined by the Server (e.g. detailed error
|
||||
information, nested errors etc.).
|
||||
|
||||
"""
|
||||
|
||||
serialize = staticmethod(json.dumps)
|
||||
deserialize = staticmethod(json.loads)
|
||||
|
||||
def __init__(self, code=None, message=None, data=None):
|
||||
self._data = dict()
|
||||
self.code = getattr(self.__class__, "CODE", code)
|
||||
self.message = getattr(self.__class__, "MESSAGE", message)
|
||||
self.data = data
|
||||
|
||||
def __get_code(self):
|
||||
return self._data["code"]
|
||||
|
||||
def __set_code(self, value):
|
||||
if not isinstance(value, six.integer_types):
|
||||
raise ValueError("Error code should be integer")
|
||||
|
||||
self._data["code"] = value
|
||||
|
||||
code = property(__get_code, __set_code)
|
||||
|
||||
def __get_message(self):
|
||||
return self._data["message"]
|
||||
|
||||
def __set_message(self, value):
|
||||
if not isinstance(value, six.string_types):
|
||||
raise ValueError("Error message should be string")
|
||||
|
||||
self._data["message"] = value
|
||||
|
||||
message = property(__get_message, __set_message)
|
||||
|
||||
def __get_data(self):
|
||||
return self._data.get("data")
|
||||
|
||||
def __set_data(self, value):
|
||||
if value is not None:
|
||||
self._data["data"] = value
|
||||
|
||||
data = property(__get_data, __set_data)
|
||||
|
||||
@classmethod
|
||||
def from_json(cls, json_str):
|
||||
data = cls.deserialize(json_str)
|
||||
return cls(
|
||||
code=data["code"], message=data["message"], data=data.get("data"))
|
||||
|
||||
@property
|
||||
def json(self):
|
||||
return self.serialize(self._data)
|
||||
|
||||
|
||||
class JSONRPCParseError(JSONRPCError):
|
||||
|
||||
""" Parse Error.
|
||||
|
||||
Invalid JSON was received by the server.
|
||||
An error occurred on the server while parsing the JSON text.
|
||||
|
||||
"""
|
||||
|
||||
CODE = -32700
|
||||
MESSAGE = "Parse error"
|
||||
|
||||
|
||||
class JSONRPCInvalidRequest(JSONRPCError):
|
||||
|
||||
""" Invalid Request.
|
||||
|
||||
The JSON sent is not a valid Request object.
|
||||
|
||||
"""
|
||||
|
||||
CODE = -32600
|
||||
MESSAGE = "Invalid Request"
|
||||
|
||||
|
||||
class JSONRPCMethodNotFound(JSONRPCError):
|
||||
|
||||
""" Method not found.
|
||||
|
||||
The method does not exist / is not available.
|
||||
|
||||
"""
|
||||
|
||||
CODE = -32601
|
||||
MESSAGE = "Method not found"
|
||||
|
||||
|
||||
class JSONRPCInvalidParams(JSONRPCError):
|
||||
|
||||
""" Invalid params.
|
||||
|
||||
Invalid method parameter(s).
|
||||
|
||||
"""
|
||||
|
||||
CODE = -32602
|
||||
MESSAGE = "Invalid params"
|
||||
|
||||
|
||||
class JSONRPCInternalError(JSONRPCError):
|
||||
|
||||
""" Internal error.
|
||||
|
||||
Internal JSON-RPC error.
|
||||
|
||||
"""
|
||||
|
||||
CODE = -32603
|
||||
MESSAGE = "Internal error"
|
||||
|
||||
|
||||
class JSONRPCServerError(JSONRPCError):
|
||||
|
||||
""" Server error.
|
||||
|
||||
Reserved for implementation-defined server-errors.
|
||||
|
||||
"""
|
||||
|
||||
CODE = -32000
|
||||
MESSAGE = "Server error"
|
||||
|
||||
|
||||
class JSONRPCException(Exception):
|
||||
|
||||
""" JSON-RPC Exception."""
|
||||
|
||||
pass
|
||||
|
||||
|
||||
class JSONRPCInvalidRequestException(JSONRPCException):
|
||||
|
||||
""" Request is not valid."""
|
||||
|
||||
pass
|
||||
|
||||
|
||||
class JSONRPCDispatchException(JSONRPCException):
|
||||
|
||||
""" JSON-RPC Dispatch Exception.
|
||||
|
||||
Should be thrown in dispatch methods.
|
||||
|
||||
"""
|
||||
|
||||
def __init__(self, code=None, message=None, data=None, *args, **kwargs):
|
||||
super(JSONRPCDispatchException, self).__init__(args, kwargs)
|
||||
self.error = JSONRPCError(code=code, data=data, message=message)
|
|
@ -0,0 +1,28 @@
|
|||
""" JSON-RPC wrappers for version 1.0 and 2.0.
|
||||
|
||||
Objects diring init operation try to choose JSON-RPC 2.0 and in case of error
|
||||
JSON-RPC 1.0.
|
||||
from_json methods could decide what format is it by presence of 'jsonrpc'
|
||||
attribute.
|
||||
|
||||
"""
|
||||
from .utils import JSONSerializable
|
||||
from .jsonrpc1 import JSONRPC10Request
|
||||
from .jsonrpc2 import JSONRPC20Request
|
||||
|
||||
|
||||
class JSONRPCRequest(JSONSerializable):
|
||||
|
||||
""" JSONRPC Request."""
|
||||
|
||||
@classmethod
|
||||
def from_json(cls, json_str):
|
||||
data = cls.deserialize(json_str)
|
||||
return cls.from_data(data)
|
||||
|
||||
@classmethod
|
||||
def from_data(cls, data):
|
||||
if isinstance(data, dict) and "jsonrpc" not in data:
|
||||
return JSONRPC10Request.from_data(data)
|
||||
else:
|
||||
return JSONRPC20Request.from_data(data)
|
|
@ -0,0 +1,151 @@
|
|||
from . import six
|
||||
|
||||
from .base import JSONRPCBaseRequest, JSONRPCBaseResponse
|
||||
from .exceptions import JSONRPCInvalidRequestException, JSONRPCError
|
||||
|
||||
|
||||
class JSONRPC10Request(JSONRPCBaseRequest):
|
||||
|
||||
""" JSON-RPC 1.0 Request.
|
||||
|
||||
A remote method is invoked by sending a request to a remote service.
|
||||
The request is a single object serialized using json.
|
||||
|
||||
:param str method: The name of the method to be invoked.
|
||||
:param list params: An Array of objects to pass as arguments to the method.
|
||||
:param _id: This can be of any type. It is used to match the response with
|
||||
the request that it is replying to.
|
||||
:param bool is_notification: whether request notification or not.
|
||||
|
||||
"""
|
||||
|
||||
JSONRPC_VERSION = "1.0"
|
||||
REQUIRED_FIELDS = set(["method", "params", "id"])
|
||||
POSSIBLE_FIELDS = set(["method", "params", "id"])
|
||||
|
||||
@property
|
||||
def data(self):
|
||||
data = dict((k, v) for k, v in self._data.items())
|
||||
data["id"] = None if self.is_notification else data["id"]
|
||||
return data
|
||||
|
||||
@data.setter
|
||||
def data(self, value):
|
||||
if not isinstance(value, dict):
|
||||
raise ValueError("data should be dict")
|
||||
|
||||
self._data = value
|
||||
|
||||
@property
|
||||
def method(self):
|
||||
return self._data.get("method")
|
||||
|
||||
@method.setter
|
||||
def method(self, value):
|
||||
if not isinstance(value, six.string_types):
|
||||
raise ValueError("Method should be string")
|
||||
|
||||
self._data["method"] = str(value)
|
||||
|
||||
@property
|
||||
def params(self):
|
||||
return self._data.get("params")
|
||||
|
||||
@params.setter
|
||||
def params(self, value):
|
||||
if not isinstance(value, (list, tuple)):
|
||||
raise ValueError("Incorrect params {0}".format(value))
|
||||
|
||||
self._data["params"] = list(value)
|
||||
|
||||
@property
|
||||
def _id(self):
|
||||
return self._data.get("id")
|
||||
|
||||
@_id.setter
|
||||
def _id(self, value):
|
||||
self._data["id"] = value
|
||||
|
||||
@property
|
||||
def is_notification(self):
|
||||
return self._data["id"] is None or self._is_notification
|
||||
|
||||
@is_notification.setter
|
||||
def is_notification(self, value):
|
||||
if value is None:
|
||||
value = self._id is None
|
||||
|
||||
if self._id is None and not value:
|
||||
raise ValueError("Can not set attribute is_notification. " +
|
||||
"Request id should not be None")
|
||||
|
||||
self._is_notification = value
|
||||
|
||||
@classmethod
|
||||
def from_json(cls, json_str):
|
||||
data = cls.deserialize(json_str)
|
||||
return cls.from_data(data)
|
||||
|
||||
@classmethod
|
||||
def from_data(cls, data):
|
||||
if not isinstance(data, dict):
|
||||
raise ValueError("data should be dict")
|
||||
|
||||
if cls.REQUIRED_FIELDS <= set(data.keys()) <= cls.POSSIBLE_FIELDS:
|
||||
return cls(
|
||||
method=data["method"], params=data["params"], _id=data["id"]
|
||||
)
|
||||
else:
|
||||
extra = set(data.keys()) - cls.POSSIBLE_FIELDS
|
||||
missed = cls.REQUIRED_FIELDS - set(data.keys())
|
||||
msg = "Invalid request. Extra fields: {0}, Missed fields: {1}"
|
||||
raise JSONRPCInvalidRequestException(msg.format(extra, missed))
|
||||
|
||||
|
||||
class JSONRPC10Response(JSONRPCBaseResponse):
|
||||
|
||||
JSONRPC_VERSION = "1.0"
|
||||
|
||||
@property
|
||||
def data(self):
|
||||
data = dict((k, v) for k, v in self._data.items())
|
||||
return data
|
||||
|
||||
@data.setter
|
||||
def data(self, value):
|
||||
if not isinstance(value, dict):
|
||||
raise ValueError("data should be dict")
|
||||
|
||||
self._data = value
|
||||
|
||||
@property
|
||||
def result(self):
|
||||
return self._data.get("result")
|
||||
|
||||
@result.setter
|
||||
def result(self, value):
|
||||
if self.error:
|
||||
raise ValueError("Either result or error should be used")
|
||||
self._data["result"] = value
|
||||
|
||||
@property
|
||||
def error(self):
|
||||
return self._data.get("error")
|
||||
|
||||
@error.setter
|
||||
def error(self, value):
|
||||
self._data.pop('value', None)
|
||||
if value:
|
||||
self._data["error"] = value
|
||||
# Test error
|
||||
JSONRPCError(**value)
|
||||
|
||||
@property
|
||||
def _id(self):
|
||||
return self._data.get("id")
|
||||
|
||||
@_id.setter
|
||||
def _id(self, value):
|
||||
if value is None:
|
||||
raise ValueError("id could not be null for JSON-RPC1.0 Response")
|
||||
self._data["id"] = value
|
|
@ -0,0 +1,267 @@
|
|||
from . import six
|
||||
import json
|
||||
|
||||
from .exceptions import JSONRPCError, JSONRPCInvalidRequestException
|
||||
from .base import JSONRPCBaseRequest, JSONRPCBaseResponse
|
||||
|
||||
|
||||
class JSONRPC20Request(JSONRPCBaseRequest):
|
||||
|
||||
""" A rpc call is represented by sending a Request object to a Server.
|
||||
|
||||
:param str method: A String containing the name of the method to be
|
||||
invoked. Method names that begin with the word rpc followed by a
|
||||
period character (U+002E or ASCII 46) are reserved for rpc-internal
|
||||
methods and extensions and MUST NOT be used for anything else.
|
||||
|
||||
:param params: A Structured value that holds the parameter values to be
|
||||
used during the invocation of the method. This member MAY be omitted.
|
||||
:type params: iterable or dict
|
||||
|
||||
:param _id: An identifier established by the Client that MUST contain a
|
||||
String, Number, or NULL value if included. If it is not included it is
|
||||
assumed to be a notification. The value SHOULD normally not be Null
|
||||
[1] and Numbers SHOULD NOT contain fractional parts [2].
|
||||
:type _id: str or int or None
|
||||
|
||||
:param bool is_notification: Whether request is notification or not. If
|
||||
value is True, _id is not included to request. It allows to create
|
||||
requests with id = null.
|
||||
|
||||
The Server MUST reply with the same value in the Response object if
|
||||
included. This member is used to correlate the context between the two
|
||||
objects.
|
||||
|
||||
[1] The use of Null as a value for the id member in a Request object is
|
||||
discouraged, because this specification uses a value of Null for Responses
|
||||
with an unknown id. Also, because JSON-RPC 1.0 uses an id value of Null
|
||||
for Notifications this could cause confusion in handling.
|
||||
|
||||
[2] Fractional parts may be problematic, since many decimal fractions
|
||||
cannot be represented exactly as binary fractions.
|
||||
|
||||
"""
|
||||
|
||||
JSONRPC_VERSION = "2.0"
|
||||
REQUIRED_FIELDS = set(["jsonrpc", "method"])
|
||||
POSSIBLE_FIELDS = set(["jsonrpc", "method", "params", "id"])
|
||||
|
||||
@property
|
||||
def data(self):
|
||||
data = dict(
|
||||
(k, v) for k, v in self._data.items()
|
||||
if not (k == "id" and self.is_notification)
|
||||
)
|
||||
data["jsonrpc"] = self.JSONRPC_VERSION
|
||||
return data
|
||||
|
||||
@data.setter
|
||||
def data(self, value):
|
||||
if not isinstance(value, dict):
|
||||
raise ValueError("data should be dict")
|
||||
|
||||
self._data = value
|
||||
|
||||
@property
|
||||
def method(self):
|
||||
return self._data.get("method")
|
||||
|
||||
@method.setter
|
||||
def method(self, value):
|
||||
if not isinstance(value, six.string_types):
|
||||
raise ValueError("Method should be string")
|
||||
|
||||
if value.startswith("rpc."):
|
||||
raise ValueError(
|
||||
"Method names that begin with the word rpc followed by a " +
|
||||
"period character (U+002E or ASCII 46) are reserved for " +
|
||||
"rpc-internal methods and extensions and MUST NOT be used " +
|
||||
"for anything else.")
|
||||
|
||||
self._data["method"] = str(value)
|
||||
|
||||
@property
|
||||
def params(self):
|
||||
return self._data.get("params")
|
||||
|
||||
@params.setter
|
||||
def params(self, value):
|
||||
if value is not None and not isinstance(value, (list, tuple, dict)):
|
||||
raise ValueError("Incorrect params {0}".format(value))
|
||||
|
||||
value = list(value) if isinstance(value, tuple) else value
|
||||
|
||||
if value is not None:
|
||||
self._data["params"] = value
|
||||
|
||||
@property
|
||||
def _id(self):
|
||||
return self._data.get("id")
|
||||
|
||||
@_id.setter
|
||||
def _id(self, value):
|
||||
if value is not None and \
|
||||
not isinstance(value, six.string_types + six.integer_types):
|
||||
raise ValueError("id should be string or integer")
|
||||
|
||||
self._data["id"] = value
|
||||
|
||||
@classmethod
|
||||
def from_json(cls, json_str):
|
||||
data = cls.deserialize(json_str)
|
||||
return cls.from_data(data)
|
||||
|
||||
@classmethod
|
||||
def from_data(cls, data):
|
||||
is_batch = isinstance(data, list)
|
||||
data = data if is_batch else [data]
|
||||
|
||||
if not data:
|
||||
raise JSONRPCInvalidRequestException("[] value is not accepted")
|
||||
|
||||
if not all(isinstance(d, dict) for d in data):
|
||||
raise JSONRPCInvalidRequestException(
|
||||
"Each request should be an object (dict)")
|
||||
|
||||
result = []
|
||||
for d in data:
|
||||
if not cls.REQUIRED_FIELDS <= set(d.keys()) <= cls.POSSIBLE_FIELDS:
|
||||
extra = set(d.keys()) - cls.POSSIBLE_FIELDS
|
||||
missed = cls.REQUIRED_FIELDS - set(d.keys())
|
||||
msg = "Invalid request. Extra fields: {0}, Missed fields: {1}"
|
||||
raise JSONRPCInvalidRequestException(msg.format(extra, missed))
|
||||
|
||||
try:
|
||||
result.append(JSONRPC20Request(
|
||||
method=d["method"], params=d.get("params"),
|
||||
_id=d.get("id"), is_notification="id" not in d,
|
||||
))
|
||||
except ValueError as e:
|
||||
raise JSONRPCInvalidRequestException(str(e))
|
||||
|
||||
return JSONRPC20BatchRequest(*result) if is_batch else result[0]
|
||||
|
||||
|
||||
class JSONRPC20BatchRequest(object):
|
||||
|
||||
""" Batch JSON-RPC 2.0 Request.
|
||||
|
||||
:param JSONRPC20Request *requests: requests
|
||||
|
||||
"""
|
||||
|
||||
JSONRPC_VERSION = "2.0"
|
||||
|
||||
def __init__(self, *requests):
|
||||
self.requests = requests
|
||||
|
||||
@classmethod
|
||||
def from_json(cls, json_str):
|
||||
return JSONRPC20Request.from_json(json_str)
|
||||
|
||||
@property
|
||||
def json(self):
|
||||
return json.dumps([r.data for r in self.requests])
|
||||
|
||||
def __iter__(self):
|
||||
return iter(self.requests)
|
||||
|
||||
|
||||
class JSONRPC20Response(JSONRPCBaseResponse):
|
||||
|
||||
""" JSON-RPC response object to JSONRPC20Request.
|
||||
|
||||
When a rpc call is made, the Server MUST reply with a Response, except for
|
||||
in the case of Notifications. The Response is expressed as a single JSON
|
||||
Object, with the following members:
|
||||
|
||||
:param str jsonrpc: A String specifying the version of the JSON-RPC
|
||||
protocol. MUST be exactly "2.0".
|
||||
|
||||
:param result: This member is REQUIRED on success.
|
||||
This member MUST NOT exist if there was an error invoking the method.
|
||||
The value of this member is determined by the method invoked on the
|
||||
Server.
|
||||
|
||||
:param dict error: This member is REQUIRED on error.
|
||||
This member MUST NOT exist if there was no error triggered during
|
||||
invocation. The value for this member MUST be an Object.
|
||||
|
||||
:param id: This member is REQUIRED.
|
||||
It MUST be the same as the value of the id member in the Request
|
||||
Object. If there was an error in detecting the id in the Request
|
||||
object (e.g. Parse error/Invalid Request), it MUST be Null.
|
||||
:type id: str or int or None
|
||||
|
||||
Either the result member or error member MUST be included, but both
|
||||
members MUST NOT be included.
|
||||
|
||||
"""
|
||||
|
||||
JSONRPC_VERSION = "2.0"
|
||||
|
||||
@property
|
||||
def data(self):
|
||||
data = dict((k, v) for k, v in self._data.items())
|
||||
data["jsonrpc"] = self.JSONRPC_VERSION
|
||||
return data
|
||||
|
||||
@data.setter
|
||||
def data(self, value):
|
||||
if not isinstance(value, dict):
|
||||
raise ValueError("data should be dict")
|
||||
self._data = value
|
||||
|
||||
@property
|
||||
def result(self):
|
||||
return self._data.get("result")
|
||||
|
||||
@result.setter
|
||||
def result(self, value):
|
||||
if self.error:
|
||||
raise ValueError("Either result or error should be used")
|
||||
self._data["result"] = value
|
||||
|
||||
@property
|
||||
def error(self):
|
||||
return self._data.get("error")
|
||||
|
||||
@error.setter
|
||||
def error(self, value):
|
||||
self._data.pop('value', None)
|
||||
if value:
|
||||
self._data["error"] = value
|
||||
# Test error
|
||||
JSONRPCError(**value)
|
||||
|
||||
@property
|
||||
def _id(self):
|
||||
return self._data.get("id")
|
||||
|
||||
@_id.setter
|
||||
def _id(self, value):
|
||||
if value is not None and \
|
||||
not isinstance(value, six.string_types + six.integer_types):
|
||||
raise ValueError("id should be string or integer")
|
||||
|
||||
self._data["id"] = value
|
||||
|
||||
|
||||
class JSONRPC20BatchResponse(object):
|
||||
|
||||
JSONRPC_VERSION = "2.0"
|
||||
|
||||
def __init__(self, *responses):
|
||||
self.responses = responses
|
||||
self.request = None # type: JSONRPC20BatchRequest
|
||||
|
||||
@property
|
||||
def data(self):
|
||||
return [r.data for r in self.responses]
|
||||
|
||||
@property
|
||||
def json(self):
|
||||
return json.dumps(self.data)
|
||||
|
||||
def __iter__(self):
|
||||
return iter(self.responses)
|
|
@ -0,0 +1,136 @@
|
|||
import json
|
||||
import logging
|
||||
from .utils import is_invalid_params
|
||||
from .exceptions import (
|
||||
JSONRPCInvalidParams,
|
||||
JSONRPCInvalidRequest,
|
||||
JSONRPCInvalidRequestException,
|
||||
JSONRPCMethodNotFound,
|
||||
JSONRPCParseError,
|
||||
JSONRPCServerError,
|
||||
JSONRPCDispatchException,
|
||||
)
|
||||
from .jsonrpc1 import JSONRPC10Response
|
||||
from .jsonrpc2 import (
|
||||
JSONRPC20BatchRequest,
|
||||
JSONRPC20BatchResponse,
|
||||
JSONRPC20Response,
|
||||
)
|
||||
from .jsonrpc import JSONRPCRequest
|
||||
|
||||
logger = logging.getLogger(__name__)
|
||||
|
||||
|
||||
class JSONRPCResponseManager(object):
|
||||
|
||||
""" JSON-RPC response manager.
|
||||
|
||||
Method brings syntactic sugar into library. Given dispatcher it handles
|
||||
request (both single and batch) and handles errors.
|
||||
Request could be handled in parallel, it is server responsibility.
|
||||
|
||||
:param str request_str: json string. Will be converted into
|
||||
JSONRPC20Request, JSONRPC20BatchRequest or JSONRPC10Request
|
||||
|
||||
:param dict dispather: dict<function_name:function>.
|
||||
|
||||
"""
|
||||
|
||||
RESPONSE_CLASS_MAP = {
|
||||
"1.0": JSONRPC10Response,
|
||||
"2.0": JSONRPC20Response,
|
||||
}
|
||||
|
||||
@classmethod
|
||||
def handle(cls, request_str, dispatcher):
|
||||
if isinstance(request_str, bytes):
|
||||
request_str = request_str.decode("utf-8")
|
||||
|
||||
try:
|
||||
data = json.loads(request_str)
|
||||
except (TypeError, ValueError):
|
||||
return JSONRPC20Response(error=JSONRPCParseError()._data)
|
||||
|
||||
try:
|
||||
request = JSONRPCRequest.from_data(data)
|
||||
except JSONRPCInvalidRequestException:
|
||||
return JSONRPC20Response(error=JSONRPCInvalidRequest()._data)
|
||||
|
||||
return cls.handle_request(request, dispatcher)
|
||||
|
||||
@classmethod
|
||||
def handle_request(cls, request, dispatcher):
|
||||
""" Handle request data.
|
||||
|
||||
At this moment request has correct jsonrpc format.
|
||||
|
||||
:param dict request: data parsed from request_str.
|
||||
:param jsonrpc.dispatcher.Dispatcher dispatcher:
|
||||
|
||||
.. versionadded: 1.8.0
|
||||
|
||||
"""
|
||||
rs = request if isinstance(request, JSONRPC20BatchRequest) \
|
||||
else [request]
|
||||
responses = [r for r in cls._get_responses(rs, dispatcher)
|
||||
if r is not None]
|
||||
|
||||
# notifications
|
||||
if not responses:
|
||||
return
|
||||
|
||||
if isinstance(request, JSONRPC20BatchRequest):
|
||||
response = JSONRPC20BatchResponse(*responses)
|
||||
response.request = request
|
||||
return response
|
||||
else:
|
||||
return responses[0]
|
||||
|
||||
@classmethod
|
||||
def _get_responses(cls, requests, dispatcher):
|
||||
""" Response to each single JSON-RPC Request.
|
||||
|
||||
:return iterator(JSONRPC20Response):
|
||||
|
||||
.. versionadded: 1.9.0
|
||||
TypeError inside the function is distinguished from Invalid Params.
|
||||
|
||||
"""
|
||||
for request in requests:
|
||||
def make_response(**kwargs):
|
||||
response = cls.RESPONSE_CLASS_MAP[request.JSONRPC_VERSION](
|
||||
_id=request._id, **kwargs)
|
||||
response.request = request
|
||||
return response
|
||||
|
||||
output = None
|
||||
try:
|
||||
method = dispatcher[request.method]
|
||||
except KeyError:
|
||||
output = make_response(error=JSONRPCMethodNotFound()._data)
|
||||
else:
|
||||
try:
|
||||
result = method(*request.args, **request.kwargs)
|
||||
except JSONRPCDispatchException as e:
|
||||
output = make_response(error=e.error._data)
|
||||
except Exception as e:
|
||||
data = {
|
||||
"type": e.__class__.__name__,
|
||||
"args": e.args,
|
||||
"message": str(e),
|
||||
}
|
||||
|
||||
logger.exception("API Exception: {0}".format(data))
|
||||
|
||||
if isinstance(e, TypeError) and is_invalid_params(
|
||||
method, *request.args, **request.kwargs):
|
||||
output = make_response(
|
||||
error=JSONRPCInvalidParams(data=data)._data)
|
||||
else:
|
||||
output = make_response(
|
||||
error=JSONRPCServerError(data=data)._data)
|
||||
else:
|
||||
output = make_response(result=result)
|
||||
finally:
|
||||
if not request.is_notification:
|
||||
yield output
|
|
@ -0,0 +1,584 @@
|
|||
"""Utilities for writing code that runs on Python 2 and 3"""
|
||||
|
||||
# Copyright (c) 2010-2013 Benjamin Peterson
|
||||
#
|
||||
# Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||
# of this software and associated documentation files (the "Software"), to deal
|
||||
# in the Software without restriction, including without limitation the rights
|
||||
# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||
# copies of the Software, and to permit persons to whom the Software is
|
||||
# furnished to do so, subject to the following conditions:
|
||||
#
|
||||
# The above copyright notice and this permission notice shall be included in all
|
||||
# copies or substantial portions of the Software.
|
||||
#
|
||||
# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||
# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||
# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||
# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||
# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||
# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
|
||||
# SOFTWARE.
|
||||
|
||||
import operator
|
||||
import sys
|
||||
import types
|
||||
|
||||
__author__ = "Benjamin Peterson <benjamin@python.org>"
|
||||
__version__ = "1.4.1"
|
||||
|
||||
|
||||
# Useful for very coarse version differentiation.
|
||||
PY2 = sys.version_info[0] == 2
|
||||
PY3 = sys.version_info[0] == 3
|
||||
|
||||
if PY3:
|
||||
string_types = str,
|
||||
integer_types = int,
|
||||
class_types = type,
|
||||
text_type = str
|
||||
binary_type = bytes
|
||||
|
||||
MAXSIZE = sys.maxsize
|
||||
else:
|
||||
string_types = basestring,
|
||||
integer_types = (int, long)
|
||||
class_types = (type, types.ClassType)
|
||||
text_type = unicode
|
||||
binary_type = str
|
||||
|
||||
if sys.platform.startswith("java"):
|
||||
# Jython always uses 32 bits.
|
||||
MAXSIZE = int((1 << 31) - 1)
|
||||
else:
|
||||
# It's possible to have sizeof(long) != sizeof(Py_ssize_t).
|
||||
class X(object):
|
||||
def __len__(self):
|
||||
return 1 << 31
|
||||
try:
|
||||
len(X())
|
||||
except OverflowError:
|
||||
# 32-bit
|
||||
MAXSIZE = int((1 << 31) - 1)
|
||||
else:
|
||||
# 64-bit
|
||||
MAXSIZE = int((1 << 63) - 1)
|
||||
del X
|
||||
|
||||
|
||||
def _add_doc(func, doc):
|
||||
"""Add documentation to a function."""
|
||||
func.__doc__ = doc
|
||||
|
||||
|
||||
def _import_module(name):
|
||||
"""Import module, returning the module after the last dot."""
|
||||
__import__(name)
|
||||
return sys.modules[name]
|
||||
|
||||
|
||||
class _LazyDescr(object):
|
||||
|
||||
def __init__(self, name):
|
||||
self.name = name
|
||||
|
||||
def __get__(self, obj, tp):
|
||||
result = self._resolve()
|
||||
setattr(obj, self.name, result)
|
||||
# This is a bit ugly, but it avoids running this again.
|
||||
delattr(tp, self.name)
|
||||
return result
|
||||
|
||||
|
||||
class MovedModule(_LazyDescr):
|
||||
|
||||
def __init__(self, name, old, new=None):
|
||||
super(MovedModule, self).__init__(name)
|
||||
if PY3:
|
||||
if new is None:
|
||||
new = name
|
||||
self.mod = new
|
||||
else:
|
||||
self.mod = old
|
||||
|
||||
def _resolve(self):
|
||||
return _import_module(self.mod)
|
||||
|
||||
|
||||
class MovedAttribute(_LazyDescr):
|
||||
|
||||
def __init__(self, name, old_mod, new_mod, old_attr=None, new_attr=None):
|
||||
super(MovedAttribute, self).__init__(name)
|
||||
if PY3:
|
||||
if new_mod is None:
|
||||
new_mod = name
|
||||
self.mod = new_mod
|
||||
if new_attr is None:
|
||||
if old_attr is None:
|
||||
new_attr = name
|
||||
else:
|
||||
new_attr = old_attr
|
||||
self.attr = new_attr
|
||||
else:
|
||||
self.mod = old_mod
|
||||
if old_attr is None:
|
||||
old_attr = name
|
||||
self.attr = old_attr
|
||||
|
||||
def _resolve(self):
|
||||
module = _import_module(self.mod)
|
||||
return getattr(module, self.attr)
|
||||
|
||||
|
||||
|
||||
class _MovedItems(types.ModuleType):
|
||||
"""Lazy loading of moved objects"""
|
||||
|
||||
|
||||
_moved_attributes = [
|
||||
MovedAttribute("cStringIO", "cStringIO", "io", "StringIO"),
|
||||
MovedAttribute("filter", "itertools", "builtins", "ifilter", "filter"),
|
||||
MovedAttribute("filterfalse", "itertools", "itertools", "ifilterfalse", "filterfalse"),
|
||||
MovedAttribute("input", "__builtin__", "builtins", "raw_input", "input"),
|
||||
MovedAttribute("map", "itertools", "builtins", "imap", "map"),
|
||||
MovedAttribute("range", "__builtin__", "builtins", "xrange", "range"),
|
||||
MovedAttribute("reload_module", "__builtin__", "imp", "reload"),
|
||||
MovedAttribute("reduce", "__builtin__", "functools"),
|
||||
MovedAttribute("StringIO", "StringIO", "io"),
|
||||
MovedAttribute("UserString", "UserString", "collections"),
|
||||
MovedAttribute("xrange", "__builtin__", "builtins", "xrange", "range"),
|
||||
MovedAttribute("zip", "itertools", "builtins", "izip", "zip"),
|
||||
MovedAttribute("zip_longest", "itertools", "itertools", "izip_longest", "zip_longest"),
|
||||
|
||||
MovedModule("builtins", "__builtin__"),
|
||||
MovedModule("configparser", "ConfigParser"),
|
||||
MovedModule("copyreg", "copy_reg"),
|
||||
MovedModule("dbm_gnu", "gdbm", "dbm.gnu"),
|
||||
MovedModule("http_cookiejar", "cookielib", "http.cookiejar"),
|
||||
MovedModule("http_cookies", "Cookie", "http.cookies"),
|
||||
MovedModule("html_entities", "htmlentitydefs", "html.entities"),
|
||||
MovedModule("html_parser", "HTMLParser", "html.parser"),
|
||||
MovedModule("http_client", "httplib", "http.client"),
|
||||
MovedModule("email_mime_multipart", "email.MIMEMultipart", "email.mime.multipart"),
|
||||
MovedModule("email_mime_text", "email.MIMEText", "email.mime.text"),
|
||||
MovedModule("email_mime_base", "email.MIMEBase", "email.mime.base"),
|
||||
MovedModule("BaseHTTPServer", "BaseHTTPServer", "http.server"),
|
||||
MovedModule("CGIHTTPServer", "CGIHTTPServer", "http.server"),
|
||||
MovedModule("SimpleHTTPServer", "SimpleHTTPServer", "http.server"),
|
||||
MovedModule("cPickle", "cPickle", "pickle"),
|
||||
MovedModule("queue", "Queue"),
|
||||
MovedModule("reprlib", "repr"),
|
||||
MovedModule("socketserver", "SocketServer"),
|
||||
MovedModule("_thread", "thread", "_thread"),
|
||||
MovedModule("tkinter", "Tkinter"),
|
||||
MovedModule("tkinter_dialog", "Dialog", "tkinter.dialog"),
|
||||
MovedModule("tkinter_filedialog", "FileDialog", "tkinter.filedialog"),
|
||||
MovedModule("tkinter_scrolledtext", "ScrolledText", "tkinter.scrolledtext"),
|
||||
MovedModule("tkinter_simpledialog", "SimpleDialog", "tkinter.simpledialog"),
|
||||
MovedModule("tkinter_tix", "Tix", "tkinter.tix"),
|
||||
MovedModule("tkinter_constants", "Tkconstants", "tkinter.constants"),
|
||||
MovedModule("tkinter_dnd", "Tkdnd", "tkinter.dnd"),
|
||||
MovedModule("tkinter_colorchooser", "tkColorChooser",
|
||||
"tkinter.colorchooser"),
|
||||
MovedModule("tkinter_commondialog", "tkCommonDialog",
|
||||
"tkinter.commondialog"),
|
||||
MovedModule("tkinter_tkfiledialog", "tkFileDialog", "tkinter.filedialog"),
|
||||
MovedModule("tkinter_font", "tkFont", "tkinter.font"),
|
||||
MovedModule("tkinter_messagebox", "tkMessageBox", "tkinter.messagebox"),
|
||||
MovedModule("tkinter_tksimpledialog", "tkSimpleDialog",
|
||||
"tkinter.simpledialog"),
|
||||
MovedModule("urllib_parse", __name__ + ".moves.urllib_parse", "urllib.parse"),
|
||||
MovedModule("urllib_error", __name__ + ".moves.urllib_error", "urllib.error"),
|
||||
MovedModule("urllib", __name__ + ".moves.urllib", __name__ + ".moves.urllib"),
|
||||
MovedModule("urllib_robotparser", "robotparser", "urllib.robotparser"),
|
||||
MovedModule("winreg", "_winreg"),
|
||||
]
|
||||
for attr in _moved_attributes:
|
||||
setattr(_MovedItems, attr.name, attr)
|
||||
del attr
|
||||
|
||||
moves = sys.modules[__name__ + ".moves"] = _MovedItems(__name__ + ".moves")
|
||||
|
||||
|
||||
|
||||
class Module_six_moves_urllib_parse(types.ModuleType):
|
||||
"""Lazy loading of moved objects in six.moves.urllib_parse"""
|
||||
|
||||
|
||||
_urllib_parse_moved_attributes = [
|
||||
MovedAttribute("ParseResult", "urlparse", "urllib.parse"),
|
||||
MovedAttribute("parse_qs", "urlparse", "urllib.parse"),
|
||||
MovedAttribute("parse_qsl", "urlparse", "urllib.parse"),
|
||||
MovedAttribute("urldefrag", "urlparse", "urllib.parse"),
|
||||
MovedAttribute("urljoin", "urlparse", "urllib.parse"),
|
||||
MovedAttribute("urlparse", "urlparse", "urllib.parse"),
|
||||
MovedAttribute("urlsplit", "urlparse", "urllib.parse"),
|
||||
MovedAttribute("urlunparse", "urlparse", "urllib.parse"),
|
||||
MovedAttribute("urlunsplit", "urlparse", "urllib.parse"),
|
||||
MovedAttribute("quote", "urllib", "urllib.parse"),
|
||||
MovedAttribute("quote_plus", "urllib", "urllib.parse"),
|
||||
MovedAttribute("unquote", "urllib", "urllib.parse"),
|
||||
MovedAttribute("unquote_plus", "urllib", "urllib.parse"),
|
||||
MovedAttribute("urlencode", "urllib", "urllib.parse"),
|
||||
]
|
||||
for attr in _urllib_parse_moved_attributes:
|
||||
setattr(Module_six_moves_urllib_parse, attr.name, attr)
|
||||
del attr
|
||||
|
||||
sys.modules[__name__ + ".moves.urllib_parse"] = Module_six_moves_urllib_parse(__name__ + ".moves.urllib_parse")
|
||||
sys.modules[__name__ + ".moves.urllib.parse"] = Module_six_moves_urllib_parse(__name__ + ".moves.urllib.parse")
|
||||
|
||||
|
||||
class Module_six_moves_urllib_error(types.ModuleType):
|
||||
"""Lazy loading of moved objects in six.moves.urllib_error"""
|
||||
|
||||
|
||||
_urllib_error_moved_attributes = [
|
||||
MovedAttribute("URLError", "urllib2", "urllib.error"),
|
||||
MovedAttribute("HTTPError", "urllib2", "urllib.error"),
|
||||
MovedAttribute("ContentTooShortError", "urllib", "urllib.error"),
|
||||
]
|
||||
for attr in _urllib_error_moved_attributes:
|
||||
setattr(Module_six_moves_urllib_error, attr.name, attr)
|
||||
del attr
|
||||
|
||||
sys.modules[__name__ + ".moves.urllib_error"] = Module_six_moves_urllib_error(__name__ + ".moves.urllib_error")
|
||||
sys.modules[__name__ + ".moves.urllib.error"] = Module_six_moves_urllib_error(__name__ + ".moves.urllib.error")
|
||||
|
||||
|
||||
class Module_six_moves_urllib_request(types.ModuleType):
|
||||
"""Lazy loading of moved objects in six.moves.urllib_request"""
|
||||
|
||||
|
||||
_urllib_request_moved_attributes = [
|
||||
MovedAttribute("urlopen", "urllib2", "urllib.request"),
|
||||
MovedAttribute("install_opener", "urllib2", "urllib.request"),
|
||||
MovedAttribute("build_opener", "urllib2", "urllib.request"),
|
||||
MovedAttribute("pathname2url", "urllib", "urllib.request"),
|
||||
MovedAttribute("url2pathname", "urllib", "urllib.request"),
|
||||
MovedAttribute("getproxies", "urllib", "urllib.request"),
|
||||
MovedAttribute("Request", "urllib2", "urllib.request"),
|
||||
MovedAttribute("OpenerDirector", "urllib2", "urllib.request"),
|
||||
MovedAttribute("HTTPDefaultErrorHandler", "urllib2", "urllib.request"),
|
||||
MovedAttribute("HTTPRedirectHandler", "urllib2", "urllib.request"),
|
||||
MovedAttribute("HTTPCookieProcessor", "urllib2", "urllib.request"),
|
||||
MovedAttribute("ProxyHandler", "urllib2", "urllib.request"),
|
||||
MovedAttribute("BaseHandler", "urllib2", "urllib.request"),
|
||||
MovedAttribute("HTTPPasswordMgr", "urllib2", "urllib.request"),
|
||||
MovedAttribute("HTTPPasswordMgrWithDefaultRealm", "urllib2", "urllib.request"),
|
||||
MovedAttribute("AbstractBasicAuthHandler", "urllib2", "urllib.request"),
|
||||
MovedAttribute("HTTPBasicAuthHandler", "urllib2", "urllib.request"),
|
||||
MovedAttribute("ProxyBasicAuthHandler", "urllib2", "urllib.request"),
|
||||
MovedAttribute("AbstractDigestAuthHandler", "urllib2", "urllib.request"),
|
||||
MovedAttribute("HTTPDigestAuthHandler", "urllib2", "urllib.request"),
|
||||
MovedAttribute("ProxyDigestAuthHandler", "urllib2", "urllib.request"),
|
||||
MovedAttribute("HTTPHandler", "urllib2", "urllib.request"),
|
||||
MovedAttribute("HTTPSHandler", "urllib2", "urllib.request"),
|
||||
MovedAttribute("FileHandler", "urllib2", "urllib.request"),
|
||||
MovedAttribute("FTPHandler", "urllib2", "urllib.request"),
|
||||
MovedAttribute("CacheFTPHandler", "urllib2", "urllib.request"),
|
||||
MovedAttribute("UnknownHandler", "urllib2", "urllib.request"),
|
||||
MovedAttribute("HTTPErrorProcessor", "urllib2", "urllib.request"),
|
||||
MovedAttribute("urlretrieve", "urllib", "urllib.request"),
|
||||
MovedAttribute("urlcleanup", "urllib", "urllib.request"),
|
||||
MovedAttribute("URLopener", "urllib", "urllib.request"),
|
||||
MovedAttribute("FancyURLopener", "urllib", "urllib.request"),
|
||||
]
|
||||
for attr in _urllib_request_moved_attributes:
|
||||
setattr(Module_six_moves_urllib_request, attr.name, attr)
|
||||
del attr
|
||||
|
||||
sys.modules[__name__ + ".moves.urllib_request"] = Module_six_moves_urllib_request(__name__ + ".moves.urllib_request")
|
||||
sys.modules[__name__ + ".moves.urllib.request"] = Module_six_moves_urllib_request(__name__ + ".moves.urllib.request")
|
||||
|
||||
|
||||
class Module_six_moves_urllib_response(types.ModuleType):
|
||||
"""Lazy loading of moved objects in six.moves.urllib_response"""
|
||||
|
||||
|
||||
_urllib_response_moved_attributes = [
|
||||
MovedAttribute("addbase", "urllib", "urllib.response"),
|
||||
MovedAttribute("addclosehook", "urllib", "urllib.response"),
|
||||
MovedAttribute("addinfo", "urllib", "urllib.response"),
|
||||
MovedAttribute("addinfourl", "urllib", "urllib.response"),
|
||||
]
|
||||
for attr in _urllib_response_moved_attributes:
|
||||
setattr(Module_six_moves_urllib_response, attr.name, attr)
|
||||
del attr
|
||||
|
||||
sys.modules[__name__ + ".moves.urllib_response"] = Module_six_moves_urllib_response(__name__ + ".moves.urllib_response")
|
||||
sys.modules[__name__ + ".moves.urllib.response"] = Module_six_moves_urllib_response(__name__ + ".moves.urllib.response")
|
||||
|
||||
|
||||
class Module_six_moves_urllib_robotparser(types.ModuleType):
|
||||
"""Lazy loading of moved objects in six.moves.urllib_robotparser"""
|
||||
|
||||
|
||||
_urllib_robotparser_moved_attributes = [
|
||||
MovedAttribute("RobotFileParser", "robotparser", "urllib.robotparser"),
|
||||
]
|
||||
for attr in _urllib_robotparser_moved_attributes:
|
||||
setattr(Module_six_moves_urllib_robotparser, attr.name, attr)
|
||||
del attr
|
||||
|
||||
sys.modules[__name__ + ".moves.urllib_robotparser"] = Module_six_moves_urllib_robotparser(__name__ + ".moves.urllib_robotparser")
|
||||
sys.modules[__name__ + ".moves.urllib.robotparser"] = Module_six_moves_urllib_robotparser(__name__ + ".moves.urllib.robotparser")
|
||||
|
||||
|
||||
class Module_six_moves_urllib(types.ModuleType):
|
||||
"""Create a six.moves.urllib namespace that resembles the Python 3 namespace"""
|
||||
parse = sys.modules[__name__ + ".moves.urllib_parse"]
|
||||
error = sys.modules[__name__ + ".moves.urllib_error"]
|
||||
request = sys.modules[__name__ + ".moves.urllib_request"]
|
||||
response = sys.modules[__name__ + ".moves.urllib_response"]
|
||||
robotparser = sys.modules[__name__ + ".moves.urllib_robotparser"]
|
||||
|
||||
|
||||
sys.modules[__name__ + ".moves.urllib"] = Module_six_moves_urllib(__name__ + ".moves.urllib")
|
||||
|
||||
|
||||
def add_move(move):
|
||||
"""Add an item to six.moves."""
|
||||
setattr(_MovedItems, move.name, move)
|
||||
|
||||
|
||||
def remove_move(name):
|
||||
"""Remove item from six.moves."""
|
||||
try:
|
||||
delattr(_MovedItems, name)
|
||||
except AttributeError:
|
||||
try:
|
||||
del moves.__dict__[name]
|
||||
except KeyError:
|
||||
raise AttributeError("no such move, %r" % (name,))
|
||||
|
||||
|
||||
if PY3:
|
||||
_meth_func = "__func__"
|
||||
_meth_self = "__self__"
|
||||
|
||||
_func_closure = "__closure__"
|
||||
_func_code = "__code__"
|
||||
_func_defaults = "__defaults__"
|
||||
_func_globals = "__globals__"
|
||||
|
||||
_iterkeys = "keys"
|
||||
_itervalues = "values"
|
||||
_iteritems = "items"
|
||||
_iterlists = "lists"
|
||||
else:
|
||||
_meth_func = "im_func"
|
||||
_meth_self = "im_self"
|
||||
|
||||
_func_closure = "func_closure"
|
||||
_func_code = "func_code"
|
||||
_func_defaults = "func_defaults"
|
||||
_func_globals = "func_globals"
|
||||
|
||||
_iterkeys = "iterkeys"
|
||||
_itervalues = "itervalues"
|
||||
_iteritems = "iteritems"
|
||||
_iterlists = "iterlists"
|
||||
|
||||
|
||||
try:
|
||||
advance_iterator = next
|
||||
except NameError:
|
||||
def advance_iterator(it):
|
||||
return it.next()
|
||||
next = advance_iterator
|
||||
|
||||
|
||||
try:
|
||||
callable = callable
|
||||
except NameError:
|
||||
def callable(obj):
|
||||
return any("__call__" in klass.__dict__ for klass in type(obj).__mro__)
|
||||
|
||||
|
||||
if PY3:
|
||||
def get_unbound_function(unbound):
|
||||
return unbound
|
||||
|
||||
create_bound_method = types.MethodType
|
||||
|
||||
Iterator = object
|
||||
else:
|
||||
def get_unbound_function(unbound):
|
||||
return unbound.im_func
|
||||
|
||||
def create_bound_method(func, obj):
|
||||
return types.MethodType(func, obj, obj.__class__)
|
||||
|
||||
class Iterator(object):
|
||||
|
||||
def next(self):
|
||||
return type(self).__next__(self)
|
||||
|
||||
callable = callable
|
||||
_add_doc(get_unbound_function,
|
||||
"""Get the function out of a possibly unbound function""")
|
||||
|
||||
|
||||
get_method_function = operator.attrgetter(_meth_func)
|
||||
get_method_self = operator.attrgetter(_meth_self)
|
||||
get_function_closure = operator.attrgetter(_func_closure)
|
||||
get_function_code = operator.attrgetter(_func_code)
|
||||
get_function_defaults = operator.attrgetter(_func_defaults)
|
||||
get_function_globals = operator.attrgetter(_func_globals)
|
||||
|
||||
|
||||
def iterkeys(d, **kw):
|
||||
"""Return an iterator over the keys of a dictionary."""
|
||||
return iter(getattr(d, _iterkeys)(**kw))
|
||||
|
||||
def itervalues(d, **kw):
|
||||
"""Return an iterator over the values of a dictionary."""
|
||||
return iter(getattr(d, _itervalues)(**kw))
|
||||
|
||||
def iteritems(d, **kw):
|
||||
"""Return an iterator over the (key, value) pairs of a dictionary."""
|
||||
return iter(getattr(d, _iteritems)(**kw))
|
||||
|
||||
def iterlists(d, **kw):
|
||||
"""Return an iterator over the (key, [values]) pairs of a dictionary."""
|
||||
return iter(getattr(d, _iterlists)(**kw))
|
||||
|
||||
|
||||
if PY3:
|
||||
def b(s):
|
||||
return s.encode("latin-1")
|
||||
def u(s):
|
||||
return s
|
||||
unichr = chr
|
||||
if sys.version_info[1] <= 1:
|
||||
def int2byte(i):
|
||||
return bytes((i,))
|
||||
else:
|
||||
# This is about 2x faster than the implementation above on 3.2+
|
||||
int2byte = operator.methodcaller("to_bytes", 1, "big")
|
||||
byte2int = operator.itemgetter(0)
|
||||
indexbytes = operator.getitem
|
||||
iterbytes = iter
|
||||
import io
|
||||
StringIO = io.StringIO
|
||||
BytesIO = io.BytesIO
|
||||
else:
|
||||
def b(s):
|
||||
return s
|
||||
def u(s):
|
||||
return unicode(s, "unicode_escape")
|
||||
unichr = unichr
|
||||
int2byte = chr
|
||||
def byte2int(bs):
|
||||
return ord(bs[0])
|
||||
def indexbytes(buf, i):
|
||||
return ord(buf[i])
|
||||
def iterbytes(buf):
|
||||
return (ord(byte) for byte in buf)
|
||||
import StringIO
|
||||
StringIO = BytesIO = StringIO.StringIO
|
||||
_add_doc(b, """Byte literal""")
|
||||
_add_doc(u, """Text literal""")
|
||||
|
||||
|
||||
if PY3:
|
||||
exec_ = getattr(moves.builtins, "exec")
|
||||
|
||||
|
||||
def reraise(tp, value, tb=None):
|
||||
if value.__traceback__ is not tb:
|
||||
raise value.with_traceback(tb)
|
||||
raise value
|
||||
|
||||
else:
|
||||
def exec_(_code_, _globs_=None, _locs_=None):
|
||||
"""Execute code in a namespace."""
|
||||
if _globs_ is None:
|
||||
frame = sys._getframe(1)
|
||||
_globs_ = frame.f_globals
|
||||
if _locs_ is None:
|
||||
_locs_ = frame.f_locals
|
||||
del frame
|
||||
elif _locs_ is None:
|
||||
_locs_ = _globs_
|
||||
exec("""exec _code_ in _globs_, _locs_""")
|
||||
|
||||
|
||||
exec_("""def reraise(tp, value, tb=None):
|
||||
raise tp, value, tb
|
||||
""")
|
||||
|
||||
|
||||
print_ = getattr(moves.builtins, "print", None)
|
||||
if print_ is None:
|
||||
def print_(*args, **kwargs):
|
||||
"""The new-style print function for Python 2.4 and 2.5."""
|
||||
fp = kwargs.pop("file", sys.stdout)
|
||||
if fp is None:
|
||||
return
|
||||
def write(data):
|
||||
if not isinstance(data, basestring):
|
||||
data = str(data)
|
||||
# If the file has an encoding, encode unicode with it.
|
||||
if (isinstance(fp, file) and
|
||||
isinstance(data, unicode) and
|
||||
fp.encoding is not None):
|
||||
errors = getattr(fp, "errors", None)
|
||||
if errors is None:
|
||||
errors = "strict"
|
||||
data = data.encode(fp.encoding, errors)
|
||||
fp.write(data)
|
||||
want_unicode = False
|
||||
sep = kwargs.pop("sep", None)
|
||||
if sep is not None:
|
||||
if isinstance(sep, unicode):
|
||||
want_unicode = True
|
||||
elif not isinstance(sep, str):
|
||||
raise TypeError("sep must be None or a string")
|
||||
end = kwargs.pop("end", None)
|
||||
if end is not None:
|
||||
if isinstance(end, unicode):
|
||||
want_unicode = True
|
||||
elif not isinstance(end, str):
|
||||
raise TypeError("end must be None or a string")
|
||||
if kwargs:
|
||||
raise TypeError("invalid keyword arguments to print()")
|
||||
if not want_unicode:
|
||||
for arg in args:
|
||||
if isinstance(arg, unicode):
|
||||
want_unicode = True
|
||||
break
|
||||
if want_unicode:
|
||||
newline = unicode("\n")
|
||||
space = unicode(" ")
|
||||
else:
|
||||
newline = "\n"
|
||||
space = " "
|
||||
if sep is None:
|
||||
sep = space
|
||||
if end is None:
|
||||
end = newline
|
||||
for i, arg in enumerate(args):
|
||||
if i:
|
||||
write(sep)
|
||||
write(arg)
|
||||
write(end)
|
||||
|
||||
_add_doc(reraise, """Reraise an exception.""")
|
||||
|
||||
|
||||
def with_metaclass(meta, *bases):
|
||||
"""Create a base class with a metaclass."""
|
||||
return meta("NewBase", bases, {})
|
||||
|
||||
def add_metaclass(metaclass):
|
||||
"""Class decorator for creating a class with a metaclass."""
|
||||
def wrapper(cls):
|
||||
orig_vars = cls.__dict__.copy()
|
||||
orig_vars.pop('__dict__', None)
|
||||
orig_vars.pop('__weakref__', None)
|
||||
for slots_var in orig_vars.get('__slots__', ()):
|
||||
orig_vars.pop(slots_var)
|
||||
return metaclass(cls.__name__, cls.__bases__, orig_vars)
|
||||
return wrapper
|
|
@ -0,0 +1,7 @@
|
|||
# Python3.5+ code.
|
||||
# This won't even parse in earlier versions, so it's kept in a separate file
|
||||
# and imported when needed.
|
||||
|
||||
|
||||
def distance(a: float, b: float) -> float:
|
||||
return (a ** 2 + b ** 2) ** 0.5
|
|
@ -0,0 +1,11 @@
|
|||
SECRET_KEY = 'secret'
|
||||
ROOT_URLCONF = 'jsonrpc.tests.test_backend_django.urls'
|
||||
ALLOWED_HOSTS = ['testserver']
|
||||
DATABASE_ENGINE = 'django.db.backends.sqlite3'
|
||||
DATABASES = {
|
||||
'default': {
|
||||
'ENGINE': 'django.db.backends.sqlite3',
|
||||
'NAME': ':memory:',
|
||||
}
|
||||
}
|
||||
JSONRPC_MAP_VIEW_ENABLED = True
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue