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> 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);
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