Public Member Functions | Public Attributes | Private Member Functions | Static Private Member Functions | Private Attributes | List of all members
EthercatHardware Class Reference

#include <ethercat_hardware.h>

Public Member Functions

void collectDiagnostics ()
 Collects diagnotics from all devices. More...
 
 EthercatHardware (const std::string &name)
 Constructor. More...
 
void init (char *interface, bool allow_unprogrammed)
 Initialize the EtherCAT Master Library. More...
 
void printCounters (std::ostream &os=std::cout)
 
bool publishTrace (int position, const string &reason, unsigned level, unsigned delay)
 Ask one or all EtherCAT devices to publish (motor) traces. More...
 
bool txandrx_PD (unsigned buffer_size, unsigned char *buffer, unsigned tries)
 Send process data. More...
 
void update (bool reset, bool halt)
 Send most recent motor commands and retrieve updates. This command must be run at a sufficient rate or else the motors will be disabled. More...
 
 ~EthercatHardware ()
 Destructor. More...
 

Public Attributes

pr2_hardware_interface::HardwareInterfacehw_
 

Private Member Functions

boost::shared_ptr< EthercatDeviceconfigNonEthercatDevice (const std::string &product_id, const std::string &data)
 
boost::shared_ptr< EthercatDeviceconfigSlave (EtherCAT_SlaveHandler *sh)
 
void haltMotors (bool error, const char *reason)
 
void loadNonEthercatDevices ()
 
void publishDiagnostics ()
 Collects raw diagnostics data and passes it to diagnostics_publisher. More...
 

Static Private Member Functions

static void changeState (EtherCAT_SlaveHandler *sh, EC_State new_state)
 
static void updateAccMax (double &max, const accumulator_set< double, stats< tag::max, tag::mean > > &acc)
 

Private Attributes

EtherCAT_AL * al_
 
unsigned int buffer_size_
 
unsigned char * buffers_
 
pluginlib::ClassLoader< EthercatDevicedevice_loader_
 
EthercatHardwareDiagnostics diagnostics_
 
EthercatHardwareDiagnosticsPublisher diagnostics_publisher_
 
EtherCAT_Master * em_
 
bool halt_motors_
 
string interface_
 
ros::Time last_published_
 
ros::Time last_reset_
 
unsigned max_pd_retries_
 Max number of times to retry sending process data before halting motors. More...
 
realtime_tools::RealtimePublisher< std_msgs::Bool > motor_publisher_
 
struct netif * ni_
 
ros::NodeHandle node_
 
unsigned int num_ethercat_devices_
 
EthercatOobComoob_com_
 
unsigned char * prev_buffer_
 
unsigned int reset_state_
 
std::vector< boost::shared_ptr< EthercatDevice > > slaves_
 
unsigned char * this_buffer_
 
unsigned timeout_
 Timeout (in microseconds) to used for sending/recieving packets once in realtime mode. More...
 

Detailed Description

Definition at line 209 of file ethercat_hardware.h.

Constructor & Destructor Documentation

◆ EthercatHardware()

EthercatHardware::EthercatHardware ( const std::string &  name)

Constructor.

Definition at line 76 of file ethercat_hardware.cpp.

◆ ~EthercatHardware()

EthercatHardware::~EthercatHardware ( )

Destructor.

Definition at line 87 of file ethercat_hardware.cpp.

Member Function Documentation

◆ changeState()

void EthercatHardware::changeState ( EtherCAT_SlaveHandler *  sh,
EC_State  new_state 
)
staticprivate

Definition at line 107 of file ethercat_hardware.cpp.

◆ collectDiagnostics()

void EthercatHardware::collectDiagnostics ( )

Collects diagnotics from all devices.

Definition at line 923 of file ethercat_hardware.cpp.

◆ configNonEthercatDevice()

boost::shared_ptr< EthercatDevice > EthercatHardware::configNonEthercatDevice ( const std::string &  product_id,
const std::string &  data 
)
private

Definition at line 826 of file ethercat_hardware.cpp.

◆ configSlave()

boost::shared_ptr< EthercatDevice > EthercatHardware::configSlave ( EtherCAT_SlaveHandler *  sh)
private

Definition at line 719 of file ethercat_hardware.cpp.

◆ haltMotors()

void EthercatHardware::haltMotors ( bool  error,
const char *  reason 
)
private

Definition at line 661 of file ethercat_hardware.cpp.

◆ init()

void EthercatHardware::init ( char *  interface,
bool  allow_unprogrammed 
)

Initialize the EtherCAT Master Library.

Parameters
interfaceThe socket interface that is connected to the EtherCAT devices (e.g., eth0)
allow_unprogrammedA boolean indicating if the driver should treat the discovery of unprogrammed boards as a fatal error. Set to 'true' during board configuration, and set to 'false' otherwise.

Definition at line 124 of file ethercat_hardware.cpp.

◆ loadNonEthercatDevices()

void EthercatHardware::loadNonEthercatDevices ( )
private

Definition at line 855 of file ethercat_hardware.cpp.

◆ printCounters()

void EthercatHardware::printCounters ( std::ostream &  os = std::cout)

Definition at line 958 of file ethercat_hardware.cpp.

◆ publishDiagnostics()

