EtherCAT Control Framework v0.9
Implementation of EtherCAT protocol using IgH EtherCAT library for robot controller.
ecat_globals.hpp File Reference
#include <iostream>
#include <cstring>
#include <limits.h>
#include <stdlib.h>
#include <pthread.h>
#include <errno.h>
#include <signal.h>
#include <stdio.h>
#include <string.h>
#include <sys/resource.h>
#include <sys/time.h>
#include <sys/types.h>
#include <unistd.h>
#include <time.h>
#include <sys/mman.h>
#include <malloc.h>
#include <sched.h>
#include <chrono>
#include <memory>
#include <vector>
#include "ecrt.h"
#include "object_dictionary.hpp"
Include dependency graph for ecat_globals.hpp:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  Controller
 Xbox Controller values. More...
 
struct  SDO_data
 SDO_data Structure holding all data needed to send an SDO object. More...
 
struct  DataReceived
 Structure for data to be received from slaves. More...
 
struct  DataSent
 Structure for data to be sent to slaves. More...
 
struct  OffsetPDO
 offset for PDO entries to register PDOs. More...
 
struct  SdoRequest
 EtherCAT SDO request structure for configuration phase. More...
 
struct  ProfilePosParam
 Parameters that should be specified in position mode. More...
 
struct  CSPositionModeParam
 Struct contains configuration parameters for cyclic sync. position mode. More...
 
struct  VelControlParam
 Struct containing 'velocity control parameter set' 0x30A2 Has 4 sub index. Default values are from EPOS4 firmware manual. More...
 
struct  CSVelocityModeParam
 Struct contains configuration parameters for cyclic sync. velocity mode. More...
 
struct  CSTorqueModeParam
 Struct contains configuration parameters for cyclic sync. torque mode. More...
 
struct  HomingParam
 Homing mode configuration parameters. More...
 
struct  ProfileVelocityParam
 Profile velocity mode configuration parameters. More...
 

Macros

#define NUM_OF_SLAVES   1
 Total number of connected slave to the bus. More...
 
#define CUSTOM_SLAVE   0
 
#define FREQUENCY   1000
 Ethercat PDO exchange loop frequency in Hz
More...
 
#define MEASURE_TIMING   1
 If you want to measure timings leave it as one, otherwise make it 0. More...
 
#define VELOCITY_MODE   1
 set this to 1 if you want to use it in velocity mode (and set other modes 0) More...
 
#define POSITION_MODE   0
 set this to 1 if you want to use it in position mode (and set other modes 0)
More...
 
#define CYCLIC_POSITION_MODE   0
 set this to 1 if you want to use it in cyclic synchronous position mode (and set other modes 0) More...
 
#define CYCLIC_VELOCITY_MODE   0
 set this to 1 if you want to use it in cyclic synchronous velocity mode (and set other modes 0) More...
 
#define CYCLIC_TORQUE_MODE   0
 set this to 1 if you want to use it in cyclic synchronous torque mode (and set other modes 0) More...
 
#define DISTRIBUTED_CLOCK   1
 set this to 1 if you want to activate distributed clock, by default leave it 1.
More...
 
#define GEAR_RATIO   103
 
#define ENCODER_RESOLUTION   1024
 Motor encoder resolution. More...
 
#define INC_PER_ROTATION   GEAR_RATIO*ENCODER_RESOLUTION*4
 
#define FIVE_DEGREE_CCW   int(INC_PER_ROTATION/72)
 
#define THIRTY_DEGREE_CCW   int(INC_PER_ROTATION/12)
 
#define PERIOD_NS   (g_kNsPerSec/FREQUENCY)
 
#define PERIOD_US   (PERIOD_NS / 1000)
 
#define PERIOD_MS   (PERIOD_US / 1000)
 
#define TEST_BIT(NUM, N)   ((NUM & (1 << N))>>N)
 To sync every cycle. More...
 
#define SET_BIT(NUM, N)   (NUM | (1 << N))
 
#define RESET_BIT(NUM, N)   (NUM & ~(1 << N))
 
