WPILibC++  trunk
can_proto.h
1 //*****************************************************************************
2 //
3 // can_proto.h - Definitions for the CAN protocol used to communicate with the
4 // BDC motor controller.
5 //
6 // Copyright (c) 2008 Texas Instruments Incorporated. All rights reserved.
7 // TI Information - Selective Disclosure
8 //
9 //*****************************************************************************
10 
11 #ifndef __CAN_PROTO_H__
12 #define __CAN_PROTO_H__
13 
14 //*****************************************************************************
15 //
16 // The masks of the fields that are used in the message identifier.
17 //
18 //*****************************************************************************
19 #define CAN_MSGID_FULL_M 0x1fffffff
20 #define CAN_MSGID_DEVNO_M 0x0000003f
21 #define CAN_MSGID_API_M 0x0000ffc0
22 #define CAN_MSGID_MFR_M 0x00ff0000
23 #define CAN_MSGID_DTYPE_M 0x1f000000
24 #define CAN_MSGID_DEVNO_S 0
25 #define CAN_MSGID_API_S 6
26 #define CAN_MSGID_MFR_S 16
27 #define CAN_MSGID_DTYPE_S 24
28 
29 //*****************************************************************************
30 //
31 // The Reserved device number values in the Message Id.
32 //
33 //*****************************************************************************
34 #define CAN_MSGID_DEVNO_BCAST 0x00000000
35 
36 //*****************************************************************************
37 //
38 // The Reserved system control API numbers in the Message Id.
39 //
40 //*****************************************************************************
41 #define CAN_MSGID_API_SYSHALT 0x00000000
42 #define CAN_MSGID_API_SYSRST 0x00000040
43 #define CAN_MSGID_API_DEVASSIGN 0x00000080
44 #define CAN_MSGID_API_DEVQUERY 0x000000c0
45 #define CAN_MSGID_API_HEARTBEAT 0x00000140
46 #define CAN_MSGID_API_SYNC 0x00000180
47 #define CAN_MSGID_API_UPDATE 0x000001c0
48 #define CAN_MSGID_API_FIRMVER 0x00000200
49 #define CAN_MSGID_API_ENUMERATE 0x00000240
50 #define CAN_MSGID_API_SYSRESUME 0x00000280
51 
52 //*****************************************************************************
53 //
54 // The 32 bit values associated with the CAN_MSGID_API_STATUS request.
55 //
56 //*****************************************************************************
57 #define CAN_STATUS_CODE_M 0x0000ffff
58 #define CAN_STATUS_MFG_M 0x00ff0000
59 #define CAN_STATUS_DTYPE_M 0x1f000000
60 #define CAN_STATUS_CODE_S 0
61 #define CAN_STATUS_MFG_S 16
62 #define CAN_STATUS_DTYPE_S 24
63 
64 //*****************************************************************************
65 //
66 // The Reserved manufacturer identifiers in the Message Id.
67 //
68 //*****************************************************************************
69 #define CAN_MSGID_MFR_NI 0x00010000
70 #define CAN_MSGID_MFR_LM 0x00020000
71 #define CAN_MSGID_MFR_DEKA 0x00030000
72 
73 //*****************************************************************************
74 //
75 // The Reserved device type identifiers in the Message Id.
76 //
77 //*****************************************************************************
78 #define CAN_MSGID_DTYPE_BCAST 0x00000000
79 #define CAN_MSGID_DTYPE_ROBOT 0x01000000
80 #define CAN_MSGID_DTYPE_MOTOR 0x02000000
81 #define CAN_MSGID_DTYPE_RELAY 0x03000000
82 #define CAN_MSGID_DTYPE_GYRO 0x04000000
83 #define CAN_MSGID_DTYPE_ACCEL 0x05000000
84 #define CAN_MSGID_DTYPE_USONIC 0x06000000
85 #define CAN_MSGID_DTYPE_GEART 0x07000000
86 #define CAN_MSGID_DTYPE_UPDATE 0x1f000000
87 
88 //*****************************************************************************
89 //
90 // LM Motor Control API Classes API Class and ID masks.
91 //
92 //*****************************************************************************
93 #define CAN_MSGID_API_CLASS_M 0x0000fc00
94 #define CAN_MSGID_API_ID_M 0x000003c0
95 
96 //*****************************************************************************
97 //
98 // LM Motor Control API Classes in the Message Id for non-broadcast.
99 // These are the upper 6 bits of the API field, the lower 4 bits determine
100 // the APIId.
101 //
102 //*****************************************************************************
103 #define CAN_API_MC_VOLTAGE 0x00000000
104 #define CAN_API_MC_SPD 0x00000400
105 #define CAN_API_MC_VCOMP 0x00000800
106 #define CAN_API_MC_POS 0x00000c00
107 #define CAN_API_MC_ICTRL 0x00001000
108 #define CAN_API_MC_STATUS 0x00001400
109 #define CAN_API_MC_PSTAT 0x00001800
110 #define CAN_API_MC_CFG 0x00001c00
111 #define CAN_API_MC_ACK 0x00002000
112 
113 //*****************************************************************************
114 //
115 // The Stellaris Motor Class Control Voltage API definitions.
116 //
117 //*****************************************************************************
118 #define LM_API_VOLT (CAN_MSGID_MFR_LM | CAN_MSGID_DTYPE_MOTOR | \
119  CAN_API_MC_VOLTAGE)
120 #define LM_API_VOLT_EN (LM_API_VOLT | (0 << CAN_MSGID_API_S))
121 #define LM_API_VOLT_DIS (LM_API_VOLT | (1 << CAN_MSGID_API_S))
122 #define LM_API_VOLT_SET (LM_API_VOLT | (2 << CAN_MSGID_API_S))
123 #define LM_API_VOLT_SET_RAMP (LM_API_VOLT | (3 << CAN_MSGID_API_S))
124 //##### FIRST BEGIN #####
125 #define LM_API_VOLT_T_EN (LM_API_VOLT | (4 << CAN_MSGID_API_S))
126 #define LM_API_VOLT_T_SET (LM_API_VOLT | (5 << CAN_MSGID_API_S))
127 #define LM_API_VOLT_T_SET_NO_ACK \
128  (LM_API_VOLT | (7 << CAN_MSGID_API_S))
129 //##### FIRST END #####
130 #define LM_API_VOLT_SET_NO_ACK (LM_API_VOLT | (8 << CAN_MSGID_API_S))
131 
132 //*****************************************************************************
133 //
134 // The Stellaris Motor Class Control API definitions for LM_API_VOLT_SET_RAMP.
135 //
136 //*****************************************************************************
137 #define LM_API_VOLT_RAMP_DIS 0
138 
139 //*****************************************************************************
140 //
141 // The Stellaris Motor Class Control API definitions for CAN_MSGID_API_SYNC.
142 //
143 //*****************************************************************************
144 #define LM_API_SYNC_PEND_NOW 0
145 
146 //*****************************************************************************
147 //
148 // The Stellaris Motor Class Speed Control API definitions.
149 //
150 //*****************************************************************************
151 #define LM_API_SPD (CAN_MSGID_MFR_LM | CAN_MSGID_DTYPE_MOTOR | \
152  CAN_API_MC_SPD)
153 #define LM_API_SPD_EN (LM_API_SPD | (0 << CAN_MSGID_API_S))
154 #define LM_API_SPD_DIS (LM_API_SPD | (1 << CAN_MSGID_API_S))
155 #define LM_API_SPD_SET (LM_API_SPD | (2 << CAN_MSGID_API_S))
156 #define LM_API_SPD_PC (LM_API_SPD | (3 << CAN_MSGID_API_S))
157 #define LM_API_SPD_IC (LM_API_SPD | (4 << CAN_MSGID_API_S))
158 #define LM_API_SPD_DC (LM_API_SPD | (5 << CAN_MSGID_API_S))
159 #define LM_API_SPD_REF (LM_API_SPD | (6 << CAN_MSGID_API_S))
160 //##### FIRST BEGIN #####
161 #define LM_API_SPD_T_EN (LM_API_SPD | (7 << CAN_MSGID_API_S))
162 #define LM_API_SPD_T_SET (LM_API_SPD | (8 << CAN_MSGID_API_S))
163 #define LM_API_SPD_T_SET_NO_ACK (LM_API_SPD | (10 << CAN_MSGID_API_S))
164 //##### FIRST END #####
165 #define 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 #define LM_API_VCOMP (CAN_MSGID_MFR_LM | CAN_MSGID_DTYPE_MOTOR | \
173  CAN_API_MC_VCOMP)
174 #define LM_API_VCOMP_EN (LM_API_VCOMP | (0 << CAN_MSGID_API_S))
175 #define LM_API_VCOMP_DIS (LM_API_VCOMP | (1 << CAN_MSGID_API_S))
176 #define LM_API_VCOMP_SET (LM_API_VCOMP | (2 << CAN_MSGID_API_S))
177 #define LM_API_VCOMP_IN_RAMP (LM_API_VCOMP | (3 << CAN_MSGID_API_S))
178 #define LM_API_VCOMP_COMP_RAMP (LM_API_VCOMP | (4 << CAN_MSGID_API_S))
179 //##### FIRST BEGIN #####
180 #define LM_API_VCOMP_T_EN (LM_API_VCOMP | (5 << CAN_MSGID_API_S))
181 #define LM_API_VCOMP_T_SET (LM_API_VCOMP | (6 << CAN_MSGID_API_S))
182 #define LM_API_VCOMP_T_SET_NO_ACK \
183  (LM_API_VCOMP | (8 << CAN_MSGID_API_S))
184 //##### FIRST END #####
185 #define LM_API_VCOMP_SET_NO_ACK (LM_API_VCOMP | (9 << CAN_MSGID_API_S))
186 
187 //*****************************************************************************
188 //
189 // The Stellaris Motor Class Position Control API definitions.
190 //
191 //*****************************************************************************
192 #define LM_API_POS (CAN_MSGID_MFR_LM | CAN_MSGID_DTYPE_MOTOR | \
193  CAN_API_MC_POS)
194 #define LM_API_POS_EN (LM_API_POS | (0 << CAN_MSGID_API_S))
195 #define LM_API_POS_DIS (LM_API_POS | (1 << CAN_MSGID_API_S))
196 #define LM_API_POS_SET (LM_API_POS | (2 << CAN_MSGID_API_S))
197 #define LM_API_POS_PC (LM_API_POS | (3 << CAN_MSGID_API_S))
198 #define LM_API_POS_IC (LM_API_POS | (4 << CAN_MSGID_API_S))
199 #define LM_API_POS_DC (LM_API_POS | (5 << CAN_MSGID_API_S))
200 #define LM_API_POS_REF (LM_API_POS | (6 << CAN_MSGID_API_S))
201 //##### FIRST BEGIN #####
202 #define LM_API_POS_T_EN (LM_API_POS | (7 << CAN_MSGID_API_S))
203 #define LM_API_POS_T_SET (LM_API_POS | (8 << CAN_MSGID_API_S))
204 #define LM_API_POS_T_SET_NO_ACK (LM_API_POS | (10 << CAN_MSGID_API_S))
205 //##### FIRST END #####
206 #define LM_API_POS_SET_NO_ACK (LM_API_POS | (11 << CAN_MSGID_API_S))
207 
208 //*****************************************************************************
209 //
210 // The Stellaris Motor Class Current Control API definitions.
211 //
212 //*****************************************************************************
213 #define LM_API_ICTRL (CAN_MSGID_MFR_LM | CAN_MSGID_DTYPE_MOTOR | \
214  CAN_API_MC_ICTRL)
215 #define LM_API_ICTRL_EN (LM_API_ICTRL | (0 << CAN_MSGID_API_S))
216 #define LM_API_ICTRL_DIS (LM_API_ICTRL | (1 << CAN_MSGID_API_S))
217 #define LM_API_ICTRL_SET (LM_API_ICTRL | (2 << CAN_MSGID_API_S))
218 #define LM_API_ICTRL_PC (LM_API_ICTRL | (3 << CAN_MSGID_API_S))
219 #define LM_API_ICTRL_IC (LM_API_ICTRL | (4 << CAN_MSGID_API_S))
220 #define LM_API_ICTRL_DC (LM_API_ICTRL | (5 << CAN_MSGID_API_S))
221 //##### FIRST BEGIN #####
222 #define LM_API_ICTRL_T_EN (LM_API_ICTRL | (6 << CAN_MSGID_API_S))
223 #define LM_API_ICTRL_T_SET (LM_API_ICTRL | (7 << CAN_MSGID_API_S))
224 #define LM_API_ICTRL_T_SET_NO_ACK \
225  (LM_API_ICTRL | (9 << CAN_MSGID_API_S))
226 //##### FIRST END #####
227 #define LM_API_ICTRL_SET_NO_ACK (LM_API_ICTRL | (10 << CAN_MSGID_API_S))
228 
229 //*****************************************************************************
230 //
231 // The Stellaris Motor Class Firmware Update API definitions.
232 //
233 //*****************************************************************************
234 #define LM_API_UPD (CAN_MSGID_MFR_LM | CAN_MSGID_DTYPE_UPDATE)
235 #define LM_API_UPD_PING (LM_API_UPD | (0 << CAN_MSGID_API_S))
236 #define LM_API_UPD_DOWNLOAD (LM_API_UPD | (1 << CAN_MSGID_API_S))
237 #define LM_API_UPD_SEND_DATA (LM_API_UPD | (2 << CAN_MSGID_API_S))
238 #define LM_API_UPD_RESET (LM_API_UPD | (3 << CAN_MSGID_API_S))
239 #define LM_API_UPD_ACK (LM_API_UPD | (4 << CAN_MSGID_API_S))
240 #define LM_API_HWVER (LM_API_UPD | (5 << CAN_MSGID_API_S))
241 #define LM_API_UPD_REQUEST (LM_API_UPD | (6 << CAN_MSGID_API_S))
242 //##### FIRST BEGIN #####
243 #define LM_API_UNTRUST_EN (LM_API_UPD | (11 << CAN_MSGID_API_S))
244 #define LM_API_TRUST_EN (LM_API_UPD | (12 << CAN_MSGID_API_S))
245 #define LM_API_TRUST_HEARTBEAT (LM_API_UPD | (13 << CAN_MSGID_API_S))
246 //##### FIRST END #####
247 
248 //*****************************************************************************
249 //
250 // The Stellaris Motor Class Status API definitions.
251 //
252 //*****************************************************************************
253 #define LM_API_STATUS (CAN_MSGID_MFR_LM | CAN_MSGID_DTYPE_MOTOR | \
254  CAN_API_MC_STATUS)
255 #define LM_API_STATUS_VOLTOUT (LM_API_STATUS | (0 << CAN_MSGID_API_S))
256 #define LM_API_STATUS_VOLTBUS (LM_API_STATUS | (1 << CAN_MSGID_API_S))
257 #define LM_API_STATUS_CURRENT (LM_API_STATUS | (2 << CAN_MSGID_API_S))
258 #define LM_API_STATUS_TEMP (LM_API_STATUS | (3 << CAN_MSGID_API_S))
259 #define LM_API_STATUS_POS (LM_API_STATUS | (4 << CAN_MSGID_API_S))
260 #define LM_API_STATUS_SPD (LM_API_STATUS | (5 << CAN_MSGID_API_S))
261 #define LM_API_STATUS_LIMIT (LM_API_STATUS | (6 << CAN_MSGID_API_S))
262 #define LM_API_STATUS_FAULT (LM_API_STATUS | (7 << CAN_MSGID_API_S))
263 #define LM_API_STATUS_POWER (LM_API_STATUS | (8 << CAN_MSGID_API_S))
264 #define LM_API_STATUS_CMODE (LM_API_STATUS | (9 << CAN_MSGID_API_S))
265 #define LM_API_STATUS_VOUT (LM_API_STATUS | (10 << CAN_MSGID_API_S))
266 #define LM_API_STATUS_STKY_FLT (LM_API_STATUS | (11 << CAN_MSGID_API_S))
267 #define LM_API_STATUS_FLT_COUNT (LM_API_STATUS | (12 << CAN_MSGID_API_S))
268 
269 //*****************************************************************************
270 //
271 // These definitions are used with the byte that is returned from
272 // the status request for LM_API_STATUS_LIMIT.
273 //
274 //*****************************************************************************
275 #define LM_STATUS_LIMIT_FWD 0x01
276 #define LM_STATUS_LIMIT_REV 0x02
277 #define LM_STATUS_LIMIT_SFWD 0x04
278 #define LM_STATUS_LIMIT_SREV 0x08
279 #define LM_STATUS_LIMIT_STKY_FWD \
280  0x10
281 #define LM_STATUS_LIMIT_STKY_REV \
282  0x20
283 #define LM_STATUS_LIMIT_STKY_SFWD \
284  0x40
285 #define LM_STATUS_LIMIT_STKY_SREV \
286  0x80
287 
288 //*****************************************************************************
289 //
290 // LM Motor Control status codes returned due to the CAN_STATUS_CODE_M field.
291 //
292 //*****************************************************************************
293 #define LM_STATUS_FAULT_ILIMIT 0x01
294 #define LM_STATUS_FAULT_TLIMIT 0x02
295 #define LM_STATUS_FAULT_VLIMIT 0x04
296 
297 //*****************************************************************************
298 //
299 // The Stellaris Motor Class Configuration API definitions.
300 //
301 //*****************************************************************************
302 #define LM_API_CFG (CAN_MSGID_MFR_LM | CAN_MSGID_DTYPE_MOTOR | \
303  CAN_API_MC_CFG)
304 #define LM_API_CFG_NUM_BRUSHES (LM_API_CFG | (0 << CAN_MSGID_API_S))
305 #define LM_API_CFG_ENC_LINES (LM_API_CFG | (1 << CAN_MSGID_API_S))
306 #define LM_API_CFG_POT_TURNS (LM_API_CFG | (2 << CAN_MSGID_API_S))
307 #define LM_API_CFG_BRAKE_COAST (LM_API_CFG | (3 << CAN_MSGID_API_S))
308 #define LM_API_CFG_LIMIT_MODE (LM_API_CFG | (4 << CAN_MSGID_API_S))
309 #define LM_API_CFG_LIMIT_FWD (LM_API_CFG | (5 << CAN_MSGID_API_S))
310 #define LM_API_CFG_LIMIT_REV (LM_API_CFG | (6 << CAN_MSGID_API_S))
311 #define LM_API_CFG_MAX_VOUT (LM_API_CFG | (7 << CAN_MSGID_API_S))
312 #define LM_API_CFG_FAULT_TIME (LM_API_CFG | (8 << CAN_MSGID_API_S))
313 
314 //*****************************************************************************
315 //
316 // The Stellaris ACK API definition.
317 //
318 //*****************************************************************************
319 #define LM_API_ACK (CAN_MSGID_MFR_LM | CAN_MSGID_DTYPE_MOTOR | \
320  CAN_API_MC_ACK)
321 
322 //*****************************************************************************
323 //
324 // The 8 bit values that can be returned by a call to LM_API_STATUS_HWVER.
325 //
326 //*****************************************************************************
327 #define LM_HWVER_UNKNOWN 0x00
328 #define LM_HWVER_JAG_1_0 0x01
329 #define LM_HWVER_JAG_2_0 0x02
330 
331 //*****************************************************************************
332 //
333 // The 8 bit values that can be returned by a call to LM_API_STATUS_CMODE.
334 //
335 //*****************************************************************************
336 #define LM_STATUS_CMODE_VOLT 0x00
337 #define LM_STATUS_CMODE_CURRENT 0x01
338 #define LM_STATUS_CMODE_SPEED 0x02
339 #define LM_STATUS_CMODE_POS 0x03
340 #define LM_STATUS_CMODE_VCOMP 0x04
341 
342 //*****************************************************************************
343 //
344 // The values that can specified as the position or speed reference. Not all
345 // values are valid for each reference; if an invalid reference is set, then
346 // none will be selected.
347 //
348 //*****************************************************************************
349 #define LM_REF_ENCODER 0x00
350 #define LM_REF_POT 0x01
351 #define LM_REF_INV_ENCODER 0x02
352 #define LM_REF_QUAD_ENCODER 0x03
353 #define LM_REF_NONE 0xff
354 
355 //*****************************************************************************
356 //
357 // The flags that are used to indicate the currently active fault sources.
358 //
359 //*****************************************************************************
360 #define LM_FAULT_CURRENT 0x01
361 #define LM_FAULT_TEMP 0x02
362 #define LM_FAULT_VBUS 0x04
363 #define LM_FAULT_GATE_DRIVE 0x08
364 #define LM_FAULT_COMM 0x10
365 
366 //*****************************************************************************
367 //
368 // The Stellaris Motor Class Periodic Status API definitions.
369 //
370 //*****************************************************************************
371 #define LM_API_PSTAT (CAN_MSGID_MFR_LM | CAN_MSGID_DTYPE_MOTOR | \
372  CAN_API_MC_PSTAT)
373 #define LM_API_PSTAT_PER_EN_S0 (LM_API_PSTAT | (0 << CAN_MSGID_API_S))
374 #define LM_API_PSTAT_PER_EN_S1 (LM_API_PSTAT | (1 << CAN_MSGID_API_S))
375 #define LM_API_PSTAT_PER_EN_S2 (LM_API_PSTAT | (2 << CAN_MSGID_API_S))
376 #define LM_API_PSTAT_PER_EN_S3 (LM_API_PSTAT | (3 << CAN_MSGID_API_S))
377 #define LM_API_PSTAT_CFG_S0 (LM_API_PSTAT | (4 << CAN_MSGID_API_S))
378 #define LM_API_PSTAT_CFG_S1 (LM_API_PSTAT | (5 << CAN_MSGID_API_S))
379 #define LM_API_PSTAT_CFG_S2 (LM_API_PSTAT | (6 << CAN_MSGID_API_S))
380 #define LM_API_PSTAT_CFG_S3 (LM_API_PSTAT | (7 << CAN_MSGID_API_S))
381 #define LM_API_PSTAT_DATA_S0 (LM_API_PSTAT | (8 << CAN_MSGID_API_S))
382 #define LM_API_PSTAT_DATA_S1 (LM_API_PSTAT | (9 << CAN_MSGID_API_S))
383 #define LM_API_PSTAT_DATA_S2 (LM_API_PSTAT | (10 << CAN_MSGID_API_S))
384 #define LM_API_PSTAT_DATA_S3 (LM_API_PSTAT | (11 << CAN_MSGID_API_S))
385 
386 //*****************************************************************************
387 //
388 // The values that can be used to configure the data the Periodic Status
389 // Message bytes. Bytes of a multi-byte data values are encoded as
390 // little-endian, therefore B0 is the least significant byte.
391 //
392 //*****************************************************************************
393 #define LM_PSTAT_END 0
394 #define LM_PSTAT_VOLTOUT_B0 1
395 #define LM_PSTAT_VOLTOUT_B1 2
396 #define LM_PSTAT_VOLTBUS_B0 3
397 #define LM_PSTAT_VOLTBUS_B1 4
398 #define LM_PSTAT_CURRENT_B0 5
399 #define LM_PSTAT_CURRENT_B1 6
400 #define LM_PSTAT_TEMP_B0 7
401 #define LM_PSTAT_TEMP_B1 8
402 #define LM_PSTAT_POS_B0 9
403 #define LM_PSTAT_POS_B1 10
404 #define LM_PSTAT_POS_B2 11
405 #define LM_PSTAT_POS_B3 12
406 #define LM_PSTAT_SPD_B0 13
407 #define LM_PSTAT_SPD_B1 14
408 #define LM_PSTAT_SPD_B2 15
409 #define LM_PSTAT_SPD_B3 16
410 #define LM_PSTAT_LIMIT_NCLR 17
411 #define LM_PSTAT_LIMIT_CLR 18
412 #define LM_PSTAT_FAULT 19
413 #define LM_PSTAT_STKY_FLT_NCLR 20
414 #define LM_PSTAT_STKY_FLT_CLR 21
415 #define LM_PSTAT_VOUT_B0 22
416 #define LM_PSTAT_VOUT_B1 23
417 #define LM_PSTAT_FLT_COUNT_CURRENT \
418  24
419 #define LM_PSTAT_FLT_COUNT_TEMP 25
420 #define LM_PSTAT_FLT_COUNT_VOLTBUS \
421  26
422 #define LM_PSTAT_FLT_COUNT_GATE 27
423 #define LM_PSTAT_FLT_COUNT_COMM 28
424 #define LM_PSTAT_CANSTS 29
425 #define LM_PSTAT_CANERR_B0 30
426 #define LM_PSTAT_CANERR_B1 31
427 
428 #endif // __CAN_PROTO_H__