Go to the documentation of this file.
   35 #ifndef ETHERCAT_HARDWARE_H 
   36 #define ETHERCAT_HARDWARE_H 
   44 #include <al/ethercat_AL.h> 
   45 #include <al/ethercat_master.h> 
   46 #include <al/ethercat_slave_handler.h> 
   54 #include <boost/accumulators/accumulators.hpp> 
   55 #include <boost/accumulators/statistics/stats.hpp> 
   56 #include <boost/accumulators/statistics/max.hpp> 
   57 #include <boost/accumulators/statistics/mean.hpp> 
   59 #include <boost/shared_ptr.hpp> 
   61 #include <boost/thread/thread.hpp> 
   62 #include <boost/thread/mutex.hpp> 
   63 #include <boost/thread/condition_variable.hpp> 
   67 #include <std_msgs/Bool.h> 
   69 #include <boost/regex.hpp> 
   71 using namespace boost::accumulators;
 
   76   void resetMaxTiming();
 
   92   struct netif_counters counters_;
 
   97   static const bool collect_extra_timing_ = 
true;
 
  126   void initialize(
const string &interface, 
unsigned int buffer_size, 
 
  128                   unsigned int num_ethercat_devices_,
 
  129                   unsigned timeout, 
unsigned max_pd_retries);
 
  154   void publishDiagnostics();
 
  161   void diagnosticsThreadFunc();
 
  167   static void timingInformation(
 
  170         const accumulator_set<
double, stats<tag::max, tag::mean> > &acc,
 
  185   std::vector<boost::shared_ptr<EthercatDevice> > 
slaves_;
 
  199   static const unsigned dropped_packet_warning_hold_time_ = 10;  
 
  227   void update(
bool reset, 
bool halt);
 
  234   void init(
char *interface, 
bool allow_unprogrammed);
 
  239   void collectDiagnostics();
 
  241   void printCounters(std::ostream &os=std::cout); 
 
  246   bool txandrx_PD(
unsigned buffer_size, 
unsigned char* buffer, 
unsigned tries);
 
  257   bool publishTrace(
int position, 
const string &reason, 
unsigned level, 
unsigned delay);
 
  262   static void changeState(EtherCAT_SlaveHandler *sh, EC_State new_state);
 
  264   void loadNonEthercatDevices();
 
  267   void haltMotors(
bool error, 
const char* reason);
 
  278   std::vector<boost::shared_ptr<EthercatDevice> > 
slaves_;
 
  292   void publishDiagnostics();  
 
  293   static void updateAccMax(
double &max, 
const accumulator_set<
double, stats<tag::max, tag::mean> > &acc);
 
  
realtime_tools::RealtimePublisher< std_msgs::Bool > motor_publisher_
 
unsigned int reset_state_
 
uint64_t last_dropped_packet_count_
Count of dropped packets last diagnostics cycle.
 
boost::thread diagnostics_thread_
 
unsigned int num_ethercat_devices_
 
diagnostic_msgs::DiagnosticArray diagnostic_array_
 
EthercatOobCom * oob_com_
 
ros::Time last_dropped_packet_time_
Time last packet was dropped 0 otherwise. Used for warning about dropped packets.
 
void init(char *interface)
 
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.
 
EthercatHardwareDiagnostics diagnostics_
 
unsigned char * diagnostics_buffer_
 
boost::condition_variable diagnostics_cond_
 
unsigned char * this_buffer_
 
unsigned int buffer_size_
 
EthercatHardwareDiagnosticsPublisher diagnostics_publisher_
 
boost::mutex diagnostics_mutex_
mutex protects all class data and cond variable
 
EthercatHardwareDiagnostics diagnostics_
Diagnostics information use by publish function.
 
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)
 
ros::Time last_published_
 
pr2_hardware_interface::HardwareInterface * hw_
 
bool motors_halted_
True if motors are halted
 
vector< diagnostic_msgs::KeyValue > values_
 
unsigned max_pd_retries_
Max number of times to retry sending process data before halting motors.
 
unsigned int num_ethercat_devices_
 
ros::Publisher publisher_
 
const char * motors_halted_reason_
reason that motors first halted
 
bool input_thread_is_stopped_
 
unsigned reset_motors_service_count_
Number of times reset_motor service has been used.
 
unsigned timeout_
Timeout controls how long EtherCAT driver waits for packet before declaring it as dropped.
 
std::vector< boost::shared_ptr< EthercatDevice > > slaves_
 
unsigned char * prev_buffer_
 
std::vector< boost::shared_ptr< EthercatDevice > > slaves_
 
accumulator_set< double, stats< tag::max, tag::mean > > publish_acc_
time taken by any publishing step in main loop
 
accumulator_set< double, stats< tag::max, tag::mean > > unpack_state_acc_
time taken by all devices updateState functions
 
diagnostic_updater::DiagnosticStatusWrapper status_
 
ROSCONSOLE_DECL void initialize()
 
unsigned timeout_
Timeout (in microseconds) to used for sending/recieving packets once in realtime mode.
 
Publishes EthercatHardware diagnostics.
 
unsigned int buffer_size_
 
EthernetInterfaceInfo ethernet_interface_info_
Information about Ethernet interface used for EtherCAT communication.
 
pluginlib::ClassLoader< EthercatDevice > device_loader_
 
bool halt_after_reset_
True if motor halt soon after motor reset.
 
unsigned max_pd_retries_
Number of times (in a row) to retry sending process data (realtime data) before halting motors.
 
unsigned halt_motors_error_count_
Number of transitions into halt state due to device error.
 
ethercat_hardware
Author(s): Rob Wheeler 
, Derek King 
autogenerated on Thu Sep 26 2024 02:44:04