EtherCAT Control Framework v0.9
Implementation of EtherCAT protocol using IgH EtherCAT library for robot controller.
EthercatCommunication::EthercatNode Class Reference

#include <ecat_node.hpp>

Collaboration diagram for EthercatCommunication::EthercatNode:
[legend]

Public Member Functions

 EthercatNode ()
 
 ~EthercatNode ()
 
int ConfigureMaster ()
 Requests master instance and creates a domain for a master. More...
 
void DefineDefaultSlaves ()
 Defines default connected slaves based on number of slaves. Specifies its position, vendor id , product code etc. Default connected slaves considered implementation specific. In our case it will be 3 motors and one EasyCAT slave. More...
 
void SetCustomSlave (EthercatSlave c_slave, int position)
 Passes your defined slave to EthercatNode class. More...
 
int ConfigureSlaves ()
 Obtains slave configuration for all slaves w.r.t master. More...
 
int SetProfilePositionParameters (ProfilePosParam &P, int position)
 Set mode to ProfilePositionMode with specified parameters for servo drive on that position. More...
 
int SetProfilePositionParametersAll (ProfilePosParam &P)
 Set the mode to ProfilePositionMode with specified Parameters for all servo drives on the bus. More...
 
int SetProfileVelocityParameters (ProfileVelocityParam &P, int position)
 Set mode to ProfileVelocityMode with specified parameters for servo drive on that position. More...
 
int SetProfileVelocityParametersAll (ProfileVelocityParam &P)
 Set mode to ProfileVelocityMode with specified parameters for all servo drives on the bus. More...
 
int SetCyclicSyncPositionModeParameters (CSPositionModeParam &P, int position)
 Set the Cyclic Sync Position Mode Parameters for slave in specified physical position w.r.t. master. More...
 
int SetCyclicSyncPositionModeParametersAll (CSPositionModeParam &P)
 Sets the Cyclic Synchronous Position Mode Parameters for all connected motor driver slaves. More...
 
int SetCyclicSyncVelocityModeParameters (CSVelocityModeParam &P, int position)
 Set the Cyclic Sync Velocity Mode Parameters for slave in specified physical position w.r.t. master. More...
 
int SetCyclicSyncVelocityModeParametersAll (CSVelocityModeParam &P)
 Sets the Cyclic Synchronous Velocity Mode Parameters for all connected motor driver slaves. More...
 
int SetCyclicSyncTorqueModeParameters (CSTorqueModeParam &P, int position)
 Set the Cyclic Sync Torque Mode Parameters for slave in specified physical position w.r.t. master. More...
 
int SetCyclicSyncTorqueModeParametersAll (CSTorqueModeParam &P)
 Sets the Cyclic Synchronous Torque Mode Parameters for all connected motor driver slaves. More...
 
int MapDefaultSdos ()
 Maps default SDOs which can be found. More...
 
int MapDefaultPdos ()
 Maps default PDOs for the application. More...
 
int MapCustomPdos (EthercatSlave c_slave, int position)
 Map Custom PDO based on your PDO mappings. More...
 
void ConfigDcSyncDefault ()
 Configures DC sync for our default configuration. More...
 
void ConfigDcSync (uint16_t assign_activate, int position)
 Configures DC synchronization for specified slave position. More...
 
void CheckSlaveConfigurationState ()
 This function will check slave's application layer states. (INIT/PREOP/SAFEOP/OP) More...
 
int CheckMasterState ()
 This function will check master's state, in terms of number of responding slaves and their application layer states. More...
 
void CheckMasterDomainState ()
 Reads the state of a domain. Stores the domain state in the given state structure. Using this method, the process data exchange can be monitored in realtime. More...
 
int ActivateMaster ()
 Activates master, after this function call realtime operation can start. More...
 
int RegisterDomain ()
 Registers domain for each slave. This method has to be called after ecrt_master_activate() to get the mapped domain process data memory. More...
 
int WaitForOperationalMode ()
 Puts all slave to operational mode. User must call this before entering real-time operation. Reason for this function is that, master and slave has to do several exchange before becoming operational. So this function does exchange between master and slaves for up to 10 sec, could finish earlier. If timeout occurs it will return -1. More...
 
int OpenEthercatMaster ()
 Opens EtherCAT master via command line tool if it's not already on. More...
 
