#include <ethercat_hardware.h>
Public Member Functions | |
EthercatHardwareDiagnostics () | |
void | resetMaxTiming () |
Public Attributes | |
struct netif_counters | counters_ |
unsigned | device_count_ |
bool | halt_after_reset_ |
True if motor halt soon after motor reset. | |
unsigned | halt_motors_error_count_ |
Number of transitions into halt state due to device error. | |
unsigned | halt_motors_service_count_ |
Number of time halt_motor service call is used. | |
bool | input_thread_is_stopped_ |
double | max_pack_command_ |
double | max_publish_ |
double | max_txandrx_ |
double | max_unpack_state_ |
bool | motors_halted_ |
True if motors are halted. | |
const char * | motors_halted_reason_ |
reason that motors first halted | |
accumulator_set< double, stats < tag::max, tag::mean > > | pack_command_acc_ |
time taken by all devices packCommand functions | |
bool | pd_error_ |
accumulator_set< double, stats < tag::max, tag::mean > > | publish_acc_ |
time taken by any publishing step in main loop | |
unsigned | reset_motors_service_count_ |
Number of times reset_motor service has been used. | |
accumulator_set< double, stats < tag::max, tag::mean > > | txandrx_acc_ |
time taken by to transmit and recieve process data | |
int | txandrx_errors_ |
accumulator_set< double, stats < tag::max, tag::mean > > | unpack_state_acc_ |
time taken by all devices updateState functions | |
Static Public Attributes | |
static const bool | collect_extra_timing_ = true |
Definition at line 67 of file ethercat_hardware.h.
Definition at line 48 of file ethercat_hardware.cpp.
Definition at line 63 of file ethercat_hardware.cpp.
const bool EthercatHardwareDiagnostics::collect_extra_timing_ = true [static] |
Definition at line 91 of file ethercat_hardware.h.
struct netif_counters EthercatHardwareDiagnostics::counters_ |
Definition at line 86 of file ethercat_hardware.h.
Definition at line 80 of file ethercat_hardware.h.
True if motor halt soon after motor reset.
Definition at line 82 of file ethercat_hardware.h.
Number of transitions into halt state due to device error.
Definition at line 85 of file ethercat_hardware.h.
Number of time halt_motor service call is used.
Definition at line 84 of file ethercat_hardware.h.
Definition at line 87 of file ethercat_hardware.h.
Definition at line 75 of file ethercat_hardware.h.
Definition at line 78 of file ethercat_hardware.h.
Definition at line 76 of file ethercat_hardware.h.
Definition at line 77 of file ethercat_hardware.h.
True if motors are halted.
Definition at line 88 of file ethercat_hardware.h.
reason that motors first halted
Definition at line 89 of file ethercat_hardware.h.
accumulator_set<double, stats<tag::max, tag::mean> > EthercatHardwareDiagnostics::pack_command_acc_ |
time taken by all devices packCommand functions
Definition at line 71 of file ethercat_hardware.h.
Definition at line 81 of file ethercat_hardware.h.
accumulator_set<double, stats<tag::max, tag::mean> > EthercatHardwareDiagnostics::publish_acc_ |
time taken by any publishing step in main loop
Definition at line 74 of file ethercat_hardware.h.
Number of times reset_motor service has been used.
Definition at line 83 of file ethercat_hardware.h.
accumulator_set<double, stats<tag::max, tag::mean> > EthercatHardwareDiagnostics::txandrx_acc_ |
time taken by to transmit and recieve process data
Definition at line 72 of file ethercat_hardware.h.
Definition at line 79 of file ethercat_hardware.h.
accumulator_set<double, stats<tag::max, tag::mean> > EthercatHardwareDiagnostics::unpack_state_acc_ |
time taken by all devices updateState functions
Definition at line 73 of file ethercat_hardware.h.