0220_palm_edc_ethercat_protocol.h
Go to the documentation of this file.
1 //
2 // © 2010 Shadow Robot Company Limited.
3 //
4 // FileName: this_node.h
5 // Dependencies:
6 // Processor: PIC32
7 // Compiler: MPLAB® C32
8 //
9 // +------------------------------------------------------------------------+
10 // | This file is part of The Shadow Robot PIC32 firmware code base. |
11 // | |
12 // | It is free software: you can redistribute it and/or modify |
13 // | it under the terms of the GNU General Public License as published by |
14 // | the Free Software Foundation, either version 3 of the License, or |
15 // | (at your option) any later version. |
16 // | |
17 // | It is distributed in the hope that it will be useful, |
18 // | but WITHOUT ANY WARRANTY; without even the implied warranty of |
19 // | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the |
20 // | GNU General Public License for more details. |
21 // | |
22 // | You should have received a copy of the GNU General Public License |
23 // | along with this code repository. The text of the license can be found |
24 // | in Pic32/License/gpl.txt. If not, see <http://www.gnu.org/licenses/>. |
25 // +------------------------------------------------------------------------+
26 //
27 //
28 //
29 // Doxygen
30 // -------
31 //
42 //
43 
44 #ifndef PALM_EDC_0220_ETHERCAT_PROTOCOL_H_INCLUDED
45 #define PALM_EDC_0220_ETHERCAT_PROTOCOL_H_INCLUDED
46 
47 #include "../common/tactile_edc_ethercat_protocol.h"
48 #include "../common/ethercat_can_bridge_protocol.h"
49 #include "../common/common_edc_ethercat_protocol.h"
50 
51 
52 #define NUM_MOTORS 20
53 
54 
55 // ========================================================
56 //
57 // F R O M M O T O R D A T A T Y P E
58 //
59 // ========================================================
60 
61 
88 typedef enum
89 {
103 
108 
109 
110 // ========================================================
111 //
112 // S L O W D A T A
113 //
114 // ========================================================
115 
116 
117 typedef enum
118 {
129 
137 
139 
142 
143 #define STRAIN_GAUGE_TYPE_COUPLED 0x0C
144 #define STRAIN_GAUGE_TYPE_DECOUPLED 0x0D
145 
146 
147 // ========================================================
148 //
149 // F L A G S
150 //
151 // ========================================================
152 
153 
154  // Non serious flags, Just for information. Control still works.
155  // -------------------------------------------------------------
156 #define MOTOR_FLAG_BITS_CURRENT_CHOKE 0x000F
157 
158 #define MOTOR_FLAG_BITS_EEPROM_WRITING 0x0010
159 #define MOTOR_FLAG_BITS_LAST_CONFIG_CRC_FAILED 0x0020
160 #define MOTOR_FLAG_BITS_LAST_CONFIG_OUT_OF_RANGE 0x0040
161 #define MOTOR_FLAG_BITS_JIGGLING_IN_PROGRESS 0x0080
162 
163 
164  // Serious flags cause the motor to be switched off
165  // ------------------------------------------------
166 //#define 0x0100
167 #define MOTOR_FLAG_BITS_MOTOR_ID_IS_INVALID 0x0200
168 #define MOTOR_FLAG_BITS_NO_DEMAND_SEEN 0x0400
169 #define MOTOR_FLAG_BITS_SGL_FAULT 0x0800
170 
171 #define MOTOR_FLAG_BITS_SGR_FAULT 0x1000
172 #define MOTOR_FLAG_BITS_A3950_NFAULT 0x2000
173 #define MOTOR_FLAG_BITS_EEPROM_CONFIG_BAD_CRC 0x4000
174 #define MOTOR_FLAG_BITS_OVER_TEMP 0x8000
175 
176 
177 #define NO_TORQUE_CONTROL_ERROR_FLAGS ( MOTOR_FLAG_BITS_SGL_FAULT \
178  | MOTOR_FLAG_BITS_SGR_FAULT )
179 
180 #define PALM_0200_EDC_SERIOUS_ERROR_FLAGS ( MOTOR_FLAG_BITS_NO_DEMAND_SEEN \
181  | MOTOR_FLAG_BITS_A3950_NFAULT \
182  | MOTOR_FLAG_BITS_EEPROM_CONFIG_BAD_CRC \
183  | MOTOR_FLAG_BITS_OVER_TEMP )
184 
185 
186 #define PALM_0200_EDC_NO_DEMAND_TIMEOUT_MS 20
187 
189 #ifndef NO_STRINGS // The PIC compiler doesn't deal well with strings.
190 
193  static const char* palm_0200_edc_error_flag_names[16] = { "Current choke bit 6", // 0x0001
194  "Current choke bit 7", // 0x0002
195  "Current choke bit 8", // 0x0004
196  "Current choke bit 9", // 0x0008
197 
198  "EEPROM write in progress", // 0x0010
199  "Last CRC sent didn't match configs", // 0x0020
200  "Last config received was out of range", // 0x0040
201  "Jiggling in progress", // 0x0080
202 
203  "Invalid flag", // 0x0100
204  "Motor ID is invalid", // 0x0200
205  "No demand seen for more than 20ms", // 0x0400
206  "Fault with strain gauge 0: left", // 0x0800
207 
208  "Fault with strain gauge 1: right", // 0x1000
209  "A3950 H-bridge nFault asserted", // 0x2000
210  "EEPROM contains bad CRC. Motor off.", // 0x4000
211  "Motor over temperature" // 0x8000
212  };
213 #endif
214 
215 
216 
217 
218 
219 // ========================================================
220 //
221 // T O M O T O R D A T A T Y P E
222 //
223 // ========================================================
224 
229 typedef enum
230 {
234 
238 
254 
255 #define MOTOR_SYSTEM_RESET_KEY 0x5200
256 
257 #define MOTOR_SYSTEM_CONTROL_BACKLASH_COMPENSATION_ENABLE 0x0001
258 #define MOTOR_SYSTEM_CONTROL_BACKLASH_COMPENSATION_DISABLE 0x0002
259 #define MOTOR_SYSTEM_CONTROL_SGL_TRACKING_INC 0x0004
260 #define MOTOR_SYSTEM_CONTROL_SGL_TRACKING_DEC 0x0008
261 #define MOTOR_SYSTEM_CONTROL_SGR_TRACKING_INC 0x0010
262 #define MOTOR_SYSTEM_CONTROL_SGR_TRACKING_DEC 0x0020
263 #define MOTOR_SYSTEM_CONTROL_INITIATE_JIGGLING 0x0040
264 #define MOTOR_SYSTEM_CONTROL_EEPROM_WRITE 0x0080
266 
267 
268 
269 #define MOTOR_DEMAND_TORQUE_RANGE_MIN -0x7FFF
270 #define MOTOR_DEMAND_TORQUE_RANGE_MAX 0x7FFF
271 
272 #define MOTOR_DEMAND_PWM_RANGE_MIN -0x03FF
273 #define MOTOR_DEMAND_PWM_RANGE_MAX 0x03FF
274 
275 #define MOTOR_CONFIG_F_RANGE_MIN 0x0000
276 #define MOTOR_CONFIG_F_RANGE_MAX 0x7FFF
277 
278 #define MOTOR_CONFIG_P_RANGE_MIN 0x0000
279 #define MOTOR_CONFIG_P_RANGE_MAX 0x7FFF
280 
281 #define MOTOR_CONFIG_I_RANGE_MIN 0x0000
282 #define MOTOR_CONFIG_I_RANGE_MAX 0x7FFF
283 
284 #define MOTOR_CONFIG_D_RANGE_MIN 0x0000
285 #define MOTOR_CONFIG_D_RANGE_MAX 0x7FFF
286 
287 #define MOTOR_CONFIG_IMAX_RANGE_MIN 0x0000
288 #define MOTOR_CONFIG_IMAX_RANGE_MAX 0x3FFF
289 
290 #define MOTOR_CONFIG_DEADBAND_RANGE_MIN 0x00
291 #define MOTOR_CONFIG_DEADBAND_RANGE_MAX 0xFF
292 
293 #define MOTOR_CONFIG_SIGN_RANGE_MIN 0x00
294 #define MOTOR_CONFIG_SIGN_RANGE_MAX 0x01
295 
296 #define MOTOR_DEMAND_TORQUE_LIMITER_GAIN_MIN -0x0200
297 #define MOTOR_DEMAND_TORQUE_LIMITER_GAIN_MAX 0x0200
298 
299 
300 #ifndef NO_STRINGS // The PIC compiler doesn't deal well with strings.
301 
304  static const char* to_motor_data_type_names[16] = { "INVALID",
305  "Demand: Torque",
306  "Demand: PWM",
307  "INVALID",
308  "INVALID",
309  "INVALID",
310  "INVALID",
311  "Config: Maximum PWM value",
312  "Config: Strain gauge amp references. LSB = ref for SGL, MSB = ref for SGR",
313  "Config: Feed forward gain",
314  "Config: Proportional gain",
315  "Config: Integral gain",
316  "Config: Derivative gain",
317  "Config: Maximum integral windup",
318  "Config: MSB=Deadband. LSB=Sign",
319  "Config: CRC",
320  };
321 #endif
322 
323 
330 typedef enum
331 {
339 
340 
341 
344 typedef struct
345 {
349 
350 
351 
352 #define MESSAGE_ID_MOTOR_ID_SHIFT_POS 5
353 #define MESSAGE_ID_MOTOR_ID_BOTTOM_BIT 0b00000100000
354 #define MESSAGE_ID_MOTOR_ID_TOP_2_BITS 0b00110000000
355 
356 
357 
358 #define SENSORS_NUM_0220 ((int)36)
359 
361 #define JOINTS_NUM_0220 ((int)28)
362 
364 
365 //#if (int)IGNORE > SENSORS_NUM
366 // #error Not enough sensors[] in ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS
367 //#endif
368 
370 typedef struct
371 {
373 
378 
380  int16s which_motors;
383 
388 
389  MOTOR_DATA_PACKET motor_data_packet[10];
390 
394 
396 
398 } __attribute__((packed)) ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS;
399 
400 
401 
403 typedef struct
404 {
405  EDC_COMMAND EDC_command;
406 
408  int16s which_motors;
409 
412  int16s motor_data[NUM_MOTORS];
413 
414  int32u tactile_data_type;
415 
416 } __attribute__((packed)) ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND;
417 
418 /*
419 #define ETHERCAT_COMMAND_HEADER_SIZE ( sizeof(EDC_COMMAND) \ //!< What's the minimum amount of
420  + sizeof(FROM_MOTOR_DATA_TYPE) \
421  + sizeof(int16s) )
422 */
423 
424 #define PALM_0200_ETHERCAT_COMMAND_HEADER_SIZE ( sizeof(EDC_COMMAND) + sizeof(FROM_MOTOR_DATA_TYPE) + sizeof(int16s) )
425 
426 #define PALM_0200_ETHERCAT_STATUS_DATA_SIZE sizeof(ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS)
427 #define PALM_0200_ETHERCAT_COMMAND_DATA_SIZE sizeof(ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND)
428 
429  // Now we need to be *sure* that the Host and the Slave definitely
430  // agree on the size of the EtherCAT packets, even if the host is a
431  // 64-bit machine or something. So we have these calculated sizes.
432  // The host and slave can ASSERT that the sizeof() the packets
433  // matches the agreed sizes.
434 #define ETHERCAT_STATUS_AGREED_SIZE 232
435 #define ETHERCAT_COMMAND_AGREED_SIZE 70
436 
437 
438 
450 
451 #define PALM_0200_ETHERCAT_COMMAND_DATA_ADDRESS 0x1000
452 #define PALM_0200_ETHERCAT_CAN_BRIDGE_DATA_COMMAND_ADDRESS (PALM_0200_ETHERCAT_COMMAND_DATA_ADDRESS + PALM_0200_ETHERCAT_COMMAND_DATA_SIZE)
453 
454 #define PALM_0200_ETHERCAT_STATUS_DATA_ADDRESS (PALM_0200_ETHERCAT_CAN_BRIDGE_DATA_COMMAND_ADDRESS + ETHERCAT_CAN_BRIDGE_DATA_SIZE)
455 #define PALM_0200_ETHERCAT_CAN_BRIDGE_DATA_STATUS_ADDRESS (PALM_0200_ETHERCAT_STATUS_DATA_ADDRESS + PALM_0200_ETHERCAT_STATUS_DATA_SIZE)
456 
457 //#define NUM_CONFIGS_REQUIRED 5
458 
459 
460 #endif
static const char * palm_0200_edc_error_flag_names[16]
how long, in milliseconds, before it switches off the motor.
unsigned short int16u
Proportional gain of the FPID torque controller.
Typically 5000. I.E. Torque controller runs at 5kHz.
ADC reading of right strain gauge.
For safety, this is not a valid request.
Various bits to switch on / off misc things.
Derivative gain of the FPID torque controller.
FROM_MOTOR_DATA_TYPE from_motor_data_type
Which data does the host want from the motors?
Internal proportional term from the torque controller / 256.
Integral gain of the FPID torque controller.
FROM_MOTOR_DATA_TYPE motor_data_type
This is the last config (apart from the CRC, which is special)
Feed forward gain of the FPID torque controller.
For safety, this is not a data type.
static const char * to_motor_data_type_names[16]
LSB = Dead band. Unsigned 8 bit. MSB = Sign. 0=+ve. 1=-ve.
Torque=TO_MOTOR_DATA_TYPE. Misc=config value.
This is the torque value at which the torque limiter will kick in.
Strain gauge amp references. LSB = ref for SGL, MSB = ref for SGR.
ADC reading of left strain gauge.
Internal integral term from the torque controller / 256.
int16s torque
Measured Motor Torque.
This needs to be a #define for symmetry with SENSORS_NUM.
int32u tactile_data_type
Request for specific tactile data.
Number of CAN messages received by this motor.
int16u idle_time_us
packet, and the next packet arriving. Ideally, this number should be more than 50.
Spoof the temperature sensor.
unsigned int int32u
Maximum wind up of the integral term.
Maximum integral windup.
Spoof the current sensor.
Day/Month of assembly. E.G. 0x0A1F means October 31st.
Put an upper limit on the absolute value of the motor PWM. Range [0..0x03FF].
EDC_COMMAND EDC_command
What type of data should the palm send back in the next packet?
LSB = TX error counter. MSB = RX error counter.
Did the local code have any uncomitted modifications at build time?
Spoof the right strain gauge sensor.
Spoof the left strain gauge sensor.
Important to know that this is the last one.
Number of CAN messages transmitted by this motor.
See error_flag_names[].
TO_MOTOR_DATA_TYPE to_motor_data_type
Request for specific motor data.
int32u which_motor_data_had_errors
Bit N set when motor sends bad CAN message Ideally, no bits get set.
Send with a demand value of 0x520x to reset motor x.
int32u which_motor_data_arrived
Bit N set when motor CAN message arrives. Ideally, bits 0..19 get set.
This is the proportional gain term for the torque limit controller.
0x0C = coupled gauges. 0x0D = decoupled gauges.
Demanding torque activates the Torque PID loop.
The gear ratio of the motor. E.G. 131 or 128.
A zero is what happens if an EtherCAT packet doesn&#39;t get through, so it&#39;s considered a special case...
Current motor PWM duty cycle.
See FROM_MOTOR_SLOW_DATA_TYPE.
EDC_COMMAND
The host can request different types of data from the palm.
This is the first TO_MOTOR_DATA_TYPE which is actually a configuration and should be stored in EEPROM...
int16u tactile_data_valid
Bit 0: FF. Bit 4: TH.
#define SENSORS_NUM_0220
int16u misc
Some other value, determined by motor_data_type.
signed short int16s
Internal derivative term from the torque controller / 256.
Temperature in 8.8 fixed point format.


sr_external_dependencies
Author(s): Ugo Cupcic
autogenerated on Mon Feb 28 2022 23:50:40