001 /*----------------------------------------------------------------------------*/
002 /* Copyright (c) FIRST 2008-2012. All Rights Reserved. */
003 /* Open Source Software - may be modified and shared by FRC teams. The code */
004 /* must be accompanied by the FIRST BSD license file in the root directory of */
005 /* the project. */
006 /*----------------------------------------------------------------------------*/
007
008
009 package edu.wpi.first.wpilibj.can;
010
011 public class JaguarCANProtocol {
012
013 //*****************************************************************************
014 //
015 // The masks of the fields that are used in the message identifier.
016 //
017 //*****************************************************************************
018 public static final int CAN_MSGID_FULL_M = 0x1fffffff;
019 public static final int CAN_MSGID_DEVNO_M = 0x0000003f;
020 public static final int CAN_MSGID_API_M = 0x0000ffc0;
021 public static final int CAN_MSGID_MFR_M = 0x00ff0000;
022 public static final int CAN_MSGID_DTYPE_M = 0x1f000000;
023 public static final int CAN_MSGID_DEVNO_S = 0;
024 public static final int CAN_MSGID_API_S = 6;
025 public static final int CAN_MSGID_MFR_S = 16;
026 public static final int CAN_MSGID_DTYPE_S = 24;
027
028 //*****************************************************************************
029 //
030 // The Reserved device number values in the Message Id.
031 //
032 //*****************************************************************************
033 public static final int CAN_MSGID_DEVNO_BCAST = 0x00000000;
034
035 //*****************************************************************************
036 //
037 // The Reserved system control API numbers in the Message Id.
038 //
039 //*****************************************************************************
040 public static final int CAN_MSGID_API_SYSHALT = 0x00000000;
041 public static final int CAN_MSGID_API_SYSRST = 0x00000040;
042 public static final int CAN_MSGID_API_DEVASSIGN= 0x00000080;
043 public static final int CAN_MSGID_API_DEVQUERY = 0x000000c0;
044 public static final int CAN_MSGID_API_HEARTBEAT= 0x00000140;
045 public static final int CAN_MSGID_API_SYNC = 0x00000180;
046 public static final int CAN_MSGID_API_UPDATE = 0x000001c0;
047 public static final int CAN_MSGID_API_FIRMVER = 0x00000200;
048 public static final int CAN_MSGID_API_ENUMERATE= 0x00000240;
049 public static final int CAN_MSGID_API_SYSRESUME= 0x00000280;
050
051 //*****************************************************************************
052 //
053 // The 32 bit values associated with the CAN_MSGID_API_STATUS request.
054 //
055 //*****************************************************************************
056 public static final int CAN_STATUS_CODE_M = 0x0000ffff;
057 public static final int CAN_STATUS_MFG_M = 0x00ff0000;
058 public static final int CAN_STATUS_DTYPE_M = 0x1f000000;
059 public static final int CAN_STATUS_CODE_S = 0;
060 public static final int CAN_STATUS_MFG_S = 16;
061 public static final int CAN_STATUS_DTYPE_S = 24;
062
063 //*****************************************************************************
064 //
065 // The Reserved manufacturer identifiers in the Message Id.
066 //
067 //*****************************************************************************
068 public static final int CAN_MSGID_MFR_NI = 0x00010000;
069 public static final int CAN_MSGID_MFR_LM = 0x00020000;
070 public static final int CAN_MSGID_MFR_DEKA = 0x00030000;
071
072 //*****************************************************************************
073 //
074 // The Reserved device type identifiers in the Message Id.
075 //
076 //*****************************************************************************
077 public static final int CAN_MSGID_DTYPE_BCAST = 0x00000000;
078 public static final int CAN_MSGID_DTYPE_ROBOT = 0x01000000;
079 public static final int CAN_MSGID_DTYPE_MOTOR = 0x02000000;
080 public static final int CAN_MSGID_DTYPE_RELAY = 0x03000000;
081 public static final int CAN_MSGID_DTYPE_GYRO = 0x04000000;
082 public static final int CAN_MSGID_DTYPE_ACCEL = 0x05000000;
083 public static final int CAN_MSGID_DTYPE_USONIC = 0x06000000;
084 public static final int CAN_MSGID_DTYPE_GEART = 0x07000000;
085 public static final int CAN_MSGID_DTYPE_UPDATE = 0x1f000000;
086
087 //*****************************************************************************
088 //
089 // LM Motor Control API Classes API Class and ID masks.
090 //
091 //*****************************************************************************
092 public static final int CAN_MSGID_API_CLASS_M = 0x0000fc00;
093 public static final int CAN_MSGID_API_ID_M = 0x000003c0;
094
095 //*****************************************************************************
096 //
097 // LM Motor Control API Classes in the Message Id for non-broadcast.
098 // These are the upper 6 bits of the API field, the lower 4 bits determine
099 // the APIId.
100 //
101 //*****************************************************************************
102 public static final int CAN_API_MC_VOLTAGE = 0x00000000;
103 public static final int CAN_API_MC_SPD = 0x00000400;
104 public static final int CAN_API_MC_VCOMP = 0x00000800;
105 public static final int CAN_API_MC_POS = 0x00000c00;
106 public static final int CAN_API_MC_ICTRL = 0x00001000;
107 public static final int CAN_API_MC_STATUS = 0x00001400;
108 public static final int CAN_API_MC_PSTAT = 0x00001800;
109 public static final int CAN_API_MC_CFG = 0x00001c00;
110 public static final int CAN_API_MC_ACK = 0x00002000;
111
112 //*****************************************************************************
113 //
114 // The Stellaris Motor Class Control Voltage API definitions.
115 //
116 //*****************************************************************************
117 public static final int LM_API_VOLT = (CAN_MSGID_MFR_LM | CAN_MSGID_DTYPE_MOTOR |
118 CAN_API_MC_VOLTAGE);
119 public static final int LM_API_VOLT_EN = (LM_API_VOLT | (0 << CAN_MSGID_API_S));
120 public static final int LM_API_VOLT_DIS = (LM_API_VOLT | (1 << CAN_MSGID_API_S));
121 public static final int LM_API_VOLT_SET = (LM_API_VOLT | (2 << CAN_MSGID_API_S));
122 public static final int LM_API_VOLT_SET_RAMP = (LM_API_VOLT | (3 << CAN_MSGID_API_S));
123 //##### FIRST BEGIN #####
124 public static final int LM_API_VOLT_T_EN = (LM_API_VOLT | (4 << CAN_MSGID_API_S));
125 public static final int LM_API_VOLT_T_SET = (LM_API_VOLT | (5 << CAN_MSGID_API_S));
126 public static final int LM_API_VOLT_T_SET_NO_ACK = (LM_API_VOLT | (7 << CAN_MSGID_API_S));
127 //##### FIRST END #####
128 public static final int LM_API_VOLT_SET_NO_ACK = (LM_API_VOLT | (8 << CAN_MSGID_API_S));
129
130 //*****************************************************************************
131 //
132 // The Stellaris Motor Class Control API definitions for
133 // LM_API_VOLT_SET_RAMP.
134 //
135 //*****************************************************************************
136 public static final int LM_API_VOLT_RAMP_DIS = 0;
137
138 //*****************************************************************************
139 //
140 // The Stellaris Motor Class Control API definitions for CAN_MSGID_API_SYNC.
141 //
142 //*****************************************************************************
143 public static final int LM_API_SYNC_PEND_NOW = 0;
144
145 //*****************************************************************************
146 //
147 // The Stellaris Motor Class Speed Control API definitions.
148 //
149 //*****************************************************************************
150 public static final int LM_API_SPD = (CAN_MSGID_MFR_LM | CAN_MSGID_DTYPE_MOTOR |
151 CAN_API_MC_SPD);
152 public static final int LM_API_SPD_EN = (LM_API_SPD | (0 << CAN_MSGID_API_S));
153 public static final int LM_API_SPD_DIS = (LM_API_SPD | (1 << CAN_MSGID_API_S));
154 public static final int LM_API_SPD_SET = (LM_API_SPD | (2 << CAN_MSGID_API_S));
155 public static final int LM_API_SPD_PC = (LM_API_SPD | (3 << CAN_MSGID_API_S));
156 public static final int LM_API_SPD_IC = (LM_API_SPD | (4 << CAN_MSGID_API_S));
157 public static final int LM_API_SPD_DC = (LM_API_SPD | (5 << CAN_MSGID_API_S));
158 public static final int LM_API_SPD_REF = (LM_API_SPD | (6 << CAN_MSGID_API_S));
159 //##### FIRST BEGIN #####
160 public static final int LM_API_SPD_T_EN = (LM_API_SPD | (7 << CAN_MSGID_API_S));
161 public static final int LM_API_SPD_T_SET = (LM_API_SPD | (8 << CAN_MSGID_API_S));
162 public static final int LM_API_SPD_T_SET_NO_ACK
163 = (LM_API_SPD | (10 << CAN_MSGID_API_S));
164 //##### FIRST END #####
165 public static final int LM_API_SPD_SET_NO_ACK = (LM_API_SPD | (11 << CAN_MSGID_API_S));
166
167 //*****************************************************************************
168 //
169 // The Stellaris Motor Control Voltage Compensation Control API definitions.
170 //
171 //*****************************************************************************
172 public static final int LM_API_VCOMP = (CAN_MSGID_MFR_LM | CAN_MSGID_DTYPE_MOTOR |
173 CAN_API_MC_VCOMP);
174 public static final int LM_API_VCOMP_EN = (LM_API_VCOMP | (0 << CAN_MSGID_API_S));
175 public static final int LM_API_VCOMP_DIS = (LM_API_VCOMP | (1 << CAN_MSGID_API_S));
176 public static final int LM_API_VCOMP_SET = (LM_API_VCOMP | (2 << CAN_MSGID_API_S));
177 public static final int LM_API_VCOMP_IN_RAMP = (LM_API_VCOMP | (3 << CAN_MSGID_API_S));
178 public static final int LM_API_VCOMP_COMP_RAMP = (LM_API_VCOMP | (4 << CAN_MSGID_API_S));
179 //##### FIRST BEGIN #####
180 public static final int LM_API_VCOMP_T_EN = (LM_API_VCOMP | (5 << CAN_MSGID_API_S));
181 public static final int LM_API_VCOMP_T_SET = (LM_API_VCOMP | (6 << CAN_MSGID_API_S));
182 public static final int LM_API_VCOMP_T_SET_NO_ACK
183 = (LM_API_VCOMP | (8 << CAN_MSGID_API_S));
184 //##### FIRST END #####
185 public static final int LM_API_VCOMP_SET_NO_ACK
186 = (LM_API_VCOMP | (9 << CAN_MSGID_API_S));
187
188 //*****************************************************************************
189 //
190 // The Stellaris Motor Class Position Control API definitions.
191 //
192 //*****************************************************************************
193 public static final int LM_API_POS = (CAN_MSGID_MFR_LM | CAN_MSGID_DTYPE_MOTOR |
194 CAN_API_MC_POS);
195 public static final int LM_API_POS_EN = (LM_API_POS | (0 << CAN_MSGID_API_S));
196 public static final int LM_API_POS_DIS = (LM_API_POS | (1 << CAN_MSGID_API_S));
197 public static final int LM_API_POS_SET = (LM_API_POS | (2 << CAN_MSGID_API_S));
198 public static final int LM_API_POS_PC = (LM_API_POS | (3 << CAN_MSGID_API_S));
199 public static final int LM_API_POS_IC = (LM_API_POS | (4 << CAN_MSGID_API_S));
200 public static final int LM_API_POS_DC = (LM_API_POS | (5 << CAN_MSGID_API_S));
201 public static final int LM_API_POS_REF = (LM_API_POS | (6 << CAN_MSGID_API_S));
202 //##### FIRST BEGIN #####
203 public static final int LM_API_POS_T_EN = (LM_API_POS | (7 << CAN_MSGID_API_S));
204 public static final int LM_API_POS_T_SET = (LM_API_POS | (8 << CAN_MSGID_API_S));
205 public static final int LM_API_POS_T_SET_NO_ACK
206 = (LM_API_POS | (10 << CAN_MSGID_API_S));
207 //##### FIRST END #####
208 public static final int LM_API_POS_SET_NO_ACK = (LM_API_POS | (11 << CAN_MSGID_API_S));
209
210 //*****************************************************************************
211 //
212 // The Stellaris Motor Class Current Control API definitions.
213 //
214 //*****************************************************************************
215 public static final int LM_API_ICTRL = (CAN_MSGID_MFR_LM | CAN_MSGID_DTYPE_MOTOR |
216 CAN_API_MC_ICTRL);
217 public static final int LM_API_ICTRL_EN = (LM_API_ICTRL | (0 << CAN_MSGID_API_S));
218 public static final int LM_API_ICTRL_DIS = (LM_API_ICTRL | (1 << CAN_MSGID_API_S));
219 public static final int LM_API_ICTRL_SET = (LM_API_ICTRL | (2 << CAN_MSGID_API_S));
220 public static final int LM_API_ICTRL_PC = (LM_API_ICTRL | (3 << CAN_MSGID_API_S));
221 public static final int LM_API_ICTRL_IC = (LM_API_ICTRL | (4 << CAN_MSGID_API_S));
222 public static final int LM_API_ICTRL_DC = (LM_API_ICTRL | (5 << CAN_MSGID_API_S));
223 //##### FIRST BEGIN #####
224 public static final int LM_API_ICTRL_T_EN = (LM_API_ICTRL | (6 << CAN_MSGID_API_S));
225 public static final int LM_API_ICTRL_T_SET = (LM_API_ICTRL | (7 << CAN_MSGID_API_S));
226 public static final int LM_API_ICTRL_T_SET_NO_ACK
227 = (LM_API_ICTRL | (9 << CAN_MSGID_API_S));
228 //##### FIRST END #####
229 public static final int LM_API_ICTRL_SET_NO_ACK
230 = (LM_API_ICTRL | (10 << CAN_MSGID_API_S));
231
232 //*****************************************************************************
233 //
234 // The Stellaris Motor Class Firmware Update API definitions.
235 //
236 //*****************************************************************************
237 public static final int LM_API_UPD = (CAN_MSGID_MFR_LM | CAN_MSGID_DTYPE_UPDATE);
238 public static final int LM_API_UPD_PING = (LM_API_UPD | (0 << CAN_MSGID_API_S));
239 public static final int LM_API_UPD_DOWNLOAD = (LM_API_UPD | (1 << CAN_MSGID_API_S));
240 public static final int LM_API_UPD_SEND_DATA = (LM_API_UPD | (2 << CAN_MSGID_API_S));
241 public static final int LM_API_UPD_RESET = (LM_API_UPD | (3 << CAN_MSGID_API_S));
242 public static final int LM_API_UPD_ACK = (LM_API_UPD | (4 << CAN_MSGID_API_S));
243 public static final int LM_API_HWVER = (LM_API_UPD | (5 << CAN_MSGID_API_S));
244 public static final int LM_API_UPD_REQUEST = (LM_API_UPD | (6 << CAN_MSGID_API_S));
245 //##### FIRST BEGIN #####
246 public static final int LM_API_UNTRUST_EN = (LM_API_UPD | (11 << CAN_MSGID_API_S));
247 public static final int LM_API_TRUST_EN = (LM_API_UPD | (12 << CAN_MSGID_API_S));
248 public static final int LM_API_TRUST_HEARTBEAT = (LM_API_UPD | (13 << CAN_MSGID_API_S));
249 //##### FIRST END #####
250
251 //*****************************************************************************
252 //
253 // The Stellaris Motor Class Status API definitions.
254 //
255 //*****************************************************************************
256 public static final int LM_API_STATUS = (CAN_MSGID_MFR_LM | CAN_MSGID_DTYPE_MOTOR |
257 CAN_API_MC_STATUS);
258 public static final int LM_API_STATUS_VOLTOUT = (LM_API_STATUS | (0 << CAN_MSGID_API_S));
259 public static final int LM_API_STATUS_VOLTBUS = (LM_API_STATUS | (1 << CAN_MSGID_API_S));
260 public static final int LM_API_STATUS_CURRENT = (LM_API_STATUS | (2 << CAN_MSGID_API_S));
261 public static final int LM_API_STATUS_TEMP = (LM_API_STATUS | (3 << CAN_MSGID_API_S));
262 public static final int LM_API_STATUS_POS = (LM_API_STATUS | (4 << CAN_MSGID_API_S));
263 public static final int LM_API_STATUS_SPD = (LM_API_STATUS | (5 << CAN_MSGID_API_S));
264 public static final int LM_API_STATUS_LIMIT = (LM_API_STATUS | (6 << CAN_MSGID_API_S));
265 public static final int LM_API_STATUS_FAULT = (LM_API_STATUS | (7 << CAN_MSGID_API_S));
266 public static final int LM_API_STATUS_POWER = (LM_API_STATUS | (8 << CAN_MSGID_API_S));
267 public static final int LM_API_STATUS_CMODE = (LM_API_STATUS | (9 << CAN_MSGID_API_S));
268 public static final int LM_API_STATUS_VOUT = (LM_API_STATUS | (10 << CAN_MSGID_API_S));
269 public static final int LM_API_STATUS_STKY_FLT = (LM_API_STATUS | (11 << CAN_MSGID_API_S));
270 public static final int LM_API_STATUS_FLT_COUNT
271 = (LM_API_STATUS | (12 << CAN_MSGID_API_S));
272
273 //*****************************************************************************
274 //
275 // These definitions are used with the byte that is returned from
276 // the status request for LM_API_STATUS_LIMIT.
277 //
278 //*****************************************************************************
279 public static final int LM_STATUS_LIMIT_FWD = 0x01;
280 public static final int LM_STATUS_LIMIT_REV = 0x02;
281 public static final int LM_STATUS_LIMIT_SREV = 0x08;
282 public static final int LM_STATUS_LIMIT_STKY_FWD
283 = 0x10;
284 public static final int LM_STATUS_LIMIT_STKY_REV
285 = 0x20;
286 public static final int LM_STATUS_LIMIT_STKY_SFWD
287 = 0x40;
288 public static final int LM_STATUS_LIMIT_STKY_SREV
289 = 0x80;
290 //*****************************************************************************
291 //
292 // LM Motor Control status codes returned due to the CAN_STATUS_CODE_M field.
293 //
294 //*****************************************************************************
295 public static final int LM_STATUS_FAULT_ILIMIT = 0x01;
296 public static final int LM_STATUS_FAULT_TLIMIT = 0x02;
297 public static final int LM_STATUS_FAULT_VLIMIT = 0x04;
298
299 //*****************************************************************************
300 //
301 // The Stellaris Motor Class Configuration API definitions.
302 //
303 //*****************************************************************************
304 public static final int LM_API_CFG = (CAN_MSGID_MFR_LM | CAN_MSGID_DTYPE_MOTOR |
305 CAN_API_MC_CFG);
306 public static final int LM_API_CFG_NUM_BRUSHES = (LM_API_CFG | (0 << CAN_MSGID_API_S));
307 public static final int LM_API_CFG_ENC_LINES = (LM_API_CFG | (1 << CAN_MSGID_API_S));
308 public static final int LM_API_CFG_POT_TURNS = (LM_API_CFG | (2 << CAN_MSGID_API_S));
309 public static final int LM_API_CFG_BRAKE_COAST = (LM_API_CFG | (3 << CAN_MSGID_API_S));
310 public static final int LM_API_CFG_LIMIT_MODE = (LM_API_CFG | (4 << CAN_MSGID_API_S));
311 public static final int LM_API_CFG_LIMIT_FWD = (LM_API_CFG | (5 << CAN_MSGID_API_S));
312 public static final int LM_API_CFG_LIMIT_REV = (LM_API_CFG | (6 << CAN_MSGID_API_S));
313 public static final int LM_API_CFG_MAX_VOUT = (LM_API_CFG | (7 << CAN_MSGID_API_S));
314 public static final int LM_API_CFG_FAULT_TIME = (LM_API_CFG | (8 << CAN_MSGID_API_S));
315
316 //*****************************************************************************
317 //
318 // The Stellaris ACK API definition.
319 //
320 //*****************************************************************************
321 public static final int LM_API_ACK = (CAN_MSGID_MFR_LM | CAN_MSGID_DTYPE_MOTOR |
322 CAN_API_MC_ACK);
323
324 //*****************************************************************************
325 //
326 // The 8 bit values that can be returned by a call to LM_API_STATUS_HWVER.
327 //
328 //*****************************************************************************
329 public static final int LM_HWVER_UNKNOWN = 0x00;
330 public static final int LM_HWVER_JAG_1_0 = 0x01;
331 public static final int LM_HWVER_JAG_2_0 = 0x02;
332
333
334 //*****************************************************************************
335 //
336 // The 8 bit values that can be returned by a call to LM_API_STATUS_CMODE.
337 //
338 //*****************************************************************************
339 public static final int LM_STATUS_CMODE_VOLT = 0x00;
340 public static final int LM_STATUS_CMODE_CURRENT= 0x01;
341 public static final int LM_STATUS_CMODE_SPEED = 0x02;
342 public static final int LM_STATUS_CMODE_POS = 0x03;
343 public static final int LM_STATUS_CMODE_VCOMP = 0x04;
344
345 //*****************************************************************************
346 //
347 // The values that can specified as the position or speed reference. Not all
348 // values are valid for each reference; if an invalid reference is set, then
349 // none will be selected.
350 //
351 //*****************************************************************************
352 public static final int LM_REF_ENCODER = 0x00;
353 public static final int LM_REF_POT = 0x01;
354 public static final int LM_REF_INV_ENCODER = 0x02;
355 public static final int LM_REF_QUAD_ENCODER = 0x03;
356 public static final int LM_REF_NONE = 0xff;
357
358 //*****************************************************************************
359 //
360 // The flags that are used to indicate the currently active fault sources.
361 //
362 //*****************************************************************************
363 public static final int LM_FAULT_CURRENT = 0x01;
364 public static final int LM_FAULT_TEMP = 0x02;
365 public static final int LM_FAULT_VBUS = 0x04;
366 public static final int LM_FAULT_GATE_DRIVE = 0x08;
367 public static final int LM_FAULT_COMM = 0x10;
368
369 //*****************************************************************************
370 //
371 // The Stellaris Motor Class Periodic Status API definitions.
372 //
373 //*****************************************************************************
374 public static final int LM_API_PSTAT = (CAN_MSGID_MFR_LM | CAN_MSGID_DTYPE_MOTOR |
375 CAN_API_MC_PSTAT);
376 public static final int LM_API_PSTAT_PER_EN_S0 = (LM_API_PSTAT | (0 << CAN_MSGID_API_S));
377 public static final int LM_API_PSTAT_PER_EN_S1 = (LM_API_PSTAT | (1 << CAN_MSGID_API_S));
378 public static final int LM_API_PSTAT_PER_EN_S2 = (LM_API_PSTAT | (2 << CAN_MSGID_API_S));
379 public static final int LM_API_PSTAT_PER_EN_S3 = (LM_API_PSTAT | (3 << CAN_MSGID_API_S));
380 public static final int LM_API_PSTAT_CFG_S0 = (LM_API_PSTAT | (4 << CAN_MSGID_API_S));
381 public static final int LM_API_PSTAT_CFG_S1 = (LM_API_PSTAT | (5 << CAN_MSGID_API_S));
382 public static final int LM_API_PSTAT_CFG_S2 = (LM_API_PSTAT | (6 << CAN_MSGID_API_S));
383 public static final int LM_API_PSTAT_CFG_S3 = (LM_API_PSTAT | (7 << CAN_MSGID_API_S));
384 public static final int LM_API_PSTAT_DATA_S0 = (LM_API_PSTAT | (8 << CAN_MSGID_API_S));
385 public static final int LM_API_PSTAT_DATA_S1 = (LM_API_PSTAT | (9 << CAN_MSGID_API_S));
386 public static final int LM_API_PSTAT_DATA_S2 = (LM_API_PSTAT | (10 << CAN_MSGID_API_S));
387 public static final int LM_API_PSTAT_DATA_S3 = (LM_API_PSTAT | (11 << CAN_MSGID_API_S));
388
389 //*****************************************************************************
390 //
391 // The values that can be used to configure the data the Periodic Status
392 // Message bytes. Bytes of a multi-byte data values are encoded as
393 // little-endian, therefore B0 is the least significant byte.
394 //
395 //*****************************************************************************
396 public static final int LM_PSTAT_END = 0;
397 public static final int LM_PSTAT_VOLTOUT_B0 = 1;
398 public static final int LM_PSTAT_VOLTOUT_B1 = 2;
399 public static final int LM_PSTAT_VOLTBUS_B0 = 3;
400 public static final int LM_PSTAT_VOLTBUS_B1 = 4;
401 public static final int LM_PSTAT_CURRENT_B0 = 5;
402 public static final int LM_PSTAT_CURRENT_B1 = 6;
403 public static final int LM_PSTAT_TEMP_B0 = 7;
404 public static final int LM_PSTAT_TEMP_B1 = 8;
405 public static final int LM_PSTAT_POS_B0 = 9;
406 public static final int LM_PSTAT_POS_B1 = 10;
407 public static final int LM_PSTAT_POS_B2 = 11;
408 public static final int LM_PSTAT_POS_B3 = 12;
409 public static final int LM_PSTAT_SPD_B0 = 13;
410 public static final int LM_PSTAT_SPD_B1 = 14;
411 public static final int LM_PSTAT_SPD_B2 = 15;
412 public static final int LM_PSTAT_SPD_B3 = 16;
413 public static final int LM_PSTAT_LIMIT_NCLR = 17;
414 public static final int LM_PSTAT_LIMIT_CLR = 18;
415 public static final int LM_PSTAT_FAULT = 19;
416 public static final int LM_PSTAT_STKY_FLT_NCLR = 20;
417 public static final int LM_PSTAT_STKY_FLT_CLR = 21;
418 public static final int LM_PSTAT_VOUT_B0 = 22;
419 public static final int LM_PSTAT_VOUT_B1 = 23;
420 public static final int LM_PSTAT_FLT_COUNT_CURRENT
421 = 24;
422 public static final int LM_PSTAT_FLT_COUNT_TEMP
423 = 25;
424 public static final int LM_PSTAT_FLT_COUNT_VOLTBUS
425 = 26;
426 public static final int LM_PSTAT_FLT_COUNT_GATE
427 = 27;
428 public static final int LM_PSTAT_FLT_COUNT_COMM
429 = 28;
430 public static final int LM_PSTAT_CANSTS = 29;
431 public static final int LM_PSTAT_CANERR_B0 = 30;
432 public static final int LM_PSTAT_CANERR_B1 = 31;
433 }