int GetNumberOfConnectedSlaves ()
 Get the Number Of physically Connected Slaves to the bus.And checks if specified NUM_OF_SLAVES is correct. More...
 
void GetAllSlaveInformation ()
 Get the information of physically connected slaves to the master. This function will return connected slave's vendor id, product code. More...
 
void DeactivateCommunication ()
 Deactivates master, and it is used to stop cyclic PDO exchange. More...
 
void ReleaseMaster ()
 Deactivates and releases master shouldn't be called in real-time. More...
 
int ShutDownEthercatMaster ()
 Shutdowns EtherCAT master via command line tool if it's not already off. More...
 
int RestartEthercatMaster ()
 Restarts Ethercat master via command line tool. More...
 
void WriteSDO (ec_sdo_request_t *req, int32_t data, int size)
 Writes SDO in real-time context. More...
 
uint16_t ReadSDO (ec_sdo_request_t *req, uint16_t &status_word)
 Reads SDO in real-time context by creating read request. More...
 
int8_t SdoRead (SDO_data &pack)
 This function reads data from specified index and subindex via SDO, returned data will be stored in pack.data which needs to be casted to correct data type afterwards. More...
 
int8_t SdoWrite (SDO_data &pack)
 This function writes data to specified index and subindex via SDO. More...
 
uint16_t ReadStatusWordViaSDO (int index)
 Get the Status Word from CiA402 slaves in specified index via SDO communication. More...
 
int16_t WriteControlWordViaSDO (int index, uint16_t control_word)
 Writes control word to slave in specified index via SDO. More...
 
int16_t WriteOpModeViaSDO (int index, uint8_t op_mode)
 
uint8_t ReadOpModeViaSDO (int index)
 Reads current operational mode from slave in specified index via SDO. More...
 
int32_t ReadActualVelocityViaSDO (int index)
 Reads actual velocity value from slave in specified index via SDO. More...
 
int16_t WriteTargetVelocityViaSDO (int index, int32_t target_vel)
 Writes target velocity value via SDO to slave in specified index. More...
 
int32_t ReadActualPositionViaSDO (int index)
 Read actual position from slave in specified index via SDO. More...
 
int16_t WriteTargetPositionViaSDO (int index, int32_t target_pos)
 Writes target position value via SDO to slave in specified index. More...
 
int16_t ReadActualTorqueViaSDO (int index)
 Read actual torque value from slave in specified index via SDO. More...
 
int16_t WriteTargetTorqueViaSDO (int index, uint16_t target_tor)
 Writes target torque value to slave in specified index via SDO. More...
 
int16_t EnableDrivesViaSDO (int index)
 Enable CiA402 supported motor drives in specified index via SDO. More...
 
int16_t DisableDrivesViaSDO (int index)
 Disable CiA402 supported motor drives in specified index via SDO. More...
 

Public Attributes

EthercatSlave slaves_ [NUM_OF_SLAVES]
 
std::vector< SdoRequestrequest_sdos_
 

Private Attributes

int fd
 File descriptor to open and wake master from CLI. More...
 

Constructor & Destructor Documentation

◆ EthercatNode()

EthercatNode::EthercatNode ( )

◆ ~EthercatNode()

EthercatNode::~EthercatNode ( )

Member Function Documentation

◆ ActivateMaster()

int EthercatNode::ActivateMaster ( )

Activates master, after this function call realtime operation can start.

Warning
Before activating master all configuration should be done
After calling this function you have to register domain(s) and start realtime task.
Returns
0 if succesful, otherwise -1.

◆ CheckMasterDomainState()

void EthercatNode::CheckMasterDomainState ( )

Reads the state of a domain. Stores the domain state in the given state structure. Using this method, the process data exchange can be monitored in realtime.

◆ CheckMasterState()

int EthercatNode::CheckMasterState ( )

This function will check master's state, in terms of number of responding slaves and their application layer states.

Returns
0 if succesful, otherwise -1
See also
ec_master_state_t structure.

◆ CheckSlaveConfigurationState()

void EthercatNode::CheckSlaveConfigurationState ( )

This function will check slave's application layer states. (INIT/PREOP/SAFEOP/OP)

◆ ConfigDcSync()

void EthercatNode::ConfigDcSync ( uint16_t  assign_activate,
int  position 
)

Configures DC synchronization for specified slave position.

