Apollo 10.0
自动驾驶开放平台
transit.proto
浏览该文件的文档.
1syntax = "proto2";
2
3package apollo.canbus;
4
6 // Report Message
7 // Steering angle feedback [deg] [0|4095]
8 optional int32 llc_fbk_maxsteeringangle = 1;
9 // Front brake pressure feedback [%] [0|113.8132]
10 optional double llc_fbk_maxbrakepercent = 2;
11}
12
14 // Control Message
16 ADC_CMD_STEERINGCONTROLMODE_NONE = 0;
17 ADC_CMD_STEERINGCONTROLMODE_ANGLE = 1;
18 ADC_CMD_STEERINGCONTROLMODE_RESERVED_CURVATURE = 2;
19 ADC_CMD_STEERINGCONTROLMODE_RESERVED = 3;
20 }
22 ADC_CMD_GEAR_P_PARK = 0;
23 ADC_CMD_GEAR_D_DRIVE = 1;
24 ADC_CMD_GEAR_N_NEUTRAL = 2;
25 ADC_CMD_GEAR_R_REVERSE = 3;
26 }
28 ADC_CMD_AUTONOMYREQUEST_AUTONOMY_NOT_REQUESTED = 0;
29 ADC_CMD_AUTONOMYREQUEST_AUTONOMY_REQUESTED = 1;
30 ADC_CMD_AUTONOMYREQUEST_RESERVED0 = 2;
31 ADC_CMD_AUTONOMYREQUEST_RESERVED1 = 3;
32 }
34 ADC_CMD_LONGITUDINALCONTROLMODE_NONE = 0;
35 ADC_CMD_LONGITUDINALCONTROLMODE_RESERVED_VELOCITY_AND_ACCELERATION = 1;
36 ADC_CMD_LONGITUDINALCONTROLMODE_RESERVED_FORCE = 2;
37 ADC_CMD_LONGITUDINALCONTROLMODE_DIRECT_THROTTLE_BRAKE = 3;
38 }
39 // Setpoint for steering wheel angle. Positive for CW [deg] [-1638.4|1638.35]
40 optional double adc_cmd_steerwheelangle = 1;
41 // Select steering control mode [] [0|3]
42 optional Adc_cmd_steeringcontrolmodeType adc_cmd_steeringcontrolmode = 2;
43 // (Reserved) Control parking brake [T/F] [0|1]
44 optional bool adc_cmd_parkingbrake = 3;
45 // Transmission control - only used in direct longitudinal control [] [0|7]
46 optional Adc_cmd_gearType adc_cmd_gear = 4;
47 // Motion Control 1 checksum [] [0|255]
48 optional int32 adc_motioncontrol1_checksum = 5;
49 // Brake pressure for direct longitudinal control [%] [0|113.8132]
50 optional double adc_cmd_brakepercentage = 6;
51 // Throttle pedal position percentage for direct longitudinal control [%]
52 // [0|100]
53 optional double adc_cmd_throttleposition = 7;
54 // Motion control 1 Heartbeat counter [] [0|3]
55 optional int32 adc_motioncontrol1_counter = 8;
56 // Request from ADC to LLC for autonomy [] [0|3]
57 optional Adc_cmd_autonomyrequestType adc_cmd_autonomyrequest = 9;
58 // Select longitudinal control mode [] [0|3]
59 optional Adc_cmd_longitudinalcontrolmodeType adc_cmd_longitudinalcontrolmode =
60 10;
61}
64 // Control Message
65 // Set limit for throttle position [%] [0|100]
66 optional double adc_cmd_throttlecommandlimit = 1;
67 // Set steering rate [deg/s] [0|3276.75]
68 optional double adc_cmd_steeringrate = 2;
69 // Set limit for steering wheel angle. Applies in both positive and negative
70 // [deg] [0|1275]
71 optional double adc_cmd_steerwheelanglelimit = 3;
72}
75 // Report Message
77 LLC_FBK_GEAR_P_PARK = 0;
78 LLC_FBK_GEAR_D_DRIVE = 1;
79 LLC_FBK_GEAR_N_NEUTRAL = 2;
80 LLC_FBK_GEAR_R_REVERSE = 3;
81 }
83 LLC_FBK_STEERINGCONTROLMODE_NONE = 0;
84 LLC_FBK_STEERINGCONTROLMODE_ANGLE = 1;
85 LLC_FBK_STEERINGCONTROLMODE_RESERVED_CURVATURE = 2;
86 LLC_FBK_STEERINGCONTROLMODE_RESERVED = 3;
87 }
89 LLC_FBK_LONGITUDINALCONTROLMODE_NONE = 0;
90 LLC_FBK_LONGITUDINALCONTROLMODE_RESERVED_VELOCITY_AND_ACCELERATION = 1;
91 LLC_FBK_LONGITUDINALCONTROLMODE_RESERVED_FORCE = 2;
92 LLC_FBK_LONGITUDINALCONTROLMODE_DIRECT_THROTTLE_BRAKE = 3;
93 }
95 LLC_FBK_STATE_RESERVED0 = 0;
96 LLC_FBK_STATE_AUTONOMY_NOT_ALLOWED = 1;
97 LLC_FBK_STATE_AUTONOMY_ALLOWED = 2;
98 LLC_FBK_STATE_AUTONOMY_REQUESTED = 3;
99 LLC_FBK_STATE_AUTONOMY = 4;
100 LLC_FBK_STATE_RESERVED1 = 5;
101 LLC_FBK_STATE_RESERVED2 = 6;
102 LLC_FBK_STATE_RESERVED3 = 7;
103 LLC_FBK_STATE_RESERVED4 = 8;
104 LLC_FBK_STATE_RESERVED5 = 9;
105 LLC_FBK_STATE_RESERVED6 = 10;
106 LLC_FBK_STATE_RESERVED7 = 11;
107 LLC_FBK_STATE_RESERVED8 = 12;
108 LLC_FBK_STATE_DISENGAGE_REQUESTED = 13;
109 LLC_FBK_STATE_DISENGAGED = 14;
110 LLC_FBK_STATE_FAULT = 15;
111 }
112 // Current gear [] [0|3]
113 optional Llc_fbk_gearType llc_fbk_gear = 1;
114 // Parking brake applied [T/F] [0|1]
115 optional bool llc_fbk_parkingbrake = 2;
116 // Throttle position feedback [%] [0|102.3]
117 optional double llc_fbk_throttleposition = 3;
118 // Rear brake pressure feedback [%] [0|113.8132]
119 optional double llc_fbk_brakepercentrear = 4;
120 // Front brake pressure feedback [%] [0|113.8132]
121 optional double llc_fbk_brakepercentfront = 5;
122 // Current steering control mode [] [0|3]
123 optional Llc_fbk_steeringcontrolmodeType llc_fbk_steeringcontrolmode = 6;
124 // Motion feedback 1 heartbeat counter [] [0|3]
125 optional int32 llc_motionfeedback1_counter = 7;
126 // Motion feedback 1 checksum [] [0|255]
127 optional int32 llc_motionfeedback1_checksum = 8;
128 // Autonomy command aligned with vehicle state according to calibration limits
129 // [T/F] [0|1]
130 optional bool llc_fbk_commandaligned = 9;
131 // Estop is pressed [T/F] [0|1]
132 optional bool llc_fbk_estoppressed = 10;
133 // Indicates that ADC is requesting autonomy mode [T/F] [0|1]
134 optional bool llc_fbk_adcrequestautonomy = 11;
135 // Indicates that LLC is ready to allow autonomy mode [T/F] [0|1]
136 optional bool llc_fbk_allowautonomy = 12;
137 // Report current longitudinal control mode [] [0|3]
138 optional Llc_fbk_longitudinalcontrolmodeType llc_fbk_longitudinalcontrolmode =
139 13;
140 // Current Autonomy State [] [0|15]
141 optional Llc_fbk_stateType llc_fbk_state = 14;
143
145 // Report Message
146 // [m/s] [0|655.35]
147 optional double llc_fbk_vehiclespeed = 1;
148 // Motion feedback 2 heartbeat counter [] [0|3]
149 optional int32 llc_motionfeedback2_counter = 2;
150 // Motion feedback 2 checksum [] [0|255]
151 optional int32 llc_motionfeedback2_checksum = 3;
152 // Steer wheel angle feedback from SbW motor (? rate) [deg/s] [-1638.4|1638.3]
153 optional double llc_fbk_steeringrate = 4;
154 // Steering angle feedback [deg] [-1638.4|1638.35]
155 optional double llc_fbk_steeringangle = 5;
157
159 // Report Message
160 // Steering angle setpoint (after limits) [deg] [-1638.4|1638.35]
161 optional double llc_fbk_steeringanglesetpoint = 1;
162 // Current throttle setpoint (after limits) [%] [0|102.3]
163 optional double llc_fbk_throttlesetpoint = 2;
164 // Front brake pressure setpoint (after limits) [%] [0|113.8132]
165 optional double llc_fbk_brakepercentsetpoint = 3;
166 // Motion command feedback 2 heartbeat counter [] [0|3]
167 optional int32 llc_motioncommandfeedback1_count = 4;
168 // Motion command feedback 1 checksum [] [0|255]
169 optional int32 llc_motioncommandfeedback1_check = 5;
171
172message Llc_vehiclestatus_25 {
173 // Report Message
174 // Vehicle 12V voltage feedback [Volt] [0|25.5]
175 optional double llc_fbk_12voltage = 1;
177
179 // Report Message
181 LLC_FBK_TURNSIGNAL_NONE = 0;
182 LLC_FBK_TURNSIGNAL_LEFT = 1;
183 LLC_FBK_TURNSIGNAL_RIGHT = 2;
184 LLC_FBK_TURNSIGNAL_RESERVE = 3;
186 // Inverter enabled [T/F] [0|1]
187 optional bool llc_fbk_inverter = 1;
188 // PDU Channel 8 enabled [T/F] [0|1]
189 optional bool llc_fbk_pdu_ch8 = 2;
190 // PDU Channel 7 enabled [T/F] [0|1]
191 optional bool llc_fbk_pdu_ch7 = 3;
192 // PDU Channel 6 enabled [T/F] [0|1]
193 optional bool llc_fbk_pdu_ch6 = 4;
194 // PDU Channel 5 enabled [T/F] [0|1]
195 optional bool llc_fbk_pdu_ch5 = 5;
196 // PDU Channel 4 enabled [T/F] [0|1]
197 optional bool llc_fbk_pdu_ch4 = 6;
198 // PDU Channel 3 enabled [T/F] [0|1]
199 optional bool llc_fbk_pdu_ch3 = 7;
200 // PDU Channel 2 enabled [T/F] [0|1]
201 optional bool llc_fbk_pdu_ch2 = 8;
202 // PDU Channel 1 enabled [T/F] [0|1]
203 optional bool llc_fbk_pdu_ch1 = 9;
204 // Hazard lights enabled [T/F] [0|1]
205 optional bool llc_fbk_hazardlights = 10;
206 // Autonomy indicator green LED on [T/F] [0|1]
207 optional bool llc_fbk_ledgreenon = 11;
208 // Horn enabled [T/F] [0|1]
209 optional bool llc_fbk_horn = 12;
210 // Buzzer enabled [T/F] [0|1]
211 optional bool llc_fbk_buzzeron = 13;
212 // Current turn signal status [] [0|3]
213 optional Llc_fbk_turnsignalType llc_fbk_turnsignal = 14;
214 // Low beam enabled [T/F] [0|1]
215 optional bool llc_fbk_lowbeam = 15;
216 // High beam enabled [T/F] [0|1]
217 optional bool llc_fbk_highbeam = 16;
218 // Autonomy indicator red LED on [T/F] [0|1]
219 optional bool llc_fbk_ledredon = 17;
220 // Autonomy button is pressed [T/F] [0|1]
221 optional bool llc_fbk_autonomybuttonpressed = 18;
223
224message Llc_diag_fault_620 {
225 // Report Message
226 // Counts the number of times that the driver has disengaged autonomy by
227 // applying the brakes since system reset.. [] [0|255]
228 optional int32 llc_disengagecounter_brake = 1;
229 // Counts the number of times that the driver has disengaged autonomy by
230 // moving the steering wheel since system reset. [] [0|255]
231 optional int32 llc_disengagecounter_steer = 2;
232 // Counts the number of times that the driver has disengaged autonomy by
233 // applying throttle since system reset. [] [0|255]
234 optional int32 llc_disengagecounter_throttle = 3;
235 // Counts the number of faults that have occurred since system reset. []
236 // [0|255]
237 optional int32 llc_fbk_faultcounter = 4;
238 // Counts the number of times that the driver has disengaged autonomy by
239 // applying the brakes since system reset.. [] [0|255]
240 optional int32 llc_disengagecounter_button = 5;
241 // Firmware version [g] [2017|2144]
242 optional int32 llc_fbk_version_year = 6;
243 // Firmware version [Month] [0|15]
244 optional int32 llc_fbk_version_month = 7;
245 // Firmware version [Day] [0|31]
246 optional int32 llc_fbk_version_day = 8;
247 // Firmware version [Hour] [0|31]
248 optional int32 llc_fbk_version_hour = 9;
250
252 // Control Message
253 // Brake control feedforward contribution [rev] [-6.5536|6.5534]
254 optional double llc_dbg_steeringsensorposition = 1;
255 // Brake control feedforward contribution [counts] [-32768|32767]
256 optional int32 llc_dbg_steeringrackinputtorque = 2;
257 // Brake control feedforward contribution [rev] [-83.88608|83.88607]
258 optional double llc_dbg_steeringmotorposition = 3;
260
262 // Control Message
264 ADC_CMD_TURNSIGNAL_NONE = 0;
265 ADC_CMD_TURNSIGNAL_LEFT = 1;
266 ADC_CMD_TURNSIGNAL_RIGHT = 2;
267 ADC_CMD_TURNSIGNAL_RESERVE = 3;
269 // Aux control heartbeat counter [] [0|3]
270 optional int32 adc_auxcontrol_counter = 1;
271 // Aux control checksum [] [0|255]
272 optional int32 adc_auxcontrol_checksum = 2;
273 // Control inverter override (default ON if not overridden) [T/F] [0|1]
274 optional bool adc_cmd_inverter_controlenable = 3;
275 // Control inverter [T/F] [0|1]
276 optional bool adc_cmd_inverter = 4;
277 // (Reserved) Control wiper [] [0|3]
278 optional int32 adc_cmd_wiper = 5;
279 // PDU Control Override (all channels default ON if not overridden) [T/F]
280 // [0|1]
281 optional bool adc_cmd_pdu_controlenable = 6;
282 // Control PDU Ch 8 (when override enabled) [T/F] [0|1]
283 optional bool adc_cmd_pdu_ch8 = 7;
284 // Control PDU Ch 7 (when override enabled) [T/F] [0|1]
285 optional bool adc_cmd_pdu_ch7 = 8;
286 // Control PDU Ch 6 (when override enabled) [T/F] [0|1]
287 optional bool adc_cmd_pdu_ch6 = 9;
288 // Control PDU Ch 5 (when override enabled) [T/F] [0|1]
289 optional bool adc_cmd_pdu_ch5 = 10;
290 // Control PDU Ch 4 (when override enabled) [T/F] [0|1]
291 optional bool adc_cmd_pdu_ch4 = 11;
292 // Control PDU Ch 3 (when override enabled) [T/F] [0|1]
293 optional bool adc_cmd_pdu_ch3 = 12;
294 // Control PDU Ch 2 (when override enabled) [T/F] [0|1]
295 optional bool adc_cmd_pdu_ch2 = 13;
296 // Control PDU Ch 1 (when override enabled) [T/F] [0|1]
297 optional bool adc_cmd_pdu_ch1 = 14;
298 // Control hazard lights [T/F] [0|1]
299 optional bool adc_cmd_hazardlights = 15;
300 // Control high beam [T/F] [0|1]
301 optional bool adc_cmd_highbeam = 16;
302 // Control low beam [T/F] [0|1]
303 optional bool adc_cmd_lowbeam = 17;
304 // Control horn [T/F] [0|1]
305 optional bool adc_cmd_horn = 18;
306 // Requested turn signals [] [0|3]
307 optional Adc_cmd_turnsignalType adc_cmd_turnsignal = 19;
309
311 // Control Message
312 // Brake control loop P contribution [mrev] [-51.2|51.1]
313 optional double llc_dbg_brakepidcontribution_p = 1;
314 // Brake control loop I contribution [mrev] [-51.2|51.1]
315 optional double llc_dbg_brakepidcontribution_i = 2;
316 // Brake control loop D contribution [mrev] [-51.2|51.1]
317 optional double llc_dbg_brakepidcontribution_d = 3;
318 // Brake control loop output [mrev] [-51.2|51.1]
319 optional double llc_dbg_brakepid_output = 4;
320 // Brake control loop error [psi] [-2048|2047]
321 optional int32 llc_dbg_brakepid_error = 5;
322 // Brake control feedforward contribution [mrev] [-1024|1023.5]
323 optional double llc_dbg_brakefeedforward = 6;
326message Transit {
327 optional Llc_vehiclelimits_24 llc_vehiclelimits_24 = 1; // report message
328 optional Adc_motioncontrol1_10 adc_motioncontrol1_10 = 2; // control message
329 optional Adc_motioncontrollimits1_12 adc_motioncontrollimits1_12 =
330 3; // control message
331 optional Llc_motionfeedback1_20 llc_motionfeedback1_20 = 4; // report message
332 optional Llc_motionfeedback2_21 llc_motionfeedback2_21 = 5; // report message
333 optional Llc_motioncommandfeedback1_22 llc_motioncommandfeedback1_22 =
334 6; // report message
335 optional Llc_vehiclestatus_25 llc_vehiclestatus_25 = 7; // report message
336 optional Llc_auxiliaryfeedback_120 llc_auxiliaryfeedback_120 =
337 8; // report message
338 optional Llc_diag_fault_620 llc_diag_fault_620 = 9; // report message
339 optional Llc_diag_steeringcontrol_722 llc_diag_steeringcontrol_722 =
340 10; // control message
341 optional Adc_auxiliarycontrol_110 adc_auxiliarycontrol_110 =
342 11; // control message
343 optional Llc_diag_brakecontrol_721 llc_diag_brakecontrol_721 =
344 12; // control message
345}
syntax
Definition transit.proto:1