#define TIMESPEC2NS(T)   ((uint64_t) (T).tv_sec * g_kNsPerSec + (T).tv_nsec)
 Convert timespec struct to nanoseconds. More...
 
#define DIFF_NS(A, B)   (((B).tv_sec - (A).tv_sec) * g_kNsPerSec + (B).tv_nsec - (A).tv_nsec)
 
#define CLOCK_TO_USE   CLOCK_MONOTONIC
 Using Monotonic system-wide clock. More...
 

Enumerations

enum  LifeCycleState { FAILURE = -1 , SUCCESS , TRANSITIONING }
 Class states. More...
 
enum  OpMode {
  kProfilePosition = 1 , kProfileVelocity = 3 , kProfileTorque = 4 , kHoming = 6 ,
  kInterpolatedPosition = 7 , kCSPosition = 8 , kCSVelocity = 9 , kCSTorque = 10
}
 Motor operation modes based on CiA402. More...
 
enum  MotorStates {
  kReadyToSwitchOn = 1 , kSwitchedOn , kOperationEnabled , kFault ,
  kVoltageEnabled , kQuickStop , kSwitchOnDisabled , kWarning ,
  kRemote , kTargetReached , kInternalLimitActivate
}
 CIA 402 state machine motor states. More...
 
enum  ErrorRegisterBits {
  kGenericError = 0 , kCurrentError , kVoltageError , kTemperatureError ,
  kCommunicationError , kDeviceProfileSpecificError , kReserved , kMotionError
}
 CiA402 Error register bits for error index. More...
 
enum  SensorConfig {
  kSensor1TypeNone =0 , kSensor1TypeDigitalIncrementalEncoder1 =1 , kSensor2TypeNone =0 , kSensor2TypeDigitalIncrementalEncoder2 =256 ,
  kSensor2TypeAnalogIncrementalEncoderSinCos =512 , kSensor2TypeSSIAbsoluteEncoder =768 , kSensor3TypeNone =0 , kSensor3TypeDigitalHallSensor =131072
}
 
enum  ControlStructureBits {
  kCurrentControlStructure = 0 , kVelocityControlStructure = 4 , kPositionControlStructure = 8 , kGearLocation = 12 ,
  kProcessValueReference = 14 , kMainSensor = 16 , kAuxiliarySensor = 20 , kMountingPositionSensor1 = 24 ,
  kMountingPositionSensor2 = 26 , kMountingPositionSensor3 = 28
}
 Control structure configuration for control mechanism to select sensor structure specific to hardware. More...
 
enum  ErrorType {
  NO_ERROR = 0 , GENERIC_ERROR = 0x1000 , GENERIC_INIT_ERROR = 0x1080 , GENERIC_INIT_ERROR_1 = 0x1081 ,
  GENERIC_INIT_ERROR_2 = 0x1082 , GENERIC_INIT_ERROR_3 = 0x1083 , GENERIC_INIT_ERROR_4 = 0x1084 , GENERIC_INIT_ERROR_5 = 0x1085 ,
  GENERIC_INIT_ERROR_6 = 0x1086 , GENERIC_INIT_ERROR_7 = 0x1087 , GENERIC_INIT_ERROR_8 = 0x1088 , FIRMWARE_INCOMPATIBLITY_ERROR = 0x1090 ,
  OVER_CURRENT_ERROR = 0x2310 , POWER_STAGE_PROTECTION_ERROR = 0x2320 , OVER_VOLTAGE_ERROR = 0x3210 , UNDER_VOLTAGE_ERROR = 0x3220 ,
  THERMAL_OVERLOAD_ERROR = 0x4210 , THERMAL_MOTOR_OVERLOAD_ERRROR = 0x4380 , LOGIC_SUPPLY_TOO_LOW_ERROR = 0x5113 , HARDWARE_DEFECT_ERROR = 0x5280 ,
  HARDWARE_INCOMPATIBLITY_ERROR = 0x5281 , HARDWARE_ERROR = 0x5480 , HARDWARE_ERROR_1 = 0x5481 , HARDWARE_ERROR_2 = 0x5482 ,
  HARDWARE_ERROR_3 = 0x5483 , SIGN_OF_LIFE_ERROR = 0x6080 , EXTENSION_1_WATCHDOG_ERROR = 0x6081 , INTERNAL_SOFTWARE_ERROR = 0x6180 ,
  SOFTWARE_PARAMETER_ERROR = 0x6320 , PERSISTENT_PARAMETER_CORRUPT_ERROR = 0x6380 , POSITION_SENSOR_ERROR = 0x7320 , POSITION_SENSOR_BREACH_ERROR = 0x7380 ,
  POSITION_SENSOR_RESOLUTION_ERROR = 0x7381 , POSITION_SENSOR_INDEX_ERROR = 0x7382 , HALL_SENSOR_ERROR = 0x7388 , HALL_SENSOR_NOT_FOUND_ERROR = 0x7389 ,
  HALL_ANGLE_DETECTION_ERROR = 0x738A , SSI_SENSOR_ERROR = 0x738C , SSI_SENSOR_FRAME_ERROR = 0x738D , MISSING_MAIN_SENSOR_ERROR = 0x7390 ,
  MISSING_COMMUTATION_SENSOR_ERROR = 0x7391 , MAIN_SENSOR_DIRECTION_ERROR = 0x7392 , ETHERCAT_COMMUNCATION_ERROR = 0x8180 , ETHERCAT_INITIALIZATION_ERROR = 0x8181 ,
  ETHERCAT_RX_QUEUE_OVERFLOW_ERROR = 0x8182 , ETHERCAT_COMMUNICATION_ERROR_INTERNAL = 0x8183 , ETHERCAT_COMMUNICATION_CYCLE_TIME_ERROR = 0x8184 , ETHERCAT_PDO_COMMUNICATION_ERROR = 0x8280 ,
  ETHERCAT_SDO_COMMUNICATION_ERROR = 0x8281 , FOLLOWING_ERROR = 0x8611 , NEGATIVE_LIMIT_SWITCH_ERROR = 0x8A80 , POSITIVE_LIMIT_SWITCH_ERROR = 0x8A81 ,
  SOFTWARE_POSITION_LIMIT_ERROR = 0x8A82 , STO_ERROR = 0x8A88 , SYSTEM_OVERLOADED_ERROR = 0xFF01 , WATCHDOG_ERROR = 0xFF02 ,
  SYSTEM_PEAK_OVERLOADED_ERROR = 0XFF0B , CONTROLLER_GAIN_ERROR = 0xFF10 , AUTO_TUNING_INDENTIFICATION_ERROR = 0xFF11 , AUTO_TUNING_CURRENT_LIMIT_ERROR = 0xFF12 ,
  AUTO_TUNING_IDENTIFICATION_CURRENT_ERROR = 0xFF13 , AUTO_TUNING_DATA_SAMPLING_ERROR = 0xFF14 , AUTO_TUNING_SAMPLE_MISMATCH_ERROR = 0xFF15 , AUTO_TUNING_PARAMETER_ERROR = 0xFF16 ,
  AUTO_TUNING_AMPLITUDE_MISMATCH_ERROR = 0xFF17 , AUTO_TUNING_TIMEOUT_ERROR = 0xFF19 , AUTO_TUNING_STAND_STILL_ERROR = 0xFF20 , AUTO_TUNING_TORQUE_INVALID_ERROR = 0xFF21 ,
  AUTO_TUNING_MAX_SYSTEM_SPEED_ERROR = 0XFF22 , AUTO_TUNING_MOTOR_CONNECTION_ERROR = 0xFF23 , AUTO_TUNING_SENSOR_SIGNAL_ERROR = 0XFF24
}
 

Functions

struct timespec timespec_add (struct timespec time1, struct timespec time2)
 Add two timespec struct. More...
 
static std::string GetErrorMessage (const int &err_code)
 

Variables

