44 #ifndef PALM_EDC_0220_ETHERCAT_PROTOCOL_H_INCLUDED 45 #define PALM_EDC_0220_ETHERCAT_PROTOCOL_H_INCLUDED 47 #include "../common/tactile_edc_ethercat_protocol.h" 48 #include "../common/ethercat_can_bridge_protocol.h" 49 #include "../common/common_edc_ethercat_protocol.h" 143 #define STRAIN_GAUGE_TYPE_COUPLED 0x0C 144 #define STRAIN_GAUGE_TYPE_DECOUPLED 0x0D 156 #define MOTOR_FLAG_BITS_CURRENT_CHOKE 0x000F 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 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 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 177 #define NO_TORQUE_CONTROL_ERROR_FLAGS ( MOTOR_FLAG_BITS_SGL_FAULT \ 178 | MOTOR_FLAG_BITS_SGR_FAULT ) 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 ) 186 #define PALM_0200_EDC_NO_DEMAND_TIMEOUT_MS 20 189 #ifndef NO_STRINGS // The PIC compiler doesn't deal well with strings. 194 "Current choke bit 7",
195 "Current choke bit 8",
196 "Current choke bit 9",
198 "EEPROM write in progress",
199 "Last CRC sent didn't match configs",
200 "Last config received was out of range",
201 "Jiggling in progress",
204 "Motor ID is invalid",
205 "No demand seen for more than 20ms",
206 "Fault with strain gauge 0: left",
208 "Fault with strain gauge 1: right",
209 "A3950 H-bridge nFault asserted",
210 "EEPROM contains bad CRC. Motor off.",
211 "Motor over temperature" 255 #define MOTOR_SYSTEM_RESET_KEY 0x5200 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 269 #define MOTOR_DEMAND_TORQUE_RANGE_MIN -0x7FFF 270 #define MOTOR_DEMAND_TORQUE_RANGE_MAX 0x7FFF 272 #define MOTOR_DEMAND_PWM_RANGE_MIN -0x03FF 273 #define MOTOR_DEMAND_PWM_RANGE_MAX 0x03FF 275 #define MOTOR_CONFIG_F_RANGE_MIN 0x0000 276 #define MOTOR_CONFIG_F_RANGE_MAX 0x7FFF 278 #define MOTOR_CONFIG_P_RANGE_MIN 0x0000 279 #define MOTOR_CONFIG_P_RANGE_MAX 0x7FFF 281 #define MOTOR_CONFIG_I_RANGE_MIN 0x0000 282 #define MOTOR_CONFIG_I_RANGE_MAX 0x7FFF 284 #define MOTOR_CONFIG_D_RANGE_MIN 0x0000 285 #define MOTOR_CONFIG_D_RANGE_MAX 0x7FFF 287 #define MOTOR_CONFIG_IMAX_RANGE_MIN 0x0000 288 #define MOTOR_CONFIG_IMAX_RANGE_MAX 0x3FFF 290 #define MOTOR_CONFIG_DEADBAND_RANGE_MIN 0x00 291 #define MOTOR_CONFIG_DEADBAND_RANGE_MAX 0xFF 293 #define MOTOR_CONFIG_SIGN_RANGE_MIN 0x00 294 #define MOTOR_CONFIG_SIGN_RANGE_MAX 0x01 296 #define MOTOR_DEMAND_TORQUE_LIMITER_GAIN_MIN -0x0200 297 #define MOTOR_DEMAND_TORQUE_LIMITER_GAIN_MAX 0x0200 300 #ifndef NO_STRINGS // The PIC compiler doesn't deal well with strings. 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",
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 358 #define SENSORS_NUM_0220 ((int)36) 361 #define JOINTS_NUM_0220 ((int)28) 398 }
__attribute__((packed)) ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS;
416 }
__attribute__((packed)) ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND;
424 #define PALM_0200_ETHERCAT_COMMAND_HEADER_SIZE ( sizeof(EDC_COMMAND) + sizeof(FROM_MOTOR_DATA_TYPE) + sizeof(int16s) ) 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) 434 #define ETHERCAT_STATUS_AGREED_SIZE 232 435 #define ETHERCAT_COMMAND_AGREED_SIZE 70 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) 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) static const char * palm_0200_edc_error_flag_names[16]
how long, in milliseconds, before it switches off the motor.
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.
The revision of the code.
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.
Year of assembly, E.G. 2012.
Maximum wind up of the integral term.
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.
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.
Same as MOTOR_DEMAND_TORQUE.
A zero is what happens if an EtherCAT packet doesn't get through, so it'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.
FROM_MOTOR_SLOW_DATA_TYPE
int16u misc
Some other value, determined by motor_data_type.
Internal derivative term from the torque controller / 256.
Temperature in 8.8 fixed point format.