Public Member Functions | Public Attributes | Private Member Functions | Static Private Member Functions | Private Attributes
EthercatHardware Class Reference

#include <ethercat_hardware.h>

List of all members.

Public Member Functions

void collectDiagnostics ()
 Collects diagnotics from all devices.
 EthercatHardware (const std::string &name)
 Constructor.
void init (char *interface, bool allow_unprogrammed)
 Initialize the EtherCAT Master Library.
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.
bool txandrx_PD (unsigned buffer_size, unsigned char *buffer, unsigned tries)
 Send process data.
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.
 ~EthercatHardware ()
 Destructor.

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.

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
< EthercatDevice
device_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.
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.

Detailed Description

Definition at line 203 of file ethercat_hardware.h.


Constructor & Destructor Documentation

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

Constructor.

Definition at line 71 of file ethercat_hardware.cpp.

Destructor.

Definition at line 82 of file ethercat_hardware.cpp.


Member Function Documentation

void EthercatHardware::changeState ( EtherCAT_SlaveHandler *  sh,
EC_State  new_state 
) [static, private]

Definition at line 102 of file ethercat_hardware.cpp.

Collects diagnotics from all devices.

Definition at line 918 of file ethercat_hardware.cpp.

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

Definition at line 821 of file ethercat_hardware.cpp.

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

Definition at line 714 of file ethercat_hardware.cpp.

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

Definition at line 656 of file ethercat_hardware.cpp.

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 119 of file ethercat_hardware.cpp.

Definition at line 850 of file ethercat_hardware.cpp.

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

Definition at line 953 of file ethercat_hardware.cpp.

Collects raw diagnostics data and passes it to diagnostics_publisher.

Definition at line 687 of file ethercat_hardware.cpp.

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 995 of file ethercat_hardware.cpp.

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

Send process data.

Definition at line 978 of file ethercat_hardware.cpp.

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 546 of file ethercat_hardware.cpp.

void EthercatHardware::updateAccMax ( double &  max,
const accumulator_set< double, stats< tag::max, tag::mean > > &  acc 
) [static, private]

Definition at line 682 of file ethercat_hardware.cpp.


Member Data Documentation

EtherCAT_AL* EthercatHardware::al_ [private]

Definition at line 268 of file ethercat_hardware.h.

unsigned int EthercatHardware::buffer_size_ [private]

Definition at line 278 of file ethercat_hardware.h.

unsigned char* EthercatHardware::buffers_ [private]

Definition at line 277 of file ethercat_hardware.h.

Definition at line 297 of file ethercat_hardware.h.

Definition at line 288 of file ethercat_hardware.h.

Definition at line 289 of file ethercat_hardware.h.

EtherCAT_Master* EthercatHardware::em_ [private]

Definition at line 269 of file ethercat_hardware.h.

Definition at line 280 of file ethercat_hardware.h.

Definition at line 253 of file ethercat_hardware.h.

string EthercatHardware::interface_ [private]

Definition at line 266 of file ethercat_hardware.h.

Definition at line 290 of file ethercat_hardware.h.

Definition at line 291 of file ethercat_hardware.h.

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

Definition at line 284 of file ethercat_hardware.h.

Definition at line 293 of file ethercat_hardware.h.

struct netif* EthercatHardware::ni_ [private]

Definition at line 265 of file ethercat_hardware.h.

Definition at line 263 of file ethercat_hardware.h.

Definition at line 273 of file ethercat_hardware.h.

Definition at line 295 of file ethercat_hardware.h.

unsigned char* EthercatHardware::prev_buffer_ [private]

Definition at line 276 of file ethercat_hardware.h.

unsigned int EthercatHardware::reset_state_ [private]

Definition at line 281 of file ethercat_hardware.h.

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

Definition at line 272 of file ethercat_hardware.h.

unsigned char* EthercatHardware::this_buffer_ [private]

Definition at line 275 of file ethercat_hardware.h.

unsigned EthercatHardware::timeout_ [private]

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

Definition at line 283 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 Fri Aug 28 2015 12:09:44