![]() |
EtherCAT Control Framework v0.9
Implementation of EtherCAT protocol using IgH EtherCAT library for robot controller.
|
#include <ecat_node.hpp>
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< SdoRequest > | request_sdos_ |
Private Attributes | |
int | fd |
File descriptor to open and wake master from CLI. More... | |
EthercatNode::EthercatNode | ( | ) |
EthercatNode::~EthercatNode | ( | ) |
int EthercatNode::ActivateMaster | ( | ) |
Activates master, after this function call realtime operation can start.
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.
int EthercatNode::CheckMasterState | ( | ) |
This function will check master's state, in terms of number of responding slaves and their application layer states.
void EthercatNode::CheckSlaveConfigurationState | ( | ) |
This function will check slave's application layer states. (INIT/PREOP/SAFEOP/OP)
void EthercatNode::ConfigDcSync | ( | uint16_t | assign_activate, |
int | position | ||
) |
Configures DC synchronization for specified slave position.
assign_activate | Activating DC synchronization for slave. 0x300 for Elmo | and same for EasyCAT |
position |
void EthercatNode::ConfigDcSyncDefault | ( | ) |
Configures DC sync for our default configuration.
int EthercatNode::ConfigureMaster | ( | ) |
Requests master instance and creates a domain for a master.
int EthercatNode::ConfigureSlaves | ( | ) |
Obtains slave configuration for all slaves w.r.t master.
void EthercatNode::DeactivateCommunication | ( | ) |
Deactivates master, and it is used to stop cyclic PDO exchange.
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.
int16_t EthercatCommunication::EthercatNode::DisableDrivesViaSDO | ( | int | index | ) |
Disable CiA402 supported motor drives in specified index via SDO.
index | slave index |
int16_t EthercatCommunication::EthercatNode::EnableDrivesViaSDO | ( | int | index | ) |
Enable CiA402 supported motor drives in specified index via SDO.
index | slave index |
void EthercatNode::GetAllSlaveInformation | ( | ) |
Get the information of physically connected slaves to the master. This function will return connected slave's vendor id, product code.
int EthercatNode::GetNumberOfConnectedSlaves | ( | ) |
Get the Number Of physically Connected Slaves to the bus.And checks if specified NUM_OF_SLAVES is correct.
int EthercatNode::MapCustomPdos | ( | EthercatSlave | c_slave, |
int | position | ||
) |
Map Custom PDO based on your PDO mappings.
c_slave | EthercatSlave instance |
position | Physical position of your slave w.r.t master |
int EthercatNode::MapDefaultPdos | ( | ) |
Maps default PDOs for the application.
This part is specific for our Custom EASYCAT slave configuration To create your custom slave and variables you can add variables to
int EthercatNode::MapDefaultSdos | ( | ) |
Maps default SDOs which can be found.
int EthercatNode::OpenEthercatMaster | ( | ) |
Opens EtherCAT master via command line tool if it's not already on.
int32_t EthercatNode::ReadActualPositionViaSDO | ( | int | index | ) |
Read actual position from slave in specified index via SDO.
index | slave index |
int16_t EthercatNode::ReadActualTorqueViaSDO | ( | int | index | ) |
Read actual torque value from slave in specified index via SDO.
index |
int32_t EthercatNode::ReadActualVelocityViaSDO | ( | int | index | ) |
Reads actual velocity value from slave in specified index via SDO.
index | slave index |
uint8_t EthercatNode::ReadOpModeViaSDO | ( | int | index | ) |
Reads current operational mode from slave in specified index via SDO.
index | slave index |
uint16_t EthercatNode::ReadSDO | ( | ec_sdo_request_t * | req, |
uint16_t & | status_word | ||
) |
Reads SDO in real-time context by creating read request.
req |
uint16_t EthercatNode::ReadStatusWordViaSDO | ( | int | index | ) |
Get the Status Word from CiA402 slaves in specified index via SDO communication.
index | slave index |
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.
void EthercatNode::ReleaseMaster | ( | ) |
Deactivates and releases master shouldn't be called in real-time.
int EthercatNode::RestartEthercatMaster | ( | ) |
Restarts Ethercat master via command line tool.
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.
pack | SDO_data struct which contains; index,subindex,data size, and data that will be used to store read data. |
int8_t EthercatNode::SdoWrite | ( | SDO_data & | pack | ) |
This function writes data to specified index and subindex via SDO.
pack | SDO_data struct which contains; index,subindex,data size and data to be written. |
void EthercatNode::SetCustomSlave | ( | EthercatSlave | c_slave, |
int | position | ||
) |
Passes your defined slave to EthercatNode class.
c_slave | first create your own EthercatSlave instance and modify it then pass it to configuration. |
position | specify the physical connection position for your custom configured slave. |
int EthercatNode::SetCyclicSyncPositionModeParameters | ( | CSPositionModeParam & | P, |
int | position | ||
) |
Set the Cyclic Sync Position Mode Parameters for slave in specified physical position w.r.t. master.
P | Cyclic Sync. Position Mode Parameters. |
position | Physical position of slave to be configured |
int EthercatNode::SetCyclicSyncPositionModeParametersAll | ( | CSPositionModeParam & | P | ) |
Sets the Cyclic Synchronous Position Mode Parameters for all connected motor driver slaves.
int EthercatNode::SetCyclicSyncTorqueModeParameters | ( | CSTorqueModeParam & | P, |
int | position | ||
) |
Set the Cyclic Sync Torque Mode Parameters for slave in specified physical position w.r.t. master.
P | Cyclic Sync. Torque Mode Parameters. |
position | Physical position of slave to be configured |
int EthercatNode::SetCyclicSyncTorqueModeParametersAll | ( | CSTorqueModeParam & | P | ) |
Sets the Cyclic Synchronous Torque Mode Parameters for all connected motor driver slaves.
int EthercatNode::SetCyclicSyncVelocityModeParameters | ( | CSVelocityModeParam & | P, |
int | position | ||
) |
Set the Cyclic Sync Velocity Mode Parameters for slave in specified physical position w.r.t. master.
P | Cyclic Sync. Velocity Mode Parameters. |
position | Physical position of slave to be configured |
int EthercatNode::SetCyclicSyncVelocityModeParametersAll | ( | CSVelocityModeParam & | P | ) |
Sets the Cyclic Synchronous Velocity Mode Parameters for all connected motor driver slaves.
int EthercatNode::SetProfilePositionParameters | ( | ProfilePosParam & | P, |
int | position | ||
) |
Set mode to ProfilePositionMode with specified parameters for servo drive on that position.
P | Profile position parameter structure specified by user. |
position | Slave position |
int EthercatNode::SetProfilePositionParametersAll | ( | ProfilePosParam & | P | ) |
Set the mode to ProfilePositionMode with specified Parameters for all servo drives on the bus.
P | Profile position parameter structure specified by user. |
int EthercatNode::SetProfileVelocityParameters | ( | ProfileVelocityParam & | P, |
int | position | ||
) |
Set mode to ProfileVelocityMode with specified parameters for servo drive on that position.
P | Profile velocity parameter structure specified by user. |
position | Slave position |
int EthercatNode::SetProfileVelocityParametersAll | ( | ProfileVelocityParam & | P | ) |
Set mode to ProfileVelocityMode with specified parameters for all servo drives on the bus.
P | Profile velocity parameter structure specified by user. |
int EthercatNode::ShutDownEthercatMaster | ( | ) |
Shutdowns EtherCAT master via command line tool if it's not already off.
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.
int16_t EthercatNode::WriteControlWordViaSDO | ( | int | index, |
uint16_t | control_word | ||
) |
Writes control word to slave in specified index via SDO.
index | slave index, |
control_word | control word to be written |
int16_t EthercatNode::WriteOpModeViaSDO | ( | int | index, |
uint8_t | op_mode | ||
) |
void EthercatNode::WriteSDO | ( | ec_sdo_request_t * | req, |
int32_t | data, | ||
int | size | ||
) |
Writes SDO in real-time context.
req | |
data |
int16_t EthercatNode::WriteTargetPositionViaSDO | ( | int | index, |
int32_t | target_pos | ||
) |
Writes target position value via SDO to slave in specified index.
index | slave index. |
target_pos | desired target position value. |
int16_t EthercatNode::WriteTargetTorqueViaSDO | ( | int | index, |
uint16_t | target_tor | ||
) |
Writes target torque value to slave in specified index via SDO.
index | slave index |
target_tor | desired target torque value. |
int16_t EthercatNode::WriteTargetVelocityViaSDO | ( | int | index, |
int32_t | target_vel | ||
) |
Writes target velocity value via SDO to slave in specified index.
index | slave index |
target_vel | desired target velocity val. |
|
private |
File descriptor to open and wake master from CLI.
std::vector<SdoRequest> EthercatCommunication::EthercatNode::request_sdos_ |
EthercatSlave EthercatCommunication::EthercatNode::slaves_[NUM_OF_SLAVES] |