void EthercatHardware::publishDiagnostics ( )
private

Collects raw diagnostics data and passes it to diagnostics_publisher.

Definition at line 692 of file ethercat_hardware.cpp.

◆ publishTrace()

bool EthercatHardware::publishTrace ( int  position,
const string &  reason,
unsigned  level,
unsigned  delay 
)

Ask one or all EtherCAT devices to publish (motor) traces.

Parameters
positiondevice ring position to publish trace for. Use -1 to trigger all devices.
reasonMessage to put in trace as reason.
levelLevel to put in trace (aka ERROR=2, WARN=1, OK=0)
delayPublish trace after delay cyles. For 1kHz realtime loop 1cycle = 1ms.
Returns
Return true if device supports publishing trace. False, if not. If all devices are triggered, returns true if any device publishes trace.

Definition at line 1000 of file ethercat_hardware.cpp.

◆ txandrx_PD()

bool EthercatHardware::txandrx_PD ( unsigned  buffer_size,
unsigned char *  buffer,
unsigned  tries 
)

Send process data.

Definition at line 983 of file ethercat_hardware.cpp.

◆ update()

void EthercatHardware::update ( bool  reset,
bool  halt 
)

Send most recent motor commands and retrieve updates. This command must be run at a sufficient rate or else the motors will be disabled.

Parameters
resetA boolean indicating if the motor controller boards should be reset
haltA boolean indicating if the motors should be halted

Definition at line 551 of file ethercat_hardware.cpp.

◆ updateAccMax()

void EthercatHardware::updateAccMax ( double &  max,
const accumulator_set< double, stats< tag::max, tag::mean > > &  acc 
)
staticprivate

Definition at line 687 of file ethercat_hardware.cpp.

Member Data Documentation

◆ al_

EtherCAT_AL* EthercatHardware::al_
private

Definition at line 274 of file ethercat_hardware.h.

◆ buffer_size_

unsigned int EthercatHardware::buffer_size_
private

Definition at line 284 of file ethercat_hardware.h.

◆ buffers_

unsigned char* EthercatHardware::buffers_
private

Definition at line 283 of file ethercat_hardware.h.

◆ device_loader_

pluginlib::ClassLoader<EthercatDevice> EthercatHardware::device_loader_
private

Definition at line 303 of file ethercat_hardware.h.

◆ diagnostics_

EthercatHardwareDiagnostics EthercatHardware::diagnostics_
private

Definition at line 294 of file ethercat_hardware.h.

◆ diagnostics_publisher_

EthercatHardwareDiagnosticsPublisher EthercatHardware::diagnostics_publisher_
private

Definition at line 295 of file ethercat_hardware.h.

◆ em_

EtherCAT_Master* EthercatHardware::em_
private

Definition at line 275 of file ethercat_hardware.h.

◆ halt_motors_

bool EthercatHardware::halt_motors_
private

Definition at line 286 of file ethercat_hardware.h.

◆ hw_

Definition at line 259 of file ethercat_hardware.h.

◆ interface_

string EthercatHardware::interface_
private

Definition at line 272 of file ethercat_hardware.h.

◆ last_published_

ros::Time EthercatHardware::last_published_
private

Definition at line 296 of file ethercat_hardware.h.

◆ last_reset_

ros::Time EthercatHardware::last_reset_
private

Definition at line 297 of file ethercat_hardware.h.

◆ max_pd_retries_

unsigned EthercatHardware::max_pd_retries_
private

Max number of times to retry sending process data before halting motors.

Definition at line 290 of file ethercat_hardware.h.

◆ motor_publisher_

realtime_tools::RealtimePublisher<std_msgs::Bool> EthercatHardware::motor_publisher_
private

Definition at line 299 of file ethercat_hardware.h.

◆ ni_

struct netif* EthercatHardware::ni_
private

Definition at line 271 of file ethercat_hardware.h.

◆ node_

ros::NodeHandle EthercatHardware::node_
private

Definition at line 269 of file ethercat_hardware.h.

◆ num_ethercat_devices_

unsigned int EthercatHardware::num_ethercat_devices_
private

Definition at line 279 of file ethercat_hardware.h.

◆ oob_com_

EthercatOobCom* EthercatHardware::oob_com_
private

Definition at line 301 of file ethercat_hardware.h.

◆ prev_buffer_

unsigned char* EthercatHardware::prev_buffer_
private

Definition at line 282 of file ethercat_hardware.h.

◆ reset_state_

unsigned int EthercatHardware::reset_state_
private

Definition at line 287 of file ethercat_hardware.h.

◆ slaves_

std::vector<boost::shared_ptr<EthercatDevice> > EthercatHardware::slaves_
private

Definition at line 278 of file ethercat_hardware.h.

◆ this_buffer_

unsigned char* EthercatHardware::this_buffer_
private

Definition at line 281 of file ethercat_hardware.h.

◆ timeout_

unsigned EthercatHardware::timeout_
private

Timeout (in microseconds) to used for sending/recieving packets once in realtime mode.

Definition at line 289 of file ethercat_hardware.h.


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


ethercat_hardware
Author(s): Rob Wheeler , Derek King
autogenerated on Tue Mar 28 2023 02:10:20