35 #ifndef ETHERCAT_HARDWARE_H    36 #define ETHERCAT_HARDWARE_H    40 #include <al/ethercat_AL.h>    41 #include <al/ethercat_master.h>    42 #include <al/ethercat_slave_handler.h>    50 #include <boost/accumulators/accumulators.hpp>    51 #include <boost/accumulators/statistics/stats.hpp>    52 #include <boost/accumulators/statistics/max.hpp>    53 #include <boost/accumulators/statistics/mean.hpp>    55 #include <boost/thread/thread.hpp>    56 #include <boost/thread/mutex.hpp>    57 #include <boost/thread/condition_variable.hpp>    61 #include <std_msgs/Bool.h>    63 #include <boost/regex.hpp>    70   void resetMaxTiming();
    86   struct netif_counters counters_;
    91   static const bool collect_extra_timing_ = 
true;
   120   void initialize(
const string &interface, 
unsigned int buffer_size, 
   122                   unsigned int num_ethercat_devices_,
   123                   unsigned timeout, 
unsigned max_pd_retries);
   148   void publishDiagnostics();
   155   void diagnosticsThreadFunc();
   161   static void timingInformation(
   164         const accumulator_set<
double, stats<tag::max, tag::mean> > &acc,
   179   std::vector<boost::shared_ptr<EthercatDevice> > 
slaves_;
   193   static const unsigned dropped_packet_warning_hold_time_ = 10;  
   221   void update(
bool reset, 
bool halt);
   228   void init(
char *interface, 
bool allow_unprogrammed);
   233   void collectDiagnostics();
   235   void printCounters(std::ostream &os=std::cout); 
   240   bool txandrx_PD(
unsigned buffer_size, 
unsigned char* buffer, 
unsigned tries);
   251   bool publishTrace(
int position, 
const string &reason, 
unsigned level, 
unsigned delay);
   256   static void changeState(EtherCAT_SlaveHandler *sh, EC_State new_state);
   258   void loadNonEthercatDevices();
   261   void haltMotors(
bool error, 
const char* reason);
   272   std::vector<boost::shared_ptr<EthercatDevice> > 
slaves_;
   286   void publishDiagnostics();  
   287   static void updateAccMax(
double &max, 
const accumulator_set<
double, stats<tag::max, tag::mean> > &acc);
 vector< diagnostic_msgs::KeyValue > values_
 
unsigned reset_motors_service_count_
Number of times reset_motor service has been used. 
 
EthercatHardwareDiagnostics diagnostics_
Diagnostics information use by publish function. 
 
ROSCONSOLE_DECL void initialize()
 
pr2_hardware_interface::HardwareInterface * hw_
 
Publishes EthercatHardware diagnostics. 
 
ros::Publisher publisher_
 
std::vector< boost::shared_ptr< EthercatDevice > > slaves_
 
accumulator_set< double, stats< tag::max, tag::mean > > pack_command_acc_
time taken by all devices packCommand functions 
 
unsigned halt_motors_service_count_
Number of time halt_motor service call is used. 
 
unsigned halt_motors_error_count_
Number of transitions into halt state due to device error. 
 
pluginlib::ClassLoader< EthercatDevice > device_loader_
 
bool motors_halted_
True if motors are halted. 
 
unsigned char * prev_buffer_
 
EthernetInterfaceInfo ethernet_interface_info_
Information about Ethernet interface used for EtherCAT communication. 
 
unsigned char * diagnostics_buffer_
 
unsigned int num_ethercat_devices_
 
accumulator_set< double, stats< tag::max, tag::mean > > txandrx_acc_
time taken by to transmit and recieve process data 
 
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
 
const char * motors_halted_reason_
reason that motors first halted 
 
unsigned timeout_
Timeout (in microseconds) to used for sending/recieving packets once in realtime mode. 
 
unsigned int buffer_size_
 
std::vector< boost::shared_ptr< EthercatDevice > > slaves_
 
boost::thread diagnostics_thread_
 
bool input_thread_is_stopped_
 
uint64_t last_dropped_packet_count_
Count of dropped packets last diagnostics cycle. 
 
EthercatHardwareDiagnostics diagnostics_
 
unsigned int reset_state_
 
diagnostic_updater::DiagnosticStatusWrapper status_
 
unsigned int num_ethercat_devices_
 
realtime_tools::RealtimePublisher< std_msgs::Bool > motor_publisher_
 
boost::condition_variable diagnostics_cond_
 
EthercatOobCom * oob_com_
 
unsigned char * this_buffer_
 
diagnostic_msgs::DiagnosticArray diagnostic_array_
 
EthercatHardwareDiagnosticsPublisher diagnostics_publisher_
 
unsigned int buffer_size_
 
unsigned timeout_
Timeout controls how long EtherCAT driver waits for packet before declaring it as dropped...
 
unsigned max_pd_retries_
Number of times (in a row) to retry sending process data (realtime data) before halting motors...
 
boost::mutex diagnostics_mutex_
mutex protects all class data and cond variable 
 
accumulator_set< double, stats< tag::max, tag::mean > > unpack_state_acc_
time taken by all devices updateState functions 
 
unsigned max_pd_retries_
Max number of times to retry sending process data before halting motors. 
 
bool halt_after_reset_
True if motor halt soon after motor reset. 
 
ros::Time last_dropped_packet_time_
Time last packet was dropped 0 otherwise. Used for warning about dropped packets. ...
 
void init(char *interface)
 
ros::Time last_published_
 
accumulator_set< double, stats< tag::max, tag::mean > > publish_acc_
time taken by any publishing step in main loop