Classes | Macros | Enumerations | Variables
0320_palm_edc_ethercat_protocol.h File Reference
#include "../common/tactile_edc_ethercat_protocol.h"
#include "../common/ethercat_can_bridge_protocol.h"
#include "../common/common_edc_ethercat_protocol.h"
Include dependency graph for 0320_palm_edc_ethercat_protocol.h:

Go to the source code of this file.

Classes

struct  __attribute__
 This needs to be a #define for symmetry with SENSORS_NUM. More...
 
struct  __attribute__
 This needs to be a #define for symmetry with SENSORS_NUM. More...
 
union  MUSCLE_DATA_PACKET
 
union  TWELVE_BIT_INT_TO_NIBBLES
 

Macros

#define DIRECTION_FROM_MUSCLE   0x02
 
#define DIRECTION_TO_MUSCLE   0x01
 
#define ETHERCAT_COMMAND_0300_AGREED_SIZE   36
 
#define ETHERCAT_STATUS_0300_AGREED_SIZE   236
 
#define JOINTS_NUM_0320   ((int)28)
 This needs to be a #define because it's used to dimension an array. More...
 
#define MESSAGE_ID_MUSCLE_DRIVER_ID_SHIFT_POS   5
 Bit number of lowest bit of MESSAGE_ID_MUSCLE_ID_BITS. More...
 
#define MUSCLE_DEMAND_VALVES_RANGE_MAX   0x4
 
#define MUSCLE_DEMAND_VALVES_RANGE_MIN   -0x4
 
#define MUSCLE_FLAG_BITS_NO_DEMAND_SEEN   0x0400
 Haven't received any demand messages for longer than NO_DEMAND_TIMEOUT_MS. Valves switched off. More...
 
#define MUSCLE_SYSTEM_RESET_KEY   0x5200
 | Muscle board ID. More...
 
#define NUM_MUSCLE_DATA_PACKETS   8
 
#define NUM_MUSCLES   40
 
#define NUM_PRESSURE_SENSORS_PER_MESSAGE   5
 
#define PALM_0300_EDC_NO_DEMAND_TIMEOUT_MS   20
 
#define PALM_0300_EDC_SERIOUS_ERROR_FLAGS   ( MOTOR_FLAG_BITS_NO_DEMAND_SEEN )
 
#define PALM_0300_ETHERCAT_CAN_BRIDGE_DATA_COMMAND_ADDRESS   (PALM_0300_ETHERCAT_COMMAND_DATA_ADDRESS + PALM_0300_ETHERCAT_COMMAND_DATA_SIZE)
 
#define PALM_0300_ETHERCAT_CAN_BRIDGE_DATA_STATUS_ADDRESS   (PALM_0300_ETHERCAT_STATUS_DATA_ADDRESS + PALM_0300_ETHERCAT_STATUS_DATA_SIZE)
 
#define PALM_0300_ETHERCAT_COMMAND_DATA_ADDRESS   0x1000
 
#define PALM_0300_ETHERCAT_COMMAND_DATA_SIZE   sizeof(ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_COMMAND)
 
#define PALM_0300_ETHERCAT_COMMAND_HEADER_SIZE   ( sizeof(EDC_COMMAND) + sizeof(FROM_MUSCLE_DATA_TYPE) + sizeof(int16s) )
 
#define PALM_0300_ETHERCAT_STATUS_DATA_ADDRESS   (PALM_0300_ETHERCAT_CAN_BRIDGE_DATA_COMMAND_ADDRESS + ETHERCAT_CAN_BRIDGE_DATA_SIZE)
 
#define PALM_0300_ETHERCAT_STATUS_DATA_SIZE   sizeof(ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_STATUS)
 
#define SENSORS_NUM_0320   ((int)36)
 

Enumerations

enum  FROM_MUSCLE_DATA_TYPE { MUSCLE_DATA_INVALID = 0x0, MUSCLE_DATA_PRESSURE = 0x1, MUSCLE_DATA_CAN_STATS = 0x2, MUSCLE_DATA_SLOW_MISC = 0x3 }
 
enum  FROM_MUSCLE_SLOW_DATA_TYPE {
  MUSCLE_SLOW_DATA_INVALID = 0x0000, MUSCLE_SLOW_DATA_SVN_REVISION = 0x0001, MUSCLE_SLOW_DATA_SVN_SERVER_REVISION = 0x0002, MUSCLE_SLOW_DATA_SVN_MODIFIED = 0x0003,
  MUSCLE_SLOW_DATA_SERIAL_NUMBER_LOW = 0x0004, MUSCLE_SLOW_DATA_SERIAL_NUMBER_HIGH = 0x0005, MUSCLE_SLOW_DATA_ASSEMBLY_DATE_YYYY = 0x0006, MUSCLE_SLOW_DATA_ASSEMBLY_DATE_MMDD = 0x0007,
  MUSCLE_SLOW_DATA_LAST = 0x0007
}
 
