Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #ifndef ETHERCAT_HARDWARE_H
00036 #define ETHERCAT_HARDWARE_H
00037
00038 #include <hardware_interface/hardware_interface.h>
00039
00040 #include <ros_ethercat_eml/ethercat_AL.h>
00041 #include <ros_ethercat_eml/ethercat_master.h>
00042 #include <ros_ethercat_eml/ethercat_slave_handler.h>
00043 #include <ros_ethercat_eml/ethercat_dll.h>
00044 #include <ros_ethercat_eml/ethercat_device_addressed_telegram.h>
00045
00046 #include "ros_ethercat_hardware/ethercat_device.h"
00047 #include "ros_ethercat_hardware/ethercat_com.h"
00048 #include "ros_ethercat_hardware/ethernet_interface_info.h"
00049
00050 #include <realtime_tools/realtime_publisher.h>
00051
00052 #include <boost/accumulators/accumulators.hpp>
00053 #include <boost/accumulators/statistics/stats.hpp>
00054 #include <boost/accumulators/statistics/max.hpp>
00055 #include <boost/accumulators/statistics/mean.hpp>
00056
00057 #include <boost/thread/thread.hpp>
00058 #include <boost/thread/mutex.hpp>
00059 #include <boost/thread/condition_variable.hpp>
00060
00061 #include <pluginlib/class_loader.h>
00062
00063 #include <std_msgs/Bool.h>
00064
00065 #include <boost/regex.hpp>
00066
00067 using namespace boost::accumulators;
00068
00069 struct EthercatHardwareDiagnostics
00070 {
00071 EthercatHardwareDiagnostics();
00072 void resetMaxTiming();
00073 accumulator_set<double, stats<tag::max, tag::mean> > pack_command_acc_;
00074 accumulator_set<double, stats<tag::max, tag::mean> > txandrx_acc_;
00075 accumulator_set<double, stats<tag::max, tag::mean> > unpack_state_acc_;
00076 accumulator_set<double, stats<tag::max, tag::mean> > publish_acc_;
00077 double max_pack_command_;
00078 double max_txandrx_;
00079 double max_unpack_state_;
00080 double max_publish_;
00081 int txandrx_errors_;
00082 unsigned device_count_;
00083 bool pd_error_;
00084 bool halt_after_reset_;
00085 unsigned reset_motors_service_count_;
00086 unsigned halt_motors_service_count_;
00087 unsigned halt_motors_error_count_;
00088 struct netif_counters counters_;
00089 bool input_thread_is_stopped_;
00090 bool motors_halted_;
00091 const char* motors_halted_reason_;
00092
00093 static const bool collect_extra_timing_ = true;
00094 };
00095
00109 class EthercatHardwareDiagnosticsPublisher
00110 {
00111 public:
00112
00113 EthercatHardwareDiagnosticsPublisher(ros::NodeHandle &node);
00114 ~EthercatHardwareDiagnosticsPublisher();
00115
00121 void initialize(const string &interface, unsigned int buffer_size,
00122 const std::vector<boost::shared_ptr<EthercatDevice> > &slaves,
00123 unsigned int num_ethercat_devices_,
00124 unsigned timeout,
00125 unsigned max_pd_retries);
00126
00134 void publish(const unsigned char *buffer, const EthercatHardwareDiagnostics &diagnostics);
00135
00139 void stop();
00140
00141 private:
00142
00150 void publishDiagnostics();
00151
00157 void diagnosticsThreadFunc();
00158
00162 static void timingInformation(diagnostic_updater::DiagnosticStatusWrapper &status,
00163 const string &key,
00164 const accumulator_set<double, stats<tag::max, tag::mean> > &acc,
00165 double max);
00166
00167 ros::NodeHandle node_;
00168
00169 boost::mutex diagnostics_mutex_;
00170 boost::condition_variable diagnostics_cond_;
00171 bool diagnostics_ready_;
00172 boost::thread diagnostics_thread_;
00173
00174 ros::Publisher publisher_;
00175
00176 EthercatHardwareDiagnostics diagnostics_;
00177 unsigned char *diagnostics_buffer_;
00178 unsigned int buffer_size_;
00179 std::vector<boost::shared_ptr<EthercatDevice> > slaves_;
00180 unsigned int num_ethercat_devices_;
00181 string interface_;
00182
00184 unsigned timeout_;
00186 unsigned max_pd_retries_;
00187
00189 uint64_t last_dropped_packet_count_;
00191 ros::Time last_dropped_packet_time_;
00193 static const unsigned dropped_packet_warning_hold_time_ = 10;
00194
00195 diagnostic_msgs::DiagnosticArray diagnostic_array_;
00197 EthernetInterfaceInfo ethernet_interface_info_;
00198 vector<diagnostic_msgs::KeyValue> values_;
00199 diagnostic_updater::DiagnosticStatusWrapper status_;
00200 };
00201
00202 class EthercatHardware
00203 {
00204 public:
00209 static std::vector<EtherCAT_SlaveHandler> scanPort(const std::string& eth);
00210
00211
00215 EthercatHardware(const std::string& name, hardware_interface::HardwareInterface *hw,
00216 const string ð, bool allow_unprogrammed);
00217
00221 ~EthercatHardware();
00222
00228 void update(bool reset, bool halt);
00229
00233 void init();
00234
00238 void collectDiagnostics();
00239
00240 void printCounters(std::ostream &os = std::cout);
00241
00245 bool txandrx_PD(unsigned buffer_size, unsigned char* buffer, unsigned tries);
00246
00256 bool publishTrace(int position, const string &reason, unsigned level, unsigned delay);
00257
00258 hardware_interface::HardwareInterface *hw_;
00259
00260 const std::vector<boost::shared_ptr<const EthercatDevice> > getSlaves() const
00261 {
00262 return std::vector<boost::shared_ptr<const EthercatDevice> >(slaves_.begin(), slaves_.end());
00263 }
00264
00265 private:
00266 static void changeState(EtherCAT_SlaveHandler *sh, EC_State new_state);
00267
00268 void loadNonEthercatDevices();
00269 boost::shared_ptr<EthercatDevice> configNonEthercatDevice(const std::string &product_id,
00270 const std::string &data);
00271
00272 void haltMotors(bool error, const char* reason);
00273
00274 void publishDiagnostics();
00275 static void updateAccMax(double &max, const accumulator_set<double, stats<tag::max, tag::mean> > &acc);
00276 boost::shared_ptr<EthercatDevice> configSlave(EtherCAT_SlaveHandler *sh);
00277 bool setRouterToSlaveHandlers();
00278
00279 ros::NodeHandle node_;
00280
00281 struct netif *ni_;
00282
00283 string interface_;
00284
00285 EtherCAT_DataLinkLayer m_dll_instance_;
00286 EC_Logic m_logic_instance_;
00287 EtherCAT_PD_Buffer pd_buffer_;
00288 EtherCAT_AL *application_layer_;
00289 EtherCAT_Router *m_router_;
00290 EtherCAT_Master *ethercat_master_;
00291
00292 std::vector<boost::shared_ptr<EthercatDevice> > slaves_;
00293 unsigned int num_ethercat_devices_;
00294
00295 unsigned char *this_buffer_;
00296 unsigned char *prev_buffer_;
00297 unsigned char *buffers_;
00298 unsigned int buffer_size_;
00299
00300 bool halt_motors_;
00301 unsigned int reset_state_;
00302
00303 unsigned timeout_;
00304 unsigned max_pd_retries_;
00305
00306 EthercatHardwareDiagnostics diagnostics_;
00307 EthercatHardwareDiagnosticsPublisher diagnostics_publisher_;
00308 ros::Time last_published_;
00309 ros::Time last_reset_;
00310
00311 realtime_tools::RealtimePublisher<std_msgs::Bool> motor_publisher_;
00312
00313 EthercatOobCom *oob_com_;
00314
00315 pluginlib::ClassLoader<EthercatDevice> device_loader_;
00316
00317 bool allow_unprogrammed_;
00318
00319 int start_address_;
00320 };
00321
00322 #endif