Parameters
assign_activateActivating DC synchronization for slave. 0x300 for Elmo | and same for EasyCAT
Note
Assign activate parameters specified in slaves ESI file
Parameters
position

◆ ConfigDcSyncDefault()

void EthercatNode::ConfigDcSyncDefault ( )

Configures DC sync for our default configuration.

◆ ConfigureMaster()

int EthercatNode::ConfigureMaster ( )

Requests master instance and creates a domain for a master.

Note
Keep in mind that created master and domain are global variables.
Returns
0 if succesful otherwise -1.

◆ ConfigureSlaves()

int EthercatNode::ConfigureSlaves ( )

Obtains slave configuration for all slaves w.r.t master.

Returns
0 if successfull, otherwise -1.

◆ DeactivateCommunication()

void EthercatNode::DeactivateCommunication ( )

Deactivates master, and it is used to stop cyclic PDO exchange.

Note
That calling this function means that your PDO exchange will stop.
Additionally all pointers created by requesting master are freed with this function./ If you want to resume your communication, you'll have to do the configuration again.

◆ DefineDefaultSlaves()

void EthercatCommunication::EthercatNode::DefineDefaultSlaves ( )

Defines default connected slaves based on number of slaves. Specifies its position, vendor id , product code etc. Default connected slaves considered implementation specific. In our case it will be 3 motors and one EasyCAT slave.

◆ DisableDrivesViaSDO()

int16_t EthercatCommunication::EthercatNode::DisableDrivesViaSDO ( int  index)

Disable CiA402 supported motor drives in specified index via SDO.

Parameters
indexslave index
Returns
0 if successfull, otherwise -1.

◆ EnableDrivesViaSDO()

int16_t EthercatCommunication::EthercatNode::EnableDrivesViaSDO ( int  index)

Enable CiA402 supported motor drives in specified index via SDO.

Parameters
indexslave index
Returns
0 if successfull, otherwise -1.

◆ GetAllSlaveInformation()

void EthercatNode::GetAllSlaveInformation ( )

Get the information of physically connected slaves to the master. This function will return connected slave's vendor id, product code.

◆ GetNumberOfConnectedSlaves()

int EthercatNode::GetNumberOfConnectedSlaves ( )

Get the Number Of physically Connected Slaves to the bus.And checks if specified NUM_OF_SLAVES is correct.

Returns
0 if NUM_OF_SLAVES setting is correct, otherwise -1.

◆ MapCustomPdos()

int EthercatNode::MapCustomPdos ( EthercatSlave  c_slave,
int  position 
)

Map Custom PDO based on your PDO mappings.

Note
You have to specify slave syncs and slave pdo registers before using function
Parameters
c_slaveEthercatSlave instance
positionPhysical position of your slave w.r.t master
Returns
0 if successfull, -1 otherwise.

◆ MapDefaultPdos()

int EthercatNode::MapDefaultPdos ( )

Maps default PDOs for the application.

Note
This method is specific to our implementation. However you can modify it to suit your needs. If you have different topology or different servo drives use MapCustomPdos() function or modify this function based on your needs.
Returns
0 if successfull, otherwise -1.

This part is specific for our Custom EASYCAT slave configuration To create your custom slave and variables you can add variables to

See also
OffsetPDO struct. Also you have add your variables to received data structure, you may have to create your custom msg files as well.

◆ MapDefaultSdos()

int EthercatNode::MapDefaultSdos ( )

Maps default SDOs which can be found.

See also
SdoRequest struct.
Returns
0 if successfull, otherwise -1.

◆ OpenEthercatMaster()

int EthercatNode::OpenEthercatMaster ( )

Opens EtherCAT master via command line tool if it's not already on.

Returns
0 if successfull, otherwise -1.

◆ ReadActualPositionViaSDO()

int32_t EthercatNode::ReadActualPositionViaSDO ( int  index)

Read actual position from slave in specified index via SDO.

Parameters
indexslave index
Returns
actual position of selected slave.

◆ ReadActualTorqueViaSDO()

int16_t EthercatNode::ReadActualTorqueViaSDO ( int  index)

Read actual torque value from slave in specified index via SDO.

Parameters
index
Returns
uint16_t

◆ ReadActualVelocityViaSDO()

int32_t EthercatNode::ReadActualVelocityViaSDO ( int  index)

Reads actual velocity value from slave in specified index via SDO.