const uint32_t g_kNumberOfServoDrivers = 1
 
const uint32_t g_kNsPerSec = 1000000000
 Nanoseconds per second. More...
 
static volatile sig_atomic_t sig = 1
 
ec_master_t * g_master
 Extern global variable declaration. More...
 
ec_master_state_t g_master_state
 EtherCAT master. More...
 
ec_domain_t * g_master_domain
 EtherCAT master state. More...
 
ec_domain_state_t g_master_domain_state
 Ethercat data passing master domain. More...
 
struct timespec g_sync_timer
 EtherCAT master domain state. More...
 
const struct timespec g_cycle_time = {0, PERIOD_NS}
 timer for DC sync . More...
 
uint32_t g_sync_ref_counter
 cycletime settings in ns. More...
 

Macro Definition Documentation

◆ CLOCK_TO_USE

#define CLOCK_TO_USE   CLOCK_MONOTONIC

Using Monotonic system-wide clock.

◆ CUSTOM_SLAVE

#define CUSTOM_SLAVE   0

If you have EtherCAT slave different than CiA402 supported motor drive, set this macro to 1

Note
That you'll have to manually specify PDO mapping for your custom slave.

◆ CYCLIC_POSITION_MODE

#define CYCLIC_POSITION_MODE   0

set this to 1 if you want to use it in cyclic synchronous position mode (and set other modes 0)

◆ CYCLIC_TORQUE_MODE

#define CYCLIC_TORQUE_MODE   0

set this to 1 if you want to use it in cyclic synchronous torque mode (and set other modes 0)

◆ CYCLIC_VELOCITY_MODE

#define CYCLIC_VELOCITY_MODE   0

set this to 1 if you want to use it in cyclic synchronous velocity mode (and set other modes 0)

◆ DIFF_NS

#define DIFF_NS (   A,
 
)    (((B).tv_sec - (A).tv_sec) * g_kNsPerSec + (B).tv_nsec - (A).tv_nsec)

◆ DISTRIBUTED_CLOCK

#define DISTRIBUTED_CLOCK   1

set this to 1 if you want to activate distributed clock, by default leave it 1.

◆ ENCODER_RESOLUTION

#define ENCODER_RESOLUTION   1024

Motor encoder resolution.

◆ FIVE_DEGREE_CCW

#define FIVE_DEGREE_CCW   int(INC_PER_ROTATION/72)

◆ FREQUENCY

#define FREQUENCY   1000

Ethercat PDO exchange loop frequency in Hz

◆ GEAR_RATIO

#define GEAR_RATIO   103

If you are using geared motor define ratio

Note
If you have different types of motors in your system you may need to create different macros for them.

◆ INC_PER_ROTATION

#define INC_PER_ROTATION   GEAR_RATIO*ENCODER_RESOLUTION*4

◆ MEASURE_TIMING

#define MEASURE_TIMING   1

If you want to measure timings leave it as one, otherwise make it 0.

◆ NUM_OF_SLAVES

#define NUM_OF_SLAVES   1

Total number of connected slave to the bus.

◆ PERIOD_MS

#define PERIOD_MS   (PERIOD_US / 1000)

◆ PERIOD_NS

#define PERIOD_NS   (g_kNsPerSec/FREQUENCY)

◆ PERIOD_US

#define PERIOD_US   (PERIOD_NS / 1000)

◆ POSITION_MODE

#define POSITION_MODE   0

set this to 1 if you want to use it in position mode (and set other modes 0)

◆ RESET_BIT

#define RESET_BIT (   NUM,
 
)    (NUM & ~(1 << N))

◆ SET_BIT

#define SET_BIT (   NUM,
 
)    (NUM | (1 << N))

◆ TEST_BIT

#define TEST_BIT (   NUM,
 
)    ((NUM & (1 << N))>>N)

To sync every cycle.

◆ THIRTY_DEGREE_CCW

#define THIRTY_DEGREE_CCW   int(INC_PER_ROTATION/12)

◆ TIMESPEC2NS

#define TIMESPEC2NS (   T)    ((uint64_t) (T).tv_sec * g_kNsPerSec + (T).tv_nsec)

Convert timespec struct to nanoseconds.

◆ VELOCITY_MODE

#define VELOCITY_MODE   1

set this to 1 if you want to use it in velocity mode (and set other modes 0)

Enumeration Type Documentation

◆ ControlStructureBits

Control structure configuration for control mechanism to select sensor structure specific to hardware.

See also
EPOS4-Firmware-Specification pg. 140
Enumerator
kCurrentControlStructure 

These are bit locations not values for values.

See also
EPOS4-Firmware-Specification pg. 140 !!!
kVelocityControlStructure 
kPositionControlStructure 
kGearLocation 
kProcessValueReference 
kMainSensor 
kAuxiliarySensor 
kMountingPositionSensor1 
kMountingPositionSensor2 
kMountingPositionSensor3 

◆ ErrorRegisterBits

CiA402 Error register bits for error index.

Enumerator
kGenericError 
kCurrentError 
kVoltageError 
kTemperatureError 
kCommunicationError 
kDeviceProfileSpecificError 
kReserved 
kMotionError 

◆ ErrorType

enum ErrorType
Enumerator
NO_ERROR 
GENERIC_ERROR 
GENERIC_INIT_ERROR 
GENERIC_INIT_ERROR_1 
GENERIC_INIT_ERROR_2 
GENERIC_INIT_ERROR_3 
GENERIC_INIT_ERROR_4 
GENERIC_INIT_ERROR_5 
GENERIC_INIT_ERROR_6 
GENERIC_INIT_ERROR_7 
GENERIC_INIT_ERROR_8 
FIRMWARE_INCOMPATIBLITY_ERROR 
OVER_CURRENT_ERROR 
POWER_STAGE_PROTECTION_ERROR 
OVER_VOLTAGE_ERROR 
UNDER_VOLTAGE_ERROR 
THERMAL_OVERLOAD_ERROR 
THERMAL_MOTOR_OVERLOAD_ERRROR 
LOGIC_SUPPLY_TOO_LOW_ERROR 
HARDWARE_DEFECT_ERROR 
HARDWARE_INCOMPATIBLITY_ERROR 
HARDWARE_ERROR 
HARDWARE_ERROR_1 
HARDWARE_ERROR_2 
HARDWARE_ERROR_3 
SIGN_OF_LIFE_ERROR 
EXTENSION_1_WATCHDOG_ERROR 
INTERNAL_SOFTWARE_ERROR 
SOFTWARE_PARAMETER_ERROR 
PERSISTENT_PARAMETER_CORRUPT_ERROR 
POSITION_SENSOR_ERROR 
POSITION_SENSOR_BREACH_ERROR 
POSITION_SENSOR_RESOLUTION_ERROR 
POSITION_SENSOR_INDEX_ERROR 
HALL_SENSOR_ERROR 
HALL_SENSOR_NOT_FOUND_ERROR 
HALL_ANGLE_DETECTION_ERROR 
SSI_SENSOR_ERROR 
SSI_SENSOR_FRAME_ERROR 
MISSING_MAIN_SENSOR_ERROR 
MISSING_COMMUTATION_SENSOR_ERROR 
MAIN_SENSOR_DIRECTION_ERROR 
ETHERCAT_COMMUNCATION_ERROR 
ETHERCAT_INITIALIZATION_ERROR 
ETHERCAT_RX_QUEUE_OVERFLOW_ERROR 
ETHERCAT_COMMUNICATION_ERROR_INTERNAL 
ETHERCAT_COMMUNICATION_CYCLE_TIME_ERROR 
ETHERCAT_PDO_COMMUNICATION_ERROR 
ETHERCAT_SDO_COMMUNICATION_ERROR 
FOLLOWING_ERROR 
NEGATIVE_LIMIT_SWITCH_ERROR 
POSITIVE_LIMIT_SWITCH_ERROR 
SOFTWARE_POSITION_LIMIT_ERROR 
STO_ERROR 
SYSTEM_OVERLOADED_ERROR 
WATCHDOG_ERROR 
SYSTEM_PEAK_OVERLOADED_ERROR 
CONTROLLER_GAIN_ERROR 
AUTO_TUNING_INDENTIFICATION_ERROR 
AUTO_TUNING_CURRENT_LIMIT_ERROR 
AUTO_TUNING_IDENTIFICATION_CURRENT_ERROR 
AUTO_TUNING_DATA_SAMPLING_ERROR 
AUTO_TUNING_SAMPLE_MISMATCH_ERROR 
AUTO_TUNING_PARAMETER_ERROR 
AUTO_TUNING_AMPLITUDE_MISMATCH_ERROR 
AUTO_TUNING_TIMEOUT_ERROR 
AUTO_TUNING_STAND_STILL_ERROR 
AUTO_TUNING_TORQUE_INVALID_ERROR 
AUTO_TUNING_MAX_SYSTEM_SPEED_ERROR 
AUTO_TUNING_MOTOR_CONNECTION_ERROR 
AUTO_TUNING_SENSOR_SIGNAL_ERROR 

◆ LifeCycleState

Class states.

Enumerator
FAILURE 
SUCCESS 
TRANSITIONING 

◆ MotorStates

CIA 402 state machine motor states.

Enumerator
kReadyToSwitchOn 
kSwitchedOn 
kOperationEnabled 
kFault 
kVoltageEnabled 
kQuickStop 
kSwitchOnDisabled 
kWarning 
kRemote 
kTargetReached 
kInternalLimitActivate 

◆ OpMode

enum OpMode

Motor operation modes based on CiA402.

Enumerator
kProfilePosition 
kProfileVelocity 
kProfileTorque 
kHoming 
kInterpolatedPosition 
kCSPosition 
kCSVelocity 
kCSTorque 

◆ SensorConfig

Sensor Configuration for motor for more information

See also
EPOS4-Firmware-Specification pdf Pg.138 on : https://www.maxongroup.com/medias/sys_master/root/8834324856862/EPOS4-Firmware-Specification-En.pdf
Enumerator
kSensor1TypeNone 
kSensor1TypeDigitalIncrementalEncoder1 
kSensor2TypeNone 
kSensor2TypeDigitalIncrementalEncoder2 
kSensor2TypeAnalogIncrementalEncoderSinCos 
kSensor2TypeSSIAbsoluteEncoder 
kSensor3TypeNone 
kSensor3TypeDigitalHallSensor 

Function Documentation

◆ GetErrorMessage()

static std::string GetErrorMessage ( const int &  err_code)
static

◆ timespec_add()

struct timespec timespec_add ( struct timespec  time1,
struct timespec  time2 
)
inline

Add two timespec struct.

Parameters
time1Timespec struct 1
time2Timespec struct 2
Returns
Addition result

Variable Documentation

◆ g_cycle_time

const struct timespec g_cycle_time = {0, PERIOD_NS}

timer for DC sync .

◆ g_kNsPerSec

const uint32_t g_kNsPerSec = 1000000000

Nanoseconds per second.

◆ g_kNumberOfServoDrivers

const uint32_t g_kNumberOfServoDrivers = 1

Number of connected servo drives.

Note
If you are using custom slaves (not servo drives) this value must be different than NUM_OF_SLAVES.

◆ g_master

ec_master_t* g_master
extern

Extern global variable declaration.

◆ g_master_domain

ec_domain_t* g_master_domain
extern

EtherCAT master state.

◆ g_master_domain_state

ec_domain_state_t g_master_domain_state
extern

Ethercat data passing master domain.

◆ g_master_state

ec_master_state_t g_master_state
extern

EtherCAT master.

◆ g_sync_ref_counter

uint32_t g_sync_ref_counter
extern

cycletime settings in ns.

◆ g_sync_timer

struct timespec g_sync_timer
extern

EtherCAT master domain state.

◆ sig

volatile sig_atomic_t sig = 1
static