Skip to content

Commit e0ab166

Browse files
author
Vehicle Researcher
committedMay 9, 2020
Squashed 'opendbc/' changes from a62d5dd..f1e69a6
f1e69a6 Fix wrong message size in Chrysler 54482cf Fix GM message signal sizes 4e796e0 Fix wrong message sizes in Nissan fb6c1ee Better GEAR signal tracking the gear stick rather than the gear box (#257) d7a2efb Raw angle signal data for easy checksum calc, and one less gear bit (#254) 7456061 add checksum check to can parser for subaru 7f3b177 Chrysler: calculate checksum in can packer/parser (#255) 0c02155 Rename BYTE_ to SET_ME_X (#253) 1efe437 Add values for a static 0xe5 (honda bosch) (#250) 7dffe0b Create DBC for HRV (#248) b693985 Add LFAHDA message to hyundai a57e7dd CANPacker: Subaru checksum support (#241) 36c471e Fixed signals order and added new signals for subaru global (#221) 7b5a1fc BMW 2008-2013 (#230) cc09af7 Add RPM signal (#216) 47db923 Add SWA_01 message detail and CRC support for VW MQB (#236) c98fe2a Fixed signal unknown1 overlapping the button bits (#239) 572261e Rear Cross Traffic Alert 044730a Speed limit signs 87b1a21 Pedals/gear, gas pedal scale value ce78044 Tracking the steer angle with LKAS signal 7f19ab4 Introduce the new mazda 3 2019/2020 dbc e585206 traffic sign speed limit 00bad5e Speed Auto High Beam Traffic signs 9d080ea Nissan leaf (#238) 50fbbe7 nissan x trail cleanup (#237) git-subtree-dir: opendbc git-subtree-split: f1e69a6
1 parent 72427d8 commit e0ab166

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

47 files changed

+1801
-320
lines changed
 

‎bmw_e9x_e8x.dbc

+291
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,291 @@
1+
VERSION ""
2+
3+
4+
NS_ :
5+
NS_DESC_
6+
CM_
7+
BA_DEF_
8+
BA_
9+
VAL_
10+
CAT_DEF_
11+
CAT_
12+
FILTER
13+
BA_DEF_DEF_
14+
EV_DATA_
15+
ENVVAR_DATA_
16+
SGTYPE_
17+
SGTYPE_VAL_
18+
BA_DEF_SGTYPE_
19+
BA_SGTYPE_
20+
SIG_TYPE_REF_
21+
VAL_TABLE_
22+
SIG_GROUP_
23+
SIG_VALTYPE_
24+
SIGTYPE_VALTYPE_
25+
BO_TX_BU_
26+
BA_DEF_REL_
27+
BA_REL_
28+
BA_DEF_DEF_REL_
29+
BU_SG_REL_
30+
BU_EV_REL_
31+
BU_BO_REL_
32+
SG_MUL_VAL_
33+
34+
BS_:
35+
36+
BU_: XXX EON Vector__XXX
37+
38+
39+
BO_ 170 AccPedal: 8 XXX
40+
SG_ KickDownPressed : 53|1@0+ (1,0) [0|3] "" XXX
41+
SG_ CruisePedalActive : 54|1@0+ (1,0) [0|1] "" XXX
42+
SG_ CruisePedalInactive : 55|1@0+ (1,0) [0|1] "" XXX
43+
SG_ ThrottlelPressed : 50|1@0+ (1,0) [0|1] "" XXX
44+
SG_ AcceleratorPedalPressed : 52|1@0+ (1,0) [0|7] "" XXX
45+
SG_ AcceleratorPedalPercentage : 16|16@1+ (0.01,0) [0|100] "" XXX
46+
SG_ Counter1 : 8|4@1+ (1,0) [0|15] "" XXX
47+
SG_ EngineSpeed : 32|16@1- (1,0) [0|65535] "" XXX
48+
SG_ uknown : 7|8@0- (1,0) [0|65535] "" XXX
49+
50+
BO_ 404 CruiseControl: 4 XXX
51+
SG_ plus1mph_request : 16|1@0+ (1,0) [0|1] "" XXX
52+
SG_ minus1mph_request : 18|1@0+ (1,0) [0|1] "" XXX
53+
SG_ Cancel_request_up_stalk : 23|1@0+ (1,0) [0|1] "" XXX
54+
SG_ Cancel_request_up_or_down_stalk : 20|1@0+ (1,0) [0|1] "" XXX
55+
SG_ Resume_request : 22|1@0+ (1,0) [0|1] "" XXX
56+
SG_ Counter1 : 3|4@0+ (1,0) [0|15] "" XXX
57+
SG_ Counter2 : 11|4@0+ (1,0) [0|15] "" XXX
58+
SG_ notCancel_0xF : 7|4@0+ (1,0) [0|15] "" XXX
59+
SG_ setMe_0xFC : 31|8@0+ (1,0) [0|255] "" XXX
60+
SG_ requests_0xF : 15|4@0+ (1,0) [0|15] "" XXX
61+
SG_ plus5mph_request : 17|1@0+ (1,0) [0|0] "" Vector__XXX
62+
SG_ minus5mph_request : 19|1@0+ (1,0) [0|0] "" Vector__XXX
63+
64+
BO_ 512 CruiseControlStatus: 8 XXX
65+
SG_ CruiseControlInactiveFlag : 12|1@0+ (1,0) [0|1] "" XXX
66+
SG_ CruiseCoontrolActiveFlag : 13|1@0+ (1,0) [0|1] "" XXX
67+
SG_ CruiseControlSetpointSpeed : 7|8@0+ (0.25,0) [0|255] "mph" XXX
68+
69+
BO_ 168 EngineAndBrake: 8 XXX
70+
SG_ Brake_active2 : 62|1@0+ (1,0) [0|1] "" XXX
71+
SG_ BrakePressed : 61|1@0+ (1,0) [0|1] "" XXX
72+
SG_ EngineTorque : 8|16@1- (1,0) [0|65535] "" XXX
73+
SG_ EngineTorqueWoInterv : 24|16@1- (1,0) [0|65535] "" XXX
74+
75+
BO_ 470 SteeringButtons: 2 XXX
76+
SG_ Volume_DOWN : 2|1@0+ (1,0) [0|1] "" XXX
77+
SG_ Volume_UP : 3|1@0+ (1,0) [0|1] "" XXX
78+
SG_ VoiceControl : 8|1@0+ (1,0) [0|1] "" XXX
79+
SG_ Telephone : 0|1@0+ (1,0) [0|1] "" XXX
80+
SG_ Next_up : 5|1@0+ (1,0) [0|1] "" XXX
81+
SG_ Previous_down : 4|1@0+ (1,0) [0|1] "" XXX
82+
83+
BO_ 403 DynamicCruiseControlStatus: 8 XXX
84+
SG_ Counter : 7|8@0+ (1,0) [0|255] "" XXX
85+
SG_ CruiseActive : 43|1@0+ (1,0) [0|1] "" XXX
86+
SG_ CruiseSpeedChangeRequest : 48|1@0+ (1,0) [0|1] "" XXX
87+
SG_ CruiseControlSetpointSpeed : 15|8@0+ (1,-2) [0|255] "mph" XXX
88+
89+
BO_ 201 SteeringWheelAngle_DSC: 8 XXX
90+
SG_ Counter1 : 23|4@0+ (1,0) [0|15] "" XXX
91+
SG_ WeirdCounter : 44|4@1+ (1,0) [0|3] "" XXX
92+
SG_ SteeringPositionComplementLow : 24|11@1- (1,0) [0|1] "" XXX
93+
SG_ SteeringPosition : 0|16@1- (0.0439453125,0) [-600|600] "deg" XXX
94+
95+
BO_ 206 WheelSpeeds: 8 XXX
96+
SG_ Wheel1 : 0|16@1- (0.0643699,0) [0|255] "kph" XXX
97+
SG_ Wheel2 : 16|16@1- (0.0643699,0) [0|255] "kph" XXX
98+
SG_ Wheel4 : 48|16@1- (0.0643699,0) [0|255] "kph" XXX
99+
SG_ Wheel3 : 32|16@1- (0.0643699,0) [0|255] "kph" XXX
100+
101+
BO_ 884 WheelToleranceAdjustment: 8 XXX
102+
103+
BO_ 678 WiperSwitch: 8 XXX
104+
SG_ AutoWipersOn : 0|1@1+ (1,0) [0|3] "" XXX
105+
106+
BO_ 304 TerminalStatus: 8 XXX
107+
SG_ AccOn : 23|1@0+ (1,0) [0|255] "" XXX
108+
SG_ IgnitionOff : 22|1@0+ (1,0) [0|3] "" XXX
109+
110+
BO_ 169 Torque2: 8 XXX
111+
112+
BO_ 184 TorqueTransmisionRequest: 8 XXX
113+
114+
BO_ 196 SteeringWheelAngle: 7 XXX
115+
SG_ SteeringPosition : 0|16@1- (0.0439453125,0) [-600|600] "degree" XXX
116+
SG_ SteeringSpeed : 24|16@1- (0.0439453125,0) [0|255] "degree/s" XXX
117+
118+
BO_ 180 WheelTorqueDriveTrain1: 8 XXX
119+
120+
BO_ 182 DynamicCruiseControlTorqueDemand: 8 XXX
121+
122+
BO_ 186 TransmissionData: 8 XXX
123+
124+
BO_ 191 RequestedWheelTorqueDriveTrainActiveCruiseControl: 8 XXX
125+
SG_ Counter : 11|4@0- (1,0) [0|255] "" XXX
126+
SG_ TorqueReq : 16|11@1+ (1,0) [0|65535] "" XXX
127+
128+
BO_ 414 Status_DSC: 8 XXX
129+
130+
BO_ 416 Speed: 8 XXX
131+
SG_ VehicleSpeed : 0|12@1+ (0.103,0) [0|255] "kph" XXX
132+
133+
BO_ 418 TransimissionData2: 8 XXX
134+
135+
BO_ 690 WheelPressure: 8 XXX
136+
137+
BO_ 691 AccelerationData: 8 XXX
138+
139+
BO_ 408 GearSelectorSwitch: 8 XXX
140+
SG_ Gear : 0|8@1+ (1,0) [0|0] "" Vector__XXX
141+
142+
BO_ 422 Distance: 8 XXX
143+
144+
BO_ 436 InstrumentClusterStatus_KOMBI: 8 XXX
145+
146+
BO_ 464 EngineData: 8 XXX
147+
148+
BO_ 945 TransmissionData3: 8 XXX
149+
150+
BO_ 200 SteeringWheelAngle_slow: 8 XXX
151+
SG_ SteeringPosition : 0|16@1- (0.0439453125,0) [-600|600] "degree" XXX
152+
SG_ SteeringSpeed : 24|16@1- (0.0439453125,0) [-65535|65535] "degree/s" XXX
153+
154+
BO_ 466 TransmissionDataDisplay: 8 XXX
155+
156+
BO_ 437 HeatFlow_LoadMomentClimate: 8 XXX
157+
158+
BO_ 1152 NetworkManagment1: 8 XXX
159+
160+
BO_ 1170 NetworkManagment2: 8 XXX
161+
162+
BO_ 1175 NetworkManagment3: 8 XXX
163+
164+
BO_ 1176 NetworkManagment4: 8 XXX
165+
166+
BO_ 1193 NetworkManagment5: 8 XXX
167+
168+
BO_ 1246 NetworkManagment6: 8 XXX
169+
170+
BO_ 438 HeatFlowEngine: 8 XXX
171+
172+
BO_ 784 AmbientTemperature: 8 XXX
173+
174+
BO_ 821 ElectricFuelPumpStatus: 8 XXX
175+
176+
BO_ 1007 EngineOBD_data: 8 XXX
177+
178+
BO_ 1432 ServicesDKG: 8 XXX
179+
180+
BO_ 309 CrashDisconnectControl: 8 XXX
181+
182+
BO_ 502 TurnSignals: 2 XXX
183+
SG_ TurnSignalIdle : 9|1@0+ (1,0) [0|1] "" XXX
184+
SG_ TurnSignalActive : 8|1@0+ (1,0) [0|1] "" XXX
185+
SG_ RightTurn : 5|1@0+ (1,0) [0|1] "" XXX
186+
SG_ LeftTurn : 4|1@1+ (1,0) [0|1] "" XXX
187+
SG_ HoldActivated : 0|1@1+ (1,0) [0|1] "" XXX
188+
189+
BO_ 514 Dimming: 8 XXX
190+
191+
BO_ 538 LampsCondition: 8 XXX
192+
193+
BO_ 550 RainSensorWiperSpeed: 8 XXX
194+
195+
BO_ 578 ClimateFrontStatus: 8 XXX
196+
197+
BO_ 704 LCD_lighting: 8 XXX
198+
199+
BO_ 758 LightControl: 8 XXX
200+
201+
BO_ 760 Time_Date: 8 XXX
202+
203+
BO_ 762 SeatBeltContact: 8 XXX
204+
205+
BO_ 764 TrunkStatus: 8 XXX
206+
207+
BO_ 797 TirePressureStatus: 8 XXX
208+
209+
BO_ 816 Range_Mileage: 8 XXX
210+
211+
BO_ 823 StatusFuelControl: 8 XXX
212+
213+
BO_ 897 EngineOilLevelStatus: 8 XXX
214+
215+
BO_ 940 Terminal30Eerror: 8 XXX
216+
217+
BO_ 947 PowerManagmentConsumptionControl: 8 XXX
218+
219+
BO_ 948 PowerBatteryVoltage: 8 XXX
220+
SG_ BatteryVoltage : 7|24@0+ (0.001,0) [0|65535] "" XXX
221+
222+
BO_ 958 PowerRunningTime: 8 XXX
223+
224+
BO_ 1408 ServicesKGM: 8 XXX
225+
226+
BO_ 1426 ServicesDME: 8 XXX
227+
228+
BO_ 1449 ServicesDSC: 8 XXX
229+
230+
BO_ 1504 ServicesKOMBI: 8 XXX
231+
232+
BO_ 1522 ServicesKBM: 8 XXX
233+
234+
BO_ 209 Accelerometer: 8 XXX
235+
SG_ LateralAcceleration : 0|16@1- (1,0) [0|7] "" XXX
236+
SG_ LongitudalAcceleration : 32|16@1- (1,0) [0|65535] "" XXX
237+
238+
BO_ 172 WheelTorqueDrivetrain2: 8 XXX
239+
240+
BO_ 128 Unknown80: 5 XXX
241+
SG_ State2 : 24|4@1+ (1,0) [0|15] "" XXX
242+
SG_ State1 : 23|8@0+ (1,0) [0|255] "" XXX
243+
SG_ Counter1 : 31|4@0+ (1,0) [0|15] "" XXX
244+
245+
BO_ 320 Unknown140: 2 XXX
246+
SG_ State : 7|8@0+ (1,0) [0|255] "" XXX
247+
248+
BO_ 212 Unknown_d4: 8 XXX
249+
SG_ State1 : 47|8@0+ (1,0) [0|255] "" XXX
250+
SG_ Counter1 : 55|8@0+ (1,0) [0|255] "" XXX
251+
SG_ Counter2 : 63|8@0+ (1,0) [0|255] "" XXX
252+
253+
BO_ 205 Unknown_cd: 8 XXX
254+
SG_ NEW_SIGNAL_2 : 15|8@0+ (1,0) [0|255] "" XXX
255+
SG_ NEW_SIGNAL_3 : 23|8@0+ (1,0) [0|255] "" XXX
256+
SG_ NEW_SIGNAL_4 : 31|8@0+ (1,0) [0|255] "" XXX
257+
SG_ NEW_SIGNAL_5 : 39|8@0- (1,0) [0|255] "" XXX
258+
SG_ NEW_SIGNAL_6 : 47|8@0+ (1,0) [0|255] "" XXX
259+
SG_ Counter1 : 55|4@0+ (1,0) [0|255] "" XXX
260+
SG_ NEW_SIGNAL_1 : 7|8@0+ (1,0) [0|255] "" XXX
261+
SG_ NEW_SIGNAL_7 : 63|8@0- (1,0) [0|255] "" XXX
262+
263+
BO_ 1577 NEW_MSG_1: 8 XXX
264+
265+
266+
267+
268+
CM_ SG_ 170 ThrottlelPressed "Active when accelerator pedal pressed or cruise control drives";
269+
CM_ SG_ 170 AcceleratorPedalPressed "Active only when driver actually presses the pedal";
270+
CM_ SG_ 170 AcceleratorPedalPercentage "ToDo Factor to be adjusted";
271+
CM_ SG_ 170 EngineSpeed "It's hard to say that is even a rate";
272+
CM_ SG_ 404 plus1mph_request "Appears when +1mph/kph stalk is depressed";
273+
CM_ SG_ 404 minus1mph_request "Appears when -1mph/kph stalk is depressed";
274+
CM_ SG_ 404 Cancel_request_up_stalk "Appears when cancel stalk (up) is depressed";
275+
CM_ SG_ 404 Cancel_request_up_or_down_stalk "Appears when cancel stalk (up or down) is depressed";
276+
CM_ SG_ 404 Resume_request "It appears when resume stalk button is depressed";
277+
CM_ SG_ 404 Counter1 "It accelerates when requests are being sent";
278+
CM_ SG_ 404 Counter2 "It accelerates when requests are being sent";
279+
CM_ SG_ 404 notCancel_0xF "0xF unless cancel is requested then 0x0";
280+
CM_ SG_ 168 Brake_active2 "";
281+
CM_ SG_ 168 BrakePressed "Brake when driver presses the brake";
282+
CM_ SG_ 168 EngineTorque "Engine torque without inertia - combustion torque";
283+
CM_ SG_ 168 EngineTorqueWoInterv "Engine torque without inertia and without shift intervention";
284+
CM_ SG_ 403 CruiseControlSetpointSpeed "Speed target";
285+
CM_ SG_ 408 Gear "This is just provision, needs to be reverse engineered";
286+
CM_ SG_ 502 TurnSignalIdle "Turn signal off";
287+
CM_ SG_ 502 TurnSignalActive "Turn signal on or transitioning";
288+
CM_ SG_ 502 RightTurn "Indicates right blinker or when steering returning right clears left blinker";
289+
CM_ SG_ 502 LeftTurn "Indicates left blinker or when steering returning left clears right blinker";
290+
CM_ SG_ 502 HoldActivated "Spikes down if blinker cleared with timeout or turn. Stays off if blinker cleared with stalk";
291+
VAL_ 408 Gear 1 "D" 2 "S" 3 "N" 4 "R" 5 "P" ;

‎can/common.cc

+48-2
Original file line numberDiff line numberDiff line change
@@ -18,12 +18,55 @@ unsigned int toyota_checksum(unsigned int address, uint64_t d, int l) {
1818
d >>= 8; // remove checksum
1919

2020
unsigned int s = l;
21-
while (address) { s += address & 0xff; address >>= 8; }
22-
while (d) { s += d & 0xff; d >>= 8; }
21+
while (address) { s += address & 0xFF; address >>= 8; }
22+
while (d) { s += d & 0xFF; d >>= 8; }
2323

2424
return s & 0xFF;
2525
}
2626

27+
unsigned int subaru_checksum(unsigned int address, uint64_t d, int l) {
28+
d >>= ((8-l)*8); // remove padding
29+
30+
unsigned int s = 0;
31+
while (address) { s += address & 0xFF; address >>= 8; }
32+
l -= 1; // checksum is first byte
33+
while (l) { s += d & 0xFF; d >>= 8; l -= 1; }
34+
35+
return s & 0xFF;
36+
}
37+
38+
unsigned int chrysler_checksum(unsigned int address, uint64_t d, int l) {
39+
/* This function does not want the checksum byte in the input data.
40+
jeep chrysler canbus checksum from http://illmatics.com/Remote%20Car%20Hacking.pdf */
41+
uint8_t checksum = 0xFF;
42+
for (int j = 0; j < (l - 1); j++) {
43+
uint8_t shift = 0x80;
44+
uint8_t curr = (d >> 8*j) & 0xFF;
45+
for (int i=0; i<8; i++) {
46+
uint8_t bit_sum = curr & shift;
47+
uint8_t temp_chk = checksum & 0x80U;
48+
if (bit_sum != 0U) {
49+
bit_sum = 0x1C;
50+
if (temp_chk != 0U) {
51+
bit_sum = 1;
52+
}
53+
checksum = checksum << 1;
54+
temp_chk = checksum | 1U;
55+
bit_sum ^= temp_chk;
56+
} else {
57+
if (temp_chk != 0U) {
58+
bit_sum = 0x1D;
59+
}
60+
checksum = checksum << 1;
61+
bit_sum ^= checksum;
62+
}
63+
checksum = bit_sum;
64+
shift = shift >> 1;
65+
}
66+
}
67+
return ~checksum & 0xFF;
68+
}
69+
2770
// Static lookup table for fast computation of CRC8 poly 0x2F, aka 8H2F/AUTOSAR
2871
uint8_t crc8_lut_8h2f[256];
2972

@@ -106,6 +149,9 @@ unsigned int volkswagen_crc(unsigned int address, uint64_t d, int l) {
106149
case 0x30C: // ACC_02 Automatic Cruise Control
107150
crc ^= (uint8_t[]){0x0F,0x0F,0x0F,0x0F,0x0F,0x0F,0x0F,0x0F,0x0F,0x0F,0x0F,0x0F,0x0F,0x0F,0x0F,0x0F}[counter];
108151
break;
152+
case 0x30F: // SWA_01 Lane Change Assist (SpurWechselAssistent)
153+
crc ^= (uint8_t[]){0x0C,0x0C,0x0C,0x0C,0x0C,0x0C,0x0C,0x0C,0x0C,0x0C,0x0C,0x0C,0x0C,0x0C,0x0C,0x0C}[counter];
154+
break;
109155
case 0x3C0: // Klemmen_Status_01 ignition and starting status
110156
crc ^= (uint8_t[]){0xC3,0xC3,0xC3,0xC3,0xC3,0xC3,0xC3,0xC3,0xC3,0xC3,0xC3,0xC3,0xC3,0xC3,0xC3,0xC3}[counter];
111157
break;

0 commit comments

Comments
 (0)