$search
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< EthercatDevice * > &slaves, unsigned int num_ethercat_devices_, unsigned timeout, unsigned max_pd_retries) |
Initializes hardware publish. | |
void | publish (const unsigned char *buffer, const EthercatHardwareDiagnostics &diagnostics) |
Triggers publishing of new diagnostics data. | |
void | stop () |
Stops publishing thread. May block. | |
~EthercatHardwareDiagnosticsPublisher () | |
Private Member Functions | |
void | diagnosticsThreadFunc () |
Publishing thread main loop. | |
void | publishDiagnostics () |
Publishes diagnostics. | |
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. | |
Private Attributes | |
unsigned int | buffer_size_ |
diagnostic_msgs::DiagnosticArray | diagnostic_array_ |
EthercatHardwareDiagnostics | diagnostics_ |
Diagnostics information use by publish function. | |
unsigned char * | diagnostics_buffer_ |
boost::condition_variable | diagnostics_cond_ |
boost::mutex | diagnostics_mutex_ |
mutex protects all class data and cond variable | |
bool | diagnostics_ready_ |
boost::thread | diagnostics_thread_ |
EthernetInterfaceInfo | ethernet_interface_info_ |
Information about Ethernet interface used for EtherCAT communication. | |
string | interface_ |
uint64_t | last_dropped_packet_count_ |
Count of dropped packets last diagnostics cycle. | |
ros::Time | last_dropped_packet_time_ |
Time last packet was dropped 0 otherwise. Used for warning about dropped packets. | |
unsigned | max_pd_retries_ |
Number of times (in a row) to retry sending process data (realtime data) before halting motors. | |
ros::NodeHandle | node_ |
unsigned int | num_ethercat_devices_ |
ros::Publisher | publisher_ |
std::vector< EthercatDevice * > | slaves_ |
diagnostic_updater::DiagnosticStatusWrapper | status_ |
unsigned | timeout_ |
Timeout controls how long EtherCAT driver waits for packet before declaring it as dropped. | |
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. |
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 107 of file ethercat_hardware.h.
EthercatHardwareDiagnosticsPublisher::EthercatHardwareDiagnosticsPublisher | ( | ros::NodeHandle & | node | ) |
Definition at line 340 of file ethercat_hardware.cpp.
EthercatHardwareDiagnosticsPublisher::~EthercatHardwareDiagnosticsPublisher | ( | ) |
Definition at line 350 of file ethercat_hardware.cpp.
void EthercatHardwareDiagnosticsPublisher::diagnosticsThreadFunc | ( | ) | [private] |
Publishing thread main loop.
Waits for condition variable to start publishing internal data.
Definition at line 402 of file ethercat_hardware.cpp.
void EthercatHardwareDiagnosticsPublisher::initialize | ( | const string & | interface, | |
unsigned int | buffer_size, | |||
const std::vector< EthercatDevice * > & | slaves, | |||
unsigned int | num_ethercat_devices_, | |||
unsigned | timeout, | |||
unsigned | max_pd_retries | |||
) |
Initializes hardware publish.
buffer_size | size of proccess data buffer | |
number | of EtherCAT slave devices |
Definition at line 355 of file ethercat_hardware.cpp.
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 378 of file ethercat_hardware.cpp.
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 429 of file ethercat_hardware.cpp.
void EthercatHardwareDiagnosticsPublisher::stop | ( | ) |
Stops publishing thread. May block.
Definition at line 395 of file ethercat_hardware.cpp.
void EthercatHardwareDiagnosticsPublisher::timingInformation | ( | diagnostic_updater::DiagnosticStatusWrapper & | status, | |
const string & | key, | |||
const accumulator_set< double, stats< tag::max, tag::mean > > & | acc, | |||
double | max | |||
) | [static, private] |
Helper function for converting timing for diagnostics.
Definition at line 418 of file ethercat_hardware.cpp.
unsigned int EthercatHardwareDiagnosticsPublisher::buffer_size_ [private] |
Definition at line 177 of file ethercat_hardware.h.
Definition at line 194 of file ethercat_hardware.h.
Diagnostics information use by publish function.
Definition at line 175 of file ethercat_hardware.h.
unsigned char* EthercatHardwareDiagnosticsPublisher::diagnostics_buffer_ [private] |
Definition at line 176 of file ethercat_hardware.h.
boost::condition_variable EthercatHardwareDiagnosticsPublisher::diagnostics_cond_ [private] |
Definition at line 169 of file ethercat_hardware.h.
boost::mutex EthercatHardwareDiagnosticsPublisher::diagnostics_mutex_ [private] |
mutex protects all class data and cond variable
Definition at line 168 of file ethercat_hardware.h.
bool EthercatHardwareDiagnosticsPublisher::diagnostics_ready_ [private] |
Definition at line 170 of file ethercat_hardware.h.
boost::thread EthercatHardwareDiagnosticsPublisher::diagnostics_thread_ [private] |
Definition at line 171 of file ethercat_hardware.h.
const unsigned EthercatHardwareDiagnosticsPublisher::dropped_packet_warning_hold_time_ = 10 [static, private] |
Number of seconds since late dropped packet to keep warning.
Definition at line 192 of file ethercat_hardware.h.
Information about Ethernet interface used for EtherCAT communication.
Definition at line 196 of file ethercat_hardware.h.
string EthercatHardwareDiagnosticsPublisher::interface_ [private] |
Definition at line 180 of file ethercat_hardware.h.
uint64_t EthercatHardwareDiagnosticsPublisher::last_dropped_packet_count_ [private] |
Count of dropped packets last diagnostics cycle.
Definition at line 188 of file ethercat_hardware.h.
Time last packet was dropped 0 otherwise. Used for warning about dropped packets.
Definition at line 190 of file ethercat_hardware.h.
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 185 of file ethercat_hardware.h.
Definition at line 166 of file ethercat_hardware.h.
unsigned int EthercatHardwareDiagnosticsPublisher::num_ethercat_devices_ [private] |
Definition at line 179 of file ethercat_hardware.h.
Definition at line 173 of file ethercat_hardware.h.
std::vector<EthercatDevice*> EthercatHardwareDiagnosticsPublisher::slaves_ [private] |
Definition at line 178 of file ethercat_hardware.h.
Definition at line 198 of file ethercat_hardware.h.
unsigned EthercatHardwareDiagnosticsPublisher::timeout_ [private] |
Timeout controls how long EtherCAT driver waits for packet before declaring it as dropped.
Definition at line 183 of file ethercat_hardware.h.
vector<diagnostic_msgs::KeyValue> EthercatHardwareDiagnosticsPublisher::values_ [private] |
Definition at line 197 of file ethercat_hardware.h.