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

Publishes EthercatHardware diagnostics. More...

#include <ethercat_hardware.h>

Public Member Functions

 EthercatHardwareDiagnosticsPublisher (ros::NodeHandle &node)
 
void initialize (const string &interface, unsigned int buffer_size, const std::vector< boost::shared_ptr< EthercatDevice > > &slaves, unsigned int num_ethercat_devices_, unsigned timeout, unsigned max_pd_retries)
 Initializes hardware publish. More...
 
void publish (const unsigned char *buffer, const EthercatHardwareDiagnostics &diagnostics)
 Triggers publishing of new diagnostics data. More...
 
void stop ()
 Stops publishing thread. May block. More...
 
 ~EthercatHardwareDiagnosticsPublisher ()
 

Private Member Functions

void diagnosticsThreadFunc ()
 Publishing thread main loop. More...
 
void publishDiagnostics ()
 Publishes diagnostics. More...
 

Static Private Member Functions

static void timingInformation (diagnostic_updater::DiagnosticStatusWrapper &status, const string &key, const accumulator_set< double, stats< tag::max, tag::mean > > &acc, double max)
 Helper function for converting timing for diagnostics. More...
 

Private Attributes

unsigned int buffer_size_
 
diagnostic_msgs::DiagnosticArray diagnostic_array_
 
EthercatHardwareDiagnostics diagnostics_
 Diagnostics information use by publish function. More...
 
unsigned char * diagnostics_buffer_
 
boost::condition_variable diagnostics_cond_
 
boost::mutex diagnostics_mutex_
 mutex protects all class data and cond variable More...
 
bool diagnostics_ready_
 
boost::thread diagnostics_thread_
 
EthernetInterfaceInfo ethernet_interface_info_
 Information about Ethernet interface used for EtherCAT communication. More...
 
string interface_
 
uint64_t last_dropped_packet_count_
 Count of dropped packets last diagnostics cycle. More...
 
ros::Time last_dropped_packet_time_
 Time last packet was dropped 0 otherwise. Used for warning about dropped packets. More...
 
unsigned max_pd_retries_
 Number of times (in a row) to retry sending process data (realtime data) before halting motors. More...
 
ros::NodeHandle node_
 
unsigned int num_ethercat_devices_
 
ros::Publisher publisher_
 
std::vector< boost::shared_ptr< EthercatDevice > > slaves_
 
diagnostic_updater::DiagnosticStatusWrapper status_
 
unsigned timeout_
 Timeout controls how long EtherCAT driver waits for packet before declaring it as dropped. More...
 
vector< diagnostic_msgs::KeyValue > values_
 

Static Private Attributes

static const unsigned dropped_packet_warning_hold_time_ = 10
 Number of seconds since late dropped packet to keep warning. More...
 

Detailed Description

Publishes EthercatHardware diagnostics.

All the string formating used for creatign diagnostics is too slow to be run in the realtime thread. Instead, a copy of the raw diagnostics data is made and a separate thread does the string conversion and publishing. Previously, the diagnostics data used by publishing thread was contained in the EthercatHardware class. However, this allowed the publishing thread access to other non thread-safe data. This class keeps the diagnostics data used by the publish thread explicitly separate.

Definition at line 114 of file ethercat_hardware.h.

Constructor & Destructor Documentation

◆ EthercatHardwareDiagnosticsPublisher()

EthercatHardwareDiagnosticsPublisher::EthercatHardwareDiagnosticsPublisher ( ros::NodeHandle node)

Definition at line 347 of file ethercat_hardware.cpp.

◆ ~EthercatHardwareDiagnosticsPublisher()

EthercatHardwareDiagnosticsPublisher::~EthercatHardwareDiagnosticsPublisher ( )

Definition at line 357 of file ethercat_hardware.cpp.

Member Function Documentation

◆ diagnosticsThreadFunc()

void EthercatHardwareDiagnosticsPublisher::diagnosticsThreadFunc ( )
private

Publishing thread main loop.

Waits for condition variable to start publishing internal data.

Definition at line 409 of file ethercat_hardware.cpp.

◆ initialize()

void EthercatHardwareDiagnosticsPublisher::initialize ( const string &  interface,
unsigned int  buffer_size,
const std::vector< boost::shared_ptr< EthercatDevice > > &  slaves,
unsigned int  num_ethercat_devices_,
unsigned  timeout,
unsigned  max_pd_retries 
)

Initializes hardware publish.

Parameters
buffer_sizesize of proccess data buffer
numberof EtherCAT slave devices

Definition at line 362 of file ethercat_hardware.cpp.

◆ publish()

void EthercatHardwareDiagnosticsPublisher::publish ( const unsigned char *  buffer,
const EthercatHardwareDiagnostics diagnostics 
)

Triggers publishing of new diagnostics data.

Makes copy of diagnostics data and triggers internal thread to started conversion and publish of data. This function will not block.

Definition at line 385 of file ethercat_hardware.cpp.

◆ publishDiagnostics()

void EthercatHardwareDiagnosticsPublisher::publishDiagnostics ( )
private

Publishes diagnostics.

Takes internally saved diagnostics data and converts to a ROS diagnostics status message. This function performs a lot of string formatting, so it is slow.

Definition at line 436 of file ethercat_hardware.cpp.

◆ stop()

void EthercatHardwareDiagnosticsPublisher::stop ( )

Stops publishing thread. May block.

Definition at line 402 of file ethercat_hardware.cpp.

◆ timingInformation()

void EthercatHardwareDiagnosticsPublisher::timingInformation ( diagnostic_updater::DiagnosticStatusWrapper status,
const string &  key,
const accumulator_set< double, stats< tag::max, tag::mean > > &  acc,
double  max 
)
staticprivate

Helper function for converting timing for diagnostics.

Definition at line 425 of file ethercat_hardware.cpp.

Member Data Documentation

◆ buffer_size_

unsigned int EthercatHardwareDiagnosticsPublisher::buffer_size_
private

Definition at line 184 of file ethercat_hardware.h.

◆ diagnostic_array_

diagnostic_msgs::DiagnosticArray EthercatHardwareDiagnosticsPublisher::diagnostic_array_
private

Definition at line 201 of file ethercat_hardware.h.

◆ diagnostics_

EthercatHardwareDiagnostics EthercatHardwareDiagnosticsPublisher::diagnostics_
private

Diagnostics information use by publish function.

Definition at line 182 of file ethercat_hardware.h.

◆ diagnostics_buffer_

unsigned char* EthercatHardwareDiagnosticsPublisher::diagnostics_buffer_
private

Definition at line 183 of file ethercat_hardware.h.

◆ diagnostics_cond_

boost::condition_variable EthercatHardwareDiagnosticsPublisher::diagnostics_cond_
private

Definition at line 176 of file ethercat_hardware.h.

◆ diagnostics_mutex_

boost::mutex EthercatHardwareDiagnosticsPublisher::diagnostics_mutex_
private

mutex protects all class data and cond variable

Definition at line 175 of file ethercat_hardware.h.

◆ diagnostics_ready_

bool EthercatHardwareDiagnosticsPublisher::diagnostics_ready_
private

Definition at line 177 of file ethercat_hardware.h.

◆ diagnostics_thread_

boost::thread EthercatHardwareDiagnosticsPublisher::diagnostics_thread_
private

Definition at line 178 of file ethercat_hardware.h.

◆ dropped_packet_warning_hold_time_

const unsigned EthercatHardwareDiagnosticsPublisher::dropped_packet_warning_hold_time_ = 10
staticprivate

Number of seconds since late dropped packet to keep warning.

Definition at line 199 of file ethercat_hardware.h.

◆ ethernet_interface_info_

EthernetInterfaceInfo EthercatHardwareDiagnosticsPublisher::ethernet_interface_info_
private

Information about Ethernet interface used for EtherCAT communication.

Definition at line 203 of file ethercat_hardware.h.

◆ interface_

string EthercatHardwareDiagnosticsPublisher::interface_
private

Definition at line 187 of file ethercat_hardware.h.

◆ last_dropped_packet_count_

uint64_t EthercatHardwareDiagnosticsPublisher::last_dropped_packet_count_
private

Count of dropped packets last diagnostics cycle.

Definition at line 195 of file ethercat_hardware.h.

◆ last_dropped_packet_time_

ros::Time EthercatHardwareDiagnosticsPublisher::last_dropped_packet_time_
private

Time last packet was dropped 0 otherwise. Used for warning about dropped packets.

Definition at line 197 of file ethercat_hardware.h.

◆ max_pd_retries_

unsigned EthercatHardwareDiagnosticsPublisher::max_pd_retries_
private

Number of times (in a row) to retry sending process data (realtime data) before halting motors.

Definition at line 192 of file ethercat_hardware.h.

◆ node_

ros::NodeHandle EthercatHardwareDiagnosticsPublisher::node_
private

Definition at line 173 of file ethercat_hardware.h.

◆ num_ethercat_devices_

unsigned int EthercatHardwareDiagnosticsPublisher::num_ethercat_devices_
private

Definition at line 186 of file ethercat_hardware.h.

◆ publisher_

ros::Publisher EthercatHardwareDiagnosticsPublisher::publisher_
private

Definition at line 180 of file ethercat_hardware.h.

◆ slaves_

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

Definition at line 185 of file ethercat_hardware.h.

◆ status_

diagnostic_updater::DiagnosticStatusWrapper EthercatHardwareDiagnosticsPublisher::status_
private

Definition at line 205 of file ethercat_hardware.h.

◆ timeout_

unsigned EthercatHardwareDiagnosticsPublisher::timeout_
private

Timeout controls how long EtherCAT driver waits for packet before declaring it as dropped.

Definition at line 190 of file ethercat_hardware.h.

◆ values_

vector<diagnostic_msgs::KeyValue> EthercatHardwareDiagnosticsPublisher::values_
private

Definition at line 204 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