Parameters
indexslave index
Returns
actual velocity value of selected slave.

◆ ReadOpModeViaSDO()

uint8_t EthercatNode::ReadOpModeViaSDO ( int  index)

Reads current operational mode from slave in specified index via SDO.

Parameters
indexslave index
Returns
status word of selected slave.

◆ ReadSDO()

uint16_t EthercatNode::ReadSDO ( ec_sdo_request_t *  req,
uint16_t &  status_word 
)

Reads SDO in real-time context by creating read request.

Parameters
req

◆ ReadStatusWordViaSDO()

uint16_t EthercatNode::ReadStatusWordViaSDO ( int  index)

Get the Status Word from CiA402 slaves in specified index via SDO communication.

Parameters
indexslave index
Returns
status word

◆ RegisterDomain()

int EthercatNode::RegisterDomain ( )

Registers domain for each slave. This method has to be called after ecrt_master_activate() to get the mapped domain process data memory.

Returns
0 if succeful , otherwise -1

◆ ReleaseMaster()

void EthercatNode::ReleaseMaster ( )

Deactivates and releases master shouldn't be called in real-time.

◆ RestartEthercatMaster()

int EthercatNode::RestartEthercatMaster ( )

Restarts Ethercat master via command line tool.

Returns
0 if successfull, otherwise -1.

◆ SdoRead()

int8_t EthercatNode::SdoRead ( SDO_data pack)

This function reads data from specified index and subindex via SDO, returned data will be stored in pack.data which needs to be casted to correct data type afterwards.

See also
@SDO_data struct
Note
This is a blocking function, until response has been received.Don't use it in real-time context!!.
Parameters
packSDO_data struct which contains; index,subindex,data size, and data that will be used to store read data.
Returns
0 if successfull, otherwise -1.

◆ SdoWrite()

int8_t EthercatNode::SdoWrite ( SDO_data pack)

This function writes data to specified index and subindex via SDO.

See also
@SDO_data struct
Note
This is a blocking function, until response has been received.Don't use it in real-time context!!.
Parameters
packSDO_data struct which contains; index,subindex,data size and data to be written.
Returns
0 if successfull, otherwise -1.

◆ SetCustomSlave()

void EthercatNode::SetCustomSlave ( EthercatSlave  c_slave,
int  position 
)

Passes your defined slave to EthercatNode class.

Parameters
c_slavefirst create your own EthercatSlave instance and modify it then pass it to configuration.
positionspecify the physical connection position for your custom configured slave.

◆ SetCyclicSyncPositionModeParameters()

int EthercatNode::SetCyclicSyncPositionModeParameters ( CSPositionModeParam P,
int  position 
)

Set the Cyclic Sync Position Mode Parameters for slave in specified physical position w.r.t. master.

Parameters
PCyclic Sync. Position Mode Parameters.
positionPhysical position of slave to be configured
Returns
0 if sucessfull, otherwise -1.

◆ SetCyclicSyncPositionModeParametersAll()

int EthercatNode::SetCyclicSyncPositionModeParametersAll ( CSPositionModeParam P)

Sets the Cyclic Synchronous Position Mode Parameters for all connected motor driver slaves.

Returns
0 if sucessful, otherwise -1.

◆ SetCyclicSyncTorqueModeParameters()

int EthercatNode::SetCyclicSyncTorqueModeParameters ( CSTorqueModeParam P,
int  position 
)

Set the Cyclic Sync Torque Mode Parameters for slave in specified physical position w.r.t. master.

Parameters
PCyclic Sync. Torque Mode Parameters.
positionPhysical position of slave to be configured
Returns
0 if sucessfull, otherwise -1.

◆ SetCyclicSyncTorqueModeParametersAll()

int EthercatNode::SetCyclicSyncTorqueModeParametersAll ( CSTorqueModeParam P)

Sets the Cyclic Synchronous Torque Mode Parameters for all connected motor driver slaves.

Returns
0 if sucessful, otherwise -1.

◆ SetCyclicSyncVelocityModeParameters()

int EthercatNode::SetCyclicSyncVelocityModeParameters ( CSVelocityModeParam P,
int  position 
)

Set the Cyclic Sync Velocity Mode Parameters for slave in specified physical position w.r.t. master.

Parameters
PCyclic Sync. Velocity Mode Parameters.
positionPhysical position of slave to be configured
Returns
0 if sucessfull, otherwise -1.

◆ SetCyclicSyncVelocityModeParametersAll()

int EthercatNode::SetCyclicSyncVelocityModeParametersAll ( CSVelocityModeParam P)

Sets the Cyclic Synchronous Velocity Mode Parameters for all connected motor driver slaves.

Returns
0 if sucessful, otherwise -1.

◆ SetProfilePositionParameters()

int EthercatNode::SetProfilePositionParameters ( ProfilePosParam P,
int  position 
)

Set mode to ProfilePositionMode with specified parameters for servo drive on that position.

Parameters
PProfile position parameter structure specified by user.
positionSlave position
Returns
0 if successfull, otherwise -1.

◆ SetProfilePositionParametersAll()

int EthercatNode::SetProfilePositionParametersAll ( ProfilePosParam P)

Set the mode to ProfilePositionMode with specified Parameters for all servo drives on the bus.

Parameters
PProfile position parameter structure specified by user.
Returns
0 if succesful, otherwise -1.

◆ SetProfileVelocityParameters()

int EthercatNode::SetProfileVelocityParameters ( ProfileVelocityParam P,
int  position 
)

Set mode to ProfileVelocityMode with specified parameters for servo drive on that position.

Parameters
PProfile velocity parameter structure specified by user.
positionSlave position
Returns
0 if succesful, -1 otherwise.

◆ SetProfileVelocityParametersAll()

int EthercatNode::SetProfileVelocityParametersAll ( ProfileVelocityParam P)

Set mode to ProfileVelocityMode with specified parameters for all servo drives on the bus.

Parameters
PProfile velocity parameter structure specified by user.
Returns
0 if successfull, -1 otherwise.

◆ ShutDownEthercatMaster()

int EthercatNode::ShutDownEthercatMaster ( )

Shutdowns EtherCAT master via command line tool if it's not already off.

Returns
0 if successfull, otherwise -1.

◆ WaitForOperationalMode()

int EthercatNode::WaitForOperationalMode ( )

Puts all slave to operational mode. User must call this before entering real-time operation. Reason for this function is that, master and slave has to do several exchange before becoming operational. So this function does exchange between master and slaves for up to 10 sec, could finish earlier. If timeout occurs it will return -1.

Returns
0 if successfull, otherwise -1.

◆ WriteControlWordViaSDO()

int16_t EthercatNode::WriteControlWordViaSDO ( int  index,
uint16_t  control_word 
)

Writes control word to slave in specified index via SDO.

Parameters
indexslave index,
control_wordcontrol word to be written
Returns
0 if successfull otherwise -1.

◆ WriteOpModeViaSDO()

int16_t EthercatNode::WriteOpModeViaSDO ( int  index,
uint8_t  op_mode 
)

◆ WriteSDO()

void EthercatNode::WriteSDO ( ec_sdo_request_t *  req,
int32_t  data,
int  size 
)

Writes SDO in real-time context.

Parameters
req
data

◆ WriteTargetPositionViaSDO()

int16_t EthercatNode::WriteTargetPositionViaSDO ( int  index,
int32_t  target_pos 
)

Writes target position value via SDO to slave in specified index.

Parameters
indexslave index.
target_posdesired target position value.
Returns
0 if successfull, otherwise -1.

◆ WriteTargetTorqueViaSDO()

int16_t EthercatNode::WriteTargetTorqueViaSDO ( int  index,
uint16_t  target_tor 
)

Writes target torque value to slave in specified index via SDO.

Parameters
indexslave index
target_tordesired target torque value.
Returns
0 if successfull, otherwise -1.

◆ WriteTargetVelocityViaSDO()

int16_t EthercatNode::WriteTargetVelocityViaSDO ( int  index,
int32_t  target_vel 
)

Writes target velocity value via SDO to slave in specified index.

Parameters
indexslave index
target_veldesired target velocity val.
Returns
0 if successfull, othewise -1.

Member Data Documentation

◆ fd

int EthercatCommunication::EthercatNode::fd
private

File descriptor to open and wake master from CLI.

◆ request_sdos_

std::vector<SdoRequest> EthercatCommunication::EthercatNode::request_sdos_

◆ slaves_

EthercatSlave EthercatCommunication::EthercatNode::slaves_[NUM_OF_SLAVES]

The documentation for this class was generated from the following files: