![]() |
EtherCAT Control Framework v0.9
Implementation of EtherCAT protocol using IgH EtherCAT library for robot controller.
|
Class for encapsulating IgH EtherCAT library functionality. More...
#include <ecat_node.hpp>
Public Member Functions | |
EthercatNode () | |
~EthercatNode () | |
int | ConfigureMaster () |
Requests master instance and creates a domain for a master. 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 drive in specified 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 in specified 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 | MapDefaultPdos () |
Maps default PDOs for our 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 slaves and can be called in real-time. 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... | |
uint8_t | SdoRead (SDO_data &pack) |
Reads data from specified slave index and subindex via SDO. Writes data to pack.data. More... | |
uint8_t | SdoWrite (SDO_data &pack) |
Writes data to specied slave's index and subindex via SDO. More... | |
Public Attributes | |
EthercatSlave | slaves_ [NUM_OF_SLAVES] |
Slave instances. More... | |
Private Attributes | |
int | fd |
File descriptor to open and wake master from CLI. More... | |
Class for encapsulating IgH EtherCAT library functionality.
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 | Physical position w.r.t master. e.g 1,2,3... |
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 slaves and can be called in real-time.
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 our application.
int EthercatNode::OpenEthercatMaster | ( | ) |
Opens EtherCAT master via command line tool if it's not already on.
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.
uint8_t EthercatNode::SdoRead | ( | SDO_data & | pack | ) |
Reads data from specified slave index and subindex via SDO. Writes data to pack.data.
uint8_t EthercatNode::SdoWrite | ( | SDO_data & | pack | ) |
Writes data to specied slave's index and subindex via SDO.
pack | SDO data structure, contains index,subindex,slave position etc. |
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 w.r.t to master 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 drive in specified 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 in specified 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.
|
private |
File descriptor to open and wake master from CLI.
EthercatSlave EthercatCommunication::EthercatNode::slaves_[NUM_OF_SLAVES] |
Slave instances.