#include "../common/tactile_edc_ethercat_protocol.h"
#include "../common/ethercat_can_bridge_protocol.h"
#include "../common/common_edc_ethercat_protocol.h"
Go to the source code of this file.
The term "Command" means data going from the ROS PC to the Node on the robot Previously known as "Incoming"
The term "Status" means data going from Node on the robot the to the ROS PC Previously known as "Outgoing"
Definition in file 0220_palm_edc_ethercat_protocol.h.
#define ETHERCAT_COMMAND_AGREED_SIZE 70 |
Definition at line 430 of file 0220_palm_edc_ethercat_protocol.h.
#define ETHERCAT_STATUS_AGREED_SIZE 232 |
Definition at line 429 of file 0220_palm_edc_ethercat_protocol.h.
#define JOINTS_NUM_0220 ((int)28) |
This needs to be a #define because it's used to dimension an array.
The number of joints in the hand
Definition at line 356 of file 0220_palm_edc_ethercat_protocol.h.
#define MESSAGE_ID_MOTOR_ID_BOTTOM_BIT 0b00000100000 |
Used to mask for even/odd motors.
Definition at line 348 of file 0220_palm_edc_ethercat_protocol.h.
#define MESSAGE_ID_MOTOR_ID_SHIFT_POS 5 |
Bit number of lowest bit of MESSAGE_ID_MOTOR_ID_BITS.
Definition at line 347 of file 0220_palm_edc_ethercat_protocol.h.
#define MESSAGE_ID_MOTOR_ID_TOP_2_BITS 0b00110000000 |
Used to group motors into fours.
Definition at line 349 of file 0220_palm_edc_ethercat_protocol.h.
#define MOTOR_CONFIG_D_RANGE_MAX 0x7FFF |
Definition at line 283 of file 0220_palm_edc_ethercat_protocol.h.
#define MOTOR_CONFIG_D_RANGE_MIN 0x0000 |
Definition at line 282 of file 0220_palm_edc_ethercat_protocol.h.
#define MOTOR_CONFIG_DEADBAND_RANGE_MAX 0xFF |
Definition at line 289 of file 0220_palm_edc_ethercat_protocol.h.
#define MOTOR_CONFIG_DEADBAND_RANGE_MIN 0x00 |
Definition at line 288 of file 0220_palm_edc_ethercat_protocol.h.
#define MOTOR_CONFIG_F_RANGE_MAX 0x7FFF |
Definition at line 274 of file 0220_palm_edc_ethercat_protocol.h.
#define MOTOR_CONFIG_F_RANGE_MIN 0x0000 |
Definition at line 273 of file 0220_palm_edc_ethercat_protocol.h.
#define MOTOR_CONFIG_I_RANGE_MAX 0x7FFF |
Definition at line 280 of file 0220_palm_edc_ethercat_protocol.h.
#define MOTOR_CONFIG_I_RANGE_MIN 0x0000 |
Definition at line 279 of file 0220_palm_edc_ethercat_protocol.h.
#define MOTOR_CONFIG_IMAX_RANGE_MAX 0x3FFF |
Definition at line 286 of file 0220_palm_edc_ethercat_protocol.h.
#define MOTOR_CONFIG_IMAX_RANGE_MIN 0x0000 |
Definition at line 285 of file 0220_palm_edc_ethercat_protocol.h.
#define MOTOR_CONFIG_P_RANGE_MAX 0x7FFF |
Definition at line 277 of file 0220_palm_edc_ethercat_protocol.h.
#define MOTOR_CONFIG_P_RANGE_MIN 0x0000 |
Definition at line 276 of file 0220_palm_edc_ethercat_protocol.h.
#define MOTOR_CONFIG_SIGN_RANGE_MAX 0x01 |
Definition at line 292 of file 0220_palm_edc_ethercat_protocol.h.
#define MOTOR_CONFIG_SIGN_RANGE_MIN 0x00 |
Definition at line 291 of file 0220_palm_edc_ethercat_protocol.h.
#define MOTOR_DEMAND_PWM_RANGE_MAX 0x03FF |
Definition at line 271 of file 0220_palm_edc_ethercat_protocol.h.
#define MOTOR_DEMAND_PWM_RANGE_MIN -0x03FF |
Definition at line 270 of file 0220_palm_edc_ethercat_protocol.h.
#define MOTOR_DEMAND_TORQUE_RANGE_MAX 0x7FFF |
Definition at line 268 of file 0220_palm_edc_ethercat_protocol.h.
#define MOTOR_DEMAND_TORQUE_RANGE_MIN -0x7FFF |
Definition at line 267 of file 0220_palm_edc_ethercat_protocol.h.
#define MOTOR_FLAG_BITS_A3950_NFAULT 0x2000 |
nFault output from A3950 H-Bridge
Definition at line 172 of file 0220_palm_edc_ethercat_protocol.h.
#define MOTOR_FLAG_BITS_CURRENT_CHOKE 0x000F |
Top 4 bits of the current choke.
Definition at line 156 of file 0220_palm_edc_ethercat_protocol.h.
#define MOTOR_FLAG_BITS_EEPROM_CONFIG_BAD_CRC 0x4000 |
EEPROM contains a bad CRC. Configs not loaded.
Definition at line 173 of file 0220_palm_edc_ethercat_protocol.h.
#define MOTOR_FLAG_BITS_EEPROM_WRITING 0x0010 |
1=EEPROM write currently in progress, don't update configuration.
Definition at line 158 of file 0220_palm_edc_ethercat_protocol.h.
#define MOTOR_FLAG_BITS_JIGGLING_IN_PROGRESS 0x0080 |
Jiggling in progress to zreo gauge readings. Control unavailable at this time.
Definition at line 161 of file 0220_palm_edc_ethercat_protocol.h.
#define MOTOR_FLAG_BITS_LAST_CONFIG_CRC_FAILED 0x0020 |
1=Last CRC message didn't patch the previously sent configs.
Definition at line 159 of file 0220_palm_edc_ethercat_protocol.h.
#define MOTOR_FLAG_BITS_LAST_CONFIG_OUT_OF_RANGE 0x0040 |
1=Last config message contained a value which was out of range.
Definition at line 160 of file 0220_palm_edc_ethercat_protocol.h.
#define MOTOR_FLAG_BITS_MOTOR_ID_IS_INVALID 0x0200 |
Motor seems to have an out-of-range ID. You'll probably never see this flag. (Might get rid of it)
Definition at line 167 of file 0220_palm_edc_ethercat_protocol.h.
#define MOTOR_FLAG_BITS_NO_DEMAND_SEEN 0x0400 |
Haven't received any demand messages for longer than NO_DEMAND_TIMEOUT_MS. Motor halted.
Definition at line 168 of file 0220_palm_edc_ethercat_protocol.h.
#define MOTOR_FLAG_BITS_OVER_TEMP 0x8000 |
Motor over-heated and halted.
Definition at line 174 of file 0220_palm_edc_ethercat_protocol.h.
#define MOTOR_FLAG_BITS_SGL_FAULT 0x0800 |
Fault seen with Left strain gauge. Not currently implemented.
Definition at line 169 of file 0220_palm_edc_ethercat_protocol.h.
#define MOTOR_FLAG_BITS_SGR_FAULT 0x1000 |
Fault seen with Left strain gauge. Not currently implemented.
Definition at line 171 of file 0220_palm_edc_ethercat_protocol.h.
#define MOTOR_SYSTEM_CONTROL_BACKLASH_COMPENSATION_DISABLE 0x0002 |
Turn off Backlash Compensation.
Definition at line 256 of file 0220_palm_edc_ethercat_protocol.h.
#define MOTOR_SYSTEM_CONTROL_BACKLASH_COMPENSATION_ENABLE 0x0001 |
Turn on Backlash Compensation.
Definition at line 255 of file 0220_palm_edc_ethercat_protocol.h.
#define MOTOR_SYSTEM_CONTROL_EEPROM_WRITE 0x0080 |
see the MOTOR_FLAG_BITS_JIGGLING_IN_PROGRESS flag appear.
Write the configuration to the EEPROM.
Definition at line 263 of file 0220_palm_edc_ethercat_protocol.h.
#define MOTOR_SYSTEM_CONTROL_INITIATE_JIGGLING 0x0040 |
Initiate the jiggling to re-zero the strain gauges. You'll
Definition at line 261 of file 0220_palm_edc_ethercat_protocol.h.
#define MOTOR_SYSTEM_CONTROL_SGL_TRACKING_DEC 0x0008 |
Decrement the tracking value for Left gauge.
Definition at line 258 of file 0220_palm_edc_ethercat_protocol.h.
#define MOTOR_SYSTEM_CONTROL_SGL_TRACKING_INC 0x0004 |
Increment the tracking value for Left gauge.
Definition at line 257 of file 0220_palm_edc_ethercat_protocol.h.
#define MOTOR_SYSTEM_CONTROL_SGR_TRACKING_DEC 0x0020 |
Decrement the tracking value for Right gauge.
Definition at line 260 of file 0220_palm_edc_ethercat_protocol.h.
#define MOTOR_SYSTEM_CONTROL_SGR_TRACKING_INC 0x0010 |
Increment the tracking value for Right gauge.
Definition at line 259 of file 0220_palm_edc_ethercat_protocol.h.
#define MOTOR_SYSTEM_RESET_KEY 0x5200 |
| Motor ID.
Definition at line 253 of file 0220_palm_edc_ethercat_protocol.h.
#define NO_TORQUE_CONTROL_ERROR_FLAGS |
Definition at line 177 of file 0220_palm_edc_ethercat_protocol.h.
#define NUM_MOTORS 20 |
Definition at line 52 of file 0220_palm_edc_ethercat_protocol.h.
#define PALM_0200_EDC_NO_DEMAND_TIMEOUT_MS 20 |
If a motor doesn't see any Torque or PWM demand values,
Definition at line 186 of file 0220_palm_edc_ethercat_protocol.h.
( MOTOR_FLAG_BITS_NO_DEMAND_SEEN \ | MOTOR_FLAG_BITS_A3950_NFAULT \ | MOTOR_FLAG_BITS_EEPROM_CONFIG_BAD_CRC \ | MOTOR_FLAG_BITS_OVER_TEMP )
Definition at line 180 of file 0220_palm_edc_ethercat_protocol.h.
#define PALM_0200_ETHERCAT_CAN_BRIDGE_DATA_COMMAND_ADDRESS (PALM_0200_ETHERCAT_COMMAND_DATA_ADDRESS + PALM_0200_ETHERCAT_COMMAND_DATA_SIZE) |
Definition at line 447 of file 0220_palm_edc_ethercat_protocol.h.
#define PALM_0200_ETHERCAT_CAN_BRIDGE_DATA_STATUS_ADDRESS (PALM_0200_ETHERCAT_STATUS_DATA_ADDRESS + PALM_0200_ETHERCAT_STATUS_DATA_SIZE) |
Definition at line 450 of file 0220_palm_edc_ethercat_protocol.h.
#define PALM_0200_ETHERCAT_COMMAND_DATA_ADDRESS 0x1000 |
| ETHERCAT_COMMAND_DATA | ETHERCAT_CAN_BRIDGE_DATA_COMMAND | ETHERCAT_STATUS_DATA | ETHERCAT_CAN_BRIDGE_DATA_STATUS | | | | | | | | ETHERCAT_CAN_BRIDGE_DATA_STATUS_ADDRESS | | | | | ETHERCAT_STATUS_DATA_ADDRESS | | | ETHERCAT_CAN_BRIDGE_DATA_COMMAND_ADDRESS | ETHERCAT_COMMAND_DATA_ADDRESS
Definition at line 446 of file 0220_palm_edc_ethercat_protocol.h.
#define PALM_0200_ETHERCAT_COMMAND_DATA_SIZE sizeof(ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_COMMAND) |
Definition at line 422 of file 0220_palm_edc_ethercat_protocol.h.
#define PALM_0200_ETHERCAT_COMMAND_HEADER_SIZE ( sizeof(EDC_COMMAND) + sizeof(FROM_MOTOR_DATA_TYPE) + sizeof(int16s) ) |
Definition at line 419 of file 0220_palm_edc_ethercat_protocol.h.
#define PALM_0200_ETHERCAT_STATUS_DATA_ADDRESS (PALM_0200_ETHERCAT_CAN_BRIDGE_DATA_COMMAND_ADDRESS + ETHERCAT_CAN_BRIDGE_DATA_SIZE) |
Definition at line 449 of file 0220_palm_edc_ethercat_protocol.h.
#define PALM_0200_ETHERCAT_STATUS_DATA_SIZE sizeof(ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS) |
Definition at line 421 of file 0220_palm_edc_ethercat_protocol.h.
#define SENSORS_NUM_0220 ((int)36) |
The number of sensors in the robot.
Definition at line 353 of file 0220_palm_edc_ethercat_protocol.h.
#define STRAIN_GAUGE_TYPE_COUPLED 0x0C |
Definition at line 143 of file 0220_palm_edc_ethercat_protocol.h.
#define STRAIN_GAUGE_TYPE_DECOUPLED 0x0D |
Definition at line 144 of file 0220_palm_edc_ethercat_protocol.h.
enum FROM_MOTOR_DATA_TYPE |
The host can request different types of data from the motors. These values are inserted into bits [3..0] of the message ID in the Data Request (Start Of Frame) message.
//!Word 0 | Word 1 | |||
FROM_MOTOR_DATA_TYPE | Byte0 | Byte1 | Byte2 | Byte3 |
MOTOR_DATA_SGL | Torque | SGL | ||
MOTOR_DATA_SGR | Torque | SGR | ||
MOTOR_DATA_PWM | Torque | PWM | ||
MOTOR_DATA_FLAGS | Torque | Flags | ||
MOTOR_DATA_CURRENT | Torque | Current | ||
MOTOR_DATA_VOLTAGE | Torque | Voltage | ||
MOTOR_DATA_TEMPERATURE | Torque | Temperature | ||
MOTOR_DATA_CAN_NUM_RECEIVED | Torque | Num Rx | ||
MOTOR_DATA_CAN_NUM_TRANSMITTED | Torque | Num Tx | ||
MOTOR_DATA_SVN_REVISION | Server revision | This revision (top bit = modified) | ||
MOTOR_DATA_READBACK_LAST_CONFIG | FROM_MOTOR_SLOW_DATA_TYPE | Config value | ||
MOTOR_DATA_CAN_ERROR_COUNTERS | Torque | Tx Err | Rx Err |
Definition at line 88 of file 0220_palm_edc_ethercat_protocol.h.
Definition at line 117 of file 0220_palm_edc_ethercat_protocol.h.
enum TO_MOTOR_DATA_TYPE |
The host can send different types of data from the motors. These can be either control demands, or configurations. These values are inserted into bits [3..0] of the message ID in the Motor data message.
Definition at line 229 of file 0220_palm_edc_ethercat_protocol.h.
enum TO_MOTOR_DEBUG_TYPE |
Then the motor is in debug mode, the host can send different types of spoof sensor data to the motors. These values are inserted into bits [3..0] of the message ID in the Motor data message.
NOT CURRENTLY IMPLEMENTED IN THE MOTORS.
Definition at line 325 of file 0220_palm_edc_ethercat_protocol.h.
const char* palm_0200_edc_error_flag_names[16] [static] |
{ "Current choke bit 6", "Current choke bit 7", "Current choke bit 8", "Current choke bit 9", "EEPROM write in progress", "Last CRC sent didn't match configs", "Last config received was out of range", "Jiggling in progress", "Invalid flag", "Motor ID is invalid", "No demand seen for more than 20ms", "Fault with strain gauge 0: left", "Fault with strain gauge 1: right", "A3950 H-bridge nFault asserted", "EEPROM contains bad CRC. Motor off.", "Motor over temperature" }
how long, in milliseconds, before it switches off the motor.
These are the names of the bits in the MOTOR_DATA_FLAGS. error_flag_names[n] is the name of bit 'n' in MOTOR_DATA_FLAGS.
Definition at line 193 of file 0220_palm_edc_ethercat_protocol.h.
const char* to_motor_data_type_names[16] [static] |
{ "INVALID", "Demand: Torque", "Demand: PWM", "INVALID", "INVALID", "INVALID", "INVALID", "Config: Maximum PWM value", "Config: Strain gauge amp references. LSB = ref for SGL, MSB = ref for SGR", "Config: Feed forward gain", "Config: Proportional gain", "Config: Integral gain", "Config: Derivative gain", "Config: Maximum integral windup", "Config: MSB=Deadband. LSB=Sign", "Config: CRC", }
These are the human-readable names of the different types of data. you can send to the motors.
Definition at line 299 of file 0220_palm_edc_ethercat_protocol.h.