enum  TO_MUSCLE_DATA_TYPE { MUSCLE_DEMAND_INVALID = 0x0, MUSCLE_DEMAND_VALVES = 0x1, MUSCLE_SYSTEM_RESET = 0x3 }
 

Variables

static const char * palm_0300_edc_error_flag_names [16]
 how long, in milliseconds, before it switches off the valves. More...
 
static const char * to_muscle_data_type_names [16]
 

Detailed Description

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 0320_palm_edc_ethercat_protocol.h.

Macro Definition Documentation

◆ DIRECTION_FROM_MUSCLE

#define DIRECTION_FROM_MUSCLE   0x02

Definition at line 162 of file 0320_palm_edc_ethercat_protocol.h.

◆ DIRECTION_TO_MUSCLE

#define DIRECTION_TO_MUSCLE   0x01

Definition at line 161 of file 0320_palm_edc_ethercat_protocol.h.

◆ ETHERCAT_COMMAND_0300_AGREED_SIZE

#define ETHERCAT_COMMAND_0300_AGREED_SIZE   36

Definition at line 331 of file 0320_palm_edc_ethercat_protocol.h.

◆ ETHERCAT_STATUS_0300_AGREED_SIZE

#define ETHERCAT_STATUS_0300_AGREED_SIZE   236

Definition at line 330 of file 0320_palm_edc_ethercat_protocol.h.

◆ JOINTS_NUM_0320

#define JOINTS_NUM_0320   ((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 262 of file 0320_palm_edc_ethercat_protocol.h.

◆ MESSAGE_ID_MUSCLE_DRIVER_ID_SHIFT_POS

#define MESSAGE_ID_MUSCLE_DRIVER_ID_SHIFT_POS   5

Bit number of lowest bit of MESSAGE_ID_MUSCLE_ID_BITS.

Definition at line 255 of file 0320_palm_edc_ethercat_protocol.h.

◆ MUSCLE_DEMAND_VALVES_RANGE_MAX

#define MUSCLE_DEMAND_VALVES_RANGE_MAX   0x4

Definition at line 159 of file 0320_palm_edc_ethercat_protocol.h.

◆ MUSCLE_DEMAND_VALVES_RANGE_MIN

#define MUSCLE_DEMAND_VALVES_RANGE_MIN   -0x4

Definition at line 158 of file 0320_palm_edc_ethercat_protocol.h.

◆ MUSCLE_FLAG_BITS_NO_DEMAND_SEEN

#define MUSCLE_FLAG_BITS_NO_DEMAND_SEEN   0x0400

Haven't received any demand messages for longer than NO_DEMAND_TIMEOUT_MS. Valves switched off.

Definition at line 115 of file 0320_palm_edc_ethercat_protocol.h.

◆ MUSCLE_SYSTEM_RESET_KEY

#define MUSCLE_SYSTEM_RESET_KEY   0x5200

| Muscle board ID.

Definition at line 153 of file 0320_palm_edc_ethercat_protocol.h.

◆ NUM_MUSCLE_DATA_PACKETS

#define NUM_MUSCLE_DATA_PACKETS   8

Definition at line 54 of file 0320_palm_edc_ethercat_protocol.h.

◆ NUM_MUSCLES

#define NUM_MUSCLES   40

Definition at line 52 of file 0320_palm_edc_ethercat_protocol.h.

◆ NUM_PRESSURE_SENSORS_PER_MESSAGE

#define NUM_PRESSURE_SENSORS_PER_MESSAGE   5

Definition at line 53 of file 0320_palm_edc_ethercat_protocol.h.

◆ PALM_0300_EDC_NO_DEMAND_TIMEOUT_MS

#define PALM_0300_EDC_NO_DEMAND_TIMEOUT_MS   20

If a muscle driver doesn't see any Torque or PWM demand values,

Definition at line 120 of file 0320_palm_edc_ethercat_protocol.h.

◆ PALM_0300_EDC_SERIOUS_ERROR_FLAGS

#define PALM_0300_EDC_SERIOUS_ERROR_FLAGS   ( MOTOR_FLAG_BITS_NO_DEMAND_SEEN )

Definition at line 118 of file 0320_palm_edc_ethercat_protocol.h.

◆ PALM_0300_ETHERCAT_CAN_BRIDGE_DATA_COMMAND_ADDRESS

#define PALM_0300_ETHERCAT_CAN_BRIDGE_DATA_COMMAND_ADDRESS   (PALM_0300_ETHERCAT_COMMAND_DATA_ADDRESS + PALM_0300_ETHERCAT_COMMAND_DATA_SIZE)

Definition at line 347 of file 0320_palm_edc_ethercat_protocol.h.

◆ PALM_0300_ETHERCAT_CAN_BRIDGE_DATA_STATUS_ADDRESS

#define PALM_0300_ETHERCAT_CAN_BRIDGE_DATA_STATUS_ADDRESS   (PALM_0300_ETHERCAT_STATUS_DATA_ADDRESS + PALM_0300_ETHERCAT_STATUS_DATA_SIZE)

Definition at line 350 of file 0320_palm_edc_ethercat_protocol.h.

◆ PALM_0300_ETHERCAT_COMMAND_DATA_ADDRESS

#define PALM_0300_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 346 of file 0320_palm_edc_ethercat_protocol.h.

◆ PALM_0300_ETHERCAT_COMMAND_DATA_SIZE

#define PALM_0300_ETHERCAT_COMMAND_DATA_SIZE   sizeof(ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_COMMAND)

Definition at line 323 of file 0320_palm_edc_ethercat_protocol.h.

◆ PALM_0300_ETHERCAT_COMMAND_HEADER_SIZE

#define PALM_0300_ETHERCAT_COMMAND_HEADER_SIZE   ( sizeof(EDC_COMMAND) + sizeof(FROM_MUSCLE_DATA_TYPE) + sizeof(int16s) )

Definition at line 320 of file 0320_palm_edc_ethercat_protocol.h.

◆ PALM_0300_ETHERCAT_STATUS_DATA_ADDRESS

#define PALM_0300_ETHERCAT_STATUS_DATA_ADDRESS   (PALM_0300_ETHERCAT_CAN_BRIDGE_DATA_COMMAND_ADDRESS + ETHERCAT_CAN_BRIDGE_DATA_SIZE)

Definition at line 349 of file 0320_palm_edc_ethercat_protocol.h.

◆ PALM_0300_ETHERCAT_STATUS_DATA_SIZE

#define PALM_0300_ETHERCAT_STATUS_DATA_SIZE   sizeof(ETHERCAT_DATA_STRUCTURE_0300_PALM_EDC_STATUS)

Definition at line 322 of file 0320_palm_edc_ethercat_protocol.h.

◆ SENSORS_NUM_0320

#define SENSORS_NUM_0320   ((int)36)

The number of sensors in the robot.

Definition at line 259 of file 0320_palm_edc_ethercat_protocol.h.

Enumeration Type Documentation

◆ FROM_MUSCLE_DATA_TYPE

Author
Hugo Elias
Enumerator
MUSCLE_DATA_INVALID 

For safety, this is not a valid request.

MUSCLE_DATA_PRESSURE 

ADC reading pressure sensors.

MUSCLE_DATA_CAN_STATS 

Number of CAN messages received / transmitted by this muscle driver + error counters.

MUSCLE_DATA_SLOW_MISC 

See FROM_MUSCLE_SLOW_DATA_TYPE.

Definition at line 65 of file 0320_palm_edc_ethercat_protocol.h.

◆ FROM_MUSCLE_SLOW_DATA_TYPE

Enumerator
MUSCLE_SLOW_DATA_INVALID 

For safety, this is not a data type.

MUSCLE_SLOW_DATA_SVN_REVISION 

The revision of the code.

MUSCLE_SLOW_DATA_SVN_SERVER_REVISION 

The revision of the code on the SVN server at build time. Should we have done an Update before building?

MUSCLE_SLOW_DATA_SVN_MODIFIED 

Did the local code have any uncomitted modifications at build time?

MUSCLE_SLOW_DATA_SERIAL_NUMBER_LOW 
MUSCLE_SLOW_DATA_SERIAL_NUMBER_HIGH 
MUSCLE_SLOW_DATA_ASSEMBLY_DATE_YYYY 

Year of assembly, E.G. 2012.

MUSCLE_SLOW_DATA_ASSEMBLY_DATE_MMDD 

Day/Month of assembly. E.G. 0x0A1F means October 31st.

MUSCLE_SLOW_DATA_LAST 

Important to know that this is the last one.

Definition at line 84 of file 0320_palm_edc_ethercat_protocol.h.

◆ TO_MUSCLE_DATA_TYPE

The host can send different types of data to the muscle drivers. These can be either control demands, system messages. These values are inserted into bits [3..0] of the message ID in the muscle driver data message.

Enumerator
MUSCLE_DEMAND_INVALID 

A zero is what happens if an EtherCAT packet doesn't get through, so it's considered a special case.

MUSCLE_DEMAND_VALVES 

Demanding valve pulses.

MUSCLE_SYSTEM_RESET 

Send with a demand value of 0x520x to reset muscle driver x.

Definition at line 145 of file 0320_palm_edc_ethercat_protocol.h.

Variable Documentation

◆ palm_0300_edc_error_flag_names

const char* palm_0300_edc_error_flag_names[16]
static
Initial value:
= { "No demand seen for more than 20ms",
}

how long, in milliseconds, before it switches off the valves.

These are the names of the bits in the MUSCLE_DATA_FLAGS. error_flag_names[n] is the name of bit 'n' in MUSCLE_DATA_FLAGS.

Definition at line 127 of file 0320_palm_edc_ethercat_protocol.h.

◆ to_muscle_data_type_names

const char* to_muscle_data_type_names[16]
static
Initial value:
= { "INVALID",
"Demand: Valves",
}

These are the human-readable names of the different types of data. you can send to the muscle drivers.

Definition at line 169 of file 0320_palm_edc_ethercat_protocol.h.



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