44 #ifndef PALM_EDC_0320_ETHERCAT_PROTOCOL_H_INCLUDED 45 #define PALM_EDC_0320_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" 52 #define NUM_MUSCLES 40 53 #define NUM_PRESSURE_SENSORS_PER_MESSAGE 5 54 #define NUM_MUSCLE_DATA_PACKETS 8 115 #define MUSCLE_FLAG_BITS_NO_DEMAND_SEEN 0x0400 118 #define PALM_0300_EDC_SERIOUS_ERROR_FLAGS ( MOTOR_FLAG_BITS_NO_DEMAND_SEEN ) 120 #define PALM_0300_EDC_NO_DEMAND_TIMEOUT_MS 20 123 #ifndef NO_STRINGS // The PIC compiler doesn't deal well with strings. 153 #define MUSCLE_SYSTEM_RESET_KEY 0x5200 158 #define MUSCLE_DEMAND_VALVES_RANGE_MIN -0x4 159 #define MUSCLE_DEMAND_VALVES_RANGE_MAX 0x4 161 #define DIRECTION_TO_MUSCLE 0x01 162 #define DIRECTION_FROM_MUSCLE 0x02 165 #ifndef NO_STRINGS // The PIC compiler doesn't deal well with strings. 255 #define MESSAGE_ID_MUSCLE_DRIVER_ID_SHIFT_POS 5 259 #define SENSORS_NUM_0320 ((int)36) 262 #define JOINTS_NUM_0320 ((int)28) 293 int16u tactile_data_valid;
299 }
__attribute__((packed)) ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_STATUS;
316 }
__attribute__((packed)) ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_COMMAND;
320 #define PALM_0300_ETHERCAT_COMMAND_HEADER_SIZE ( sizeof(EDC_COMMAND) + sizeof(FROM_MUSCLE_DATA_TYPE) + sizeof(int16s) ) 322 #define PALM_0300_ETHERCAT_STATUS_DATA_SIZE sizeof(ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_STATUS) 323 #define PALM_0300_ETHERCAT_COMMAND_DATA_SIZE sizeof(ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_COMMAND) 330 #define ETHERCAT_STATUS_0300_AGREED_SIZE 236 331 #define ETHERCAT_COMMAND_0300_AGREED_SIZE 36 346 #define PALM_0300_ETHERCAT_COMMAND_DATA_ADDRESS 0x1000 347 #define PALM_0300_ETHERCAT_CAN_BRIDGE_DATA_COMMAND_ADDRESS (PALM_0300_ETHERCAT_COMMAND_DATA_ADDRESS + PALM_0300_ETHERCAT_COMMAND_DATA_SIZE) 349 #define PALM_0300_ETHERCAT_STATUS_DATA_ADDRESS (PALM_0300_ETHERCAT_CAN_BRIDGE_DATA_COMMAND_ADDRESS + ETHERCAT_CAN_BRIDGE_DATA_SIZE) 350 #define PALM_0300_ETHERCAT_CAN_BRIDGE_DATA_STATUS_ADDRESS (PALM_0300_ETHERCAT_STATUS_DATA_ADDRESS + PALM_0300_ETHERCAT_STATUS_DATA_SIZE)
Important to know that this is the last one.
A zero is what happens if an EtherCAT packet doesn't get through, so it's considered a special case...
TO_MUSCLE_DATA_TYPE to_muscle_data_type
What type of data are we sending to the muscles?
int16u which_muscle_data_arrived
FROM_MUSCLE_DATA_TYPE from_muscle_data_type
Which data does the host want from the muscles?
See FROM_MUSCLE_SLOW_DATA_TYPE.
Send with a demand value of 0x520x to reset muscle driver x.
Year of assembly, E.G. 2012.
The revision of the code.
This needs to be a #define for symmetry with SENSORS_NUM.
Day/Month of assembly. E.G. 0x0A1F means October 31st.
Did the local code have any uncomitted modifications at build time?
static const char * to_muscle_data_type_names[16]
For safety, this is not a data type.
ADC reading pressure sensors.
static const char * palm_0300_edc_error_flag_names[16]
how long, in milliseconds, before it switches off the valves.
#define NUM_MUSCLE_DATA_PACKETS
FROM_MUSCLE_DATA_TYPE muscle_data_type
FROM_MUSCLE_SLOW_DATA_TYPE
Number of CAN messages received / transmitted by this muscle driver + error counters.
EDC_COMMAND
The host can request different types of data from the palm.
For safety, this is not a valid request.
int16u assembly_date_YYYY