This class provides a CPP interface to the SimpleOpenEthercatMaster library Given the name of an ethernet device, such as "eth0", it will connect, start a thread that cycles data around the network, and provide read/write access to the underlying io map. More...
#include <ethercat_manager.h>
Public Member Functions | |
EtherCatManager (const std::string &ifname) | |
Constructs and initializes the ethercat slaves on a given network interface. | |
int | getNumClinets () const |
get the number of clients | |
void | getStatus (int slave_no, std::string &name, int &eep_man, int &eep_id, int &eep_rev, int &obits, int &ibits, int &state, int &pdelay, int &hasdc, int &activeports, int &configadr) const |
get the status of clients | |
uint8_t | readInput (int slave_no, uint8_t channel) const |
Reads the "channel-th" input-register of the given slave no. | |
uint8_t | readOutput (int slave_no, uint8_t channel) const |
Reads the "channel-th" output-register of the given slave no. | |
template<typename T > | |
T | readSDO (int slave_no, uint16_t index, uint8_t subidx) const |
read the SDO object of the given slave no | |
void | write (int slave_no, uint8_t channel, uint8_t value) |
writes 'value' to the 'channel-th' output-register of the given 'slave' | |
template<typename T > | |
uint8_t | writeSDO (int slave_no, uint16_t index, uint8_t subidx, T value) const |
write the SDO object of the given slave no | |
~EtherCatManager () | |
Private Member Functions | |
bool | initSoem (const std::string &ifname) |
Private Attributes | |
boost::thread | cycle_thread_ |
const std::string | ifname_ |
uint8_t | iomap_ [4096] |
boost::mutex | iomap_mutex_ |
int | num_clients_ |
bool | stop_flag_ |
This class provides a CPP interface to the SimpleOpenEthercatMaster library Given the name of an ethernet device, such as "eth0", it will connect, start a thread that cycles data around the network, and provide read/write access to the underlying io map.
Please note that as used in these docs, 'Input' and 'Output' are relative to your program. So the 'Output' registers are the ones you write to, for example.
Definition at line 65 of file ethercat_manager.h.
ethercat::EtherCatManager::EtherCatManager | ( | const std::string & | ifname | ) |
Constructs and initializes the ethercat slaves on a given network interface.
[in] | ifname | the name of the network interface that the ethercat chain is connected to (i.e. "eth0") |
Constructor can throw EtherCatError exception if SOEM could not be initialized.
Definition at line 168 of file ethercat_manager.cpp.
Definition at line 186 of file ethercat_manager.cpp.
int ethercat::EtherCatManager::getNumClinets | ( | ) | const |
get the number of clients
Definition at line 397 of file ethercat_manager.cpp.
void ethercat::EtherCatManager::getStatus | ( | int | slave_no, |
std::string & | name, | ||
int & | eep_man, | ||
int & | eep_id, | ||
int & | eep_rev, | ||
int & | obits, | ||
int & | ibits, | ||
int & | state, | ||
int & | pdelay, | ||
int & | hasdc, | ||
int & | activeports, | ||
int & | configadr | ||
) | const |
get the status of clients
Definition at line 402 of file ethercat_manager.cpp.
bool ethercat::EtherCatManager::initSoem | ( | const std::string & | ifname | ) | [private] |
Definition at line 202 of file ethercat_manager.cpp.
uint8_t ethercat::EtherCatManager::readInput | ( | int | slave_no, |
uint8_t | channel | ||
) | const |
Reads the "channel-th" input-register of the given slave no.
[in] | slave_no | The slave number of the device to read from (>= 1) |
[in] | channel | The byte offset into the input IOMap to read from |
Definition at line 427 of file ethercat_manager.cpp.
uint8_t ethercat::EtherCatManager::readOutput | ( | int | slave_no, |
uint8_t | channel | ||
) | const |
Reads the "channel-th" output-register of the given slave no.
[in] | slave_no | The slave number of the device to read from (>= 1) |
[in] | channel | The byte offset into the output IOMap to read from |
Definition at line 441 of file ethercat_manager.cpp.
template unsigned long ethercat::EtherCatManager::readSDO< unsigned long > | ( | int | slave_no, |
uint16_t | index, | ||
uint8_t | subidx | ||
) | const |
read the SDO object of the given slave no
[in] | slave_no | The slave number of the device to read from (>= 1) |
[in] | index | The index address of the parameter in SDO object |
[in] | subidx | The sub-index address of the parameter in SDO object |
Definition at line 464 of file ethercat_manager.cpp.
void ethercat::EtherCatManager::write | ( | int | slave_no, |
uint8_t | channel, | ||
uint8_t | value | ||
) |
writes 'value' to the 'channel-th' output-register of the given 'slave'
[in] | slave_no | The slave number of the device to write to (>= 1) |
[in] | channel | The byte offset into the output IOMap to write value to |
[in] | value | The byte value to write |
This method currently makes no attempt to catch out of bounds errors. Make sure you know your IOMap bounds.
Definition at line 421 of file ethercat_manager.cpp.
template uint8_t ethercat::EtherCatManager::writeSDO< unsigned long > | ( | int | slave_no, |
uint16_t | index, | ||
uint8_t | subidx, | ||
T | value | ||
) | const |
write the SDO object of the given slave no
[in] | slave_no | The slave number of the device to read from (>= 1) |
[in] | index | The index address of the parameter in SDO object |
[in] | subidx | The sub-index address of the parameter in SDO object |
[in] | value | value to write |
Definition at line 456 of file ethercat_manager.cpp.
boost::thread ethercat::EtherCatManager::cycle_thread_ [private] |
Definition at line 146 of file ethercat_manager.h.
const std::string ethercat::EtherCatManager::ifname_ [private] |
Definition at line 143 of file ethercat_manager.h.
uint8_t ethercat::EtherCatManager::iomap_[4096] [private] |
Definition at line 144 of file ethercat_manager.h.
boost::mutex ethercat::EtherCatManager::iomap_mutex_ [mutable, private] |
Definition at line 147 of file ethercat_manager.h.
int ethercat::EtherCatManager::num_clients_ [private] |
Definition at line 145 of file ethercat_manager.h.
bool ethercat::EtherCatManager::stop_flag_ [private] |
Definition at line 148 of file ethercat_manager.h.