ethercat_hardware.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2008, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the Willow Garage nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
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(
00163                                 diagnostic_updater::DiagnosticStatusWrapper &status,
00164                                 const string &key,
00165                                 const accumulator_set<double, stats<tag::max, tag::mean> > &acc,
00166                                 double max);
00167 
00168   ros::NodeHandle node_;
00169 
00170   boost::mutex diagnostics_mutex_; 
00171   boost::condition_variable diagnostics_cond_;
00172   bool diagnostics_ready_;
00173   boost::thread diagnostics_thread_;
00174 
00175   ros::Publisher publisher_;
00176 
00177   EthercatHardwareDiagnostics diagnostics_; 
00178   unsigned char *diagnostics_buffer_;
00179   unsigned int buffer_size_;
00180   std::vector<boost::shared_ptr<EthercatDevice> > slaves_;
00181   unsigned int num_ethercat_devices_;
00182   string interface_;
00183 
00185   unsigned timeout_;
00187   unsigned max_pd_retries_;
00188 
00190   uint64_t last_dropped_packet_count_;
00192   ros::Time last_dropped_packet_time_;
00194   static const unsigned dropped_packet_warning_hold_time_ = 10; //keep warning up for 10 seconds
00195 
00196   diagnostic_msgs::DiagnosticArray diagnostic_array_;
00198   EthernetInterfaceInfo ethernet_interface_info_;
00199   vector<diagnostic_msgs::KeyValue> values_;
00200   diagnostic_updater::DiagnosticStatusWrapper status_;
00201 };
00202 
00203 class EthercatHardware
00204 {
00205 public:
00209   EthercatHardware(const std::string& name, hardware_interface::HardwareInterface *hw,
00210                    const string &eth, bool allow_unprogrammed);
00211 
00215   ~EthercatHardware();
00216 
00222   void update(bool reset, bool halt);
00223 
00227   void init();
00228 
00232   void collectDiagnostics();
00233 
00234   void printCounters(std::ostream &os = std::cout);
00235 
00239   bool txandrx_PD(unsigned buffer_size, unsigned char* buffer, unsigned tries);
00240 
00250   bool publishTrace(int position, const string &reason, unsigned level, unsigned delay);
00251 
00252   hardware_interface::HardwareInterface *hw_;
00253 
00254 private:
00255   static void changeState(EtherCAT_SlaveHandler *sh, EC_State new_state);
00256 
00257   void loadNonEthercatDevices();
00258   boost::shared_ptr<EthercatDevice> configNonEthercatDevice(const std::string &product_id,
00259                                                             const std::string &data);
00260 
00261   void haltMotors(bool error, const char* reason);
00262 
00263   ros::NodeHandle node_;
00264 
00265   struct netif *ni_;
00266 
00267   string interface_; 
00268 
00269   EtherCAT_AL *al_;
00270   EtherCAT_Master *em_;
00271 
00272   boost::shared_ptr<EthercatDevice> configSlave(EtherCAT_SlaveHandler *sh);
00273   std::vector<boost::shared_ptr<EthercatDevice> > slaves_;
00274   unsigned int num_ethercat_devices_;
00275 
00276   unsigned char *this_buffer_;
00277   unsigned char *prev_buffer_;
00278   unsigned char *buffers_;
00279   unsigned int buffer_size_;
00280 
00281   bool halt_motors_;
00282   unsigned int reset_state_;
00283 
00284   unsigned timeout_; 
00285   unsigned max_pd_retries_; 
00286 
00287   void publishDiagnostics(); 
00288   static void updateAccMax(double &max,
00289                            const accumulator_set<double, stats<tag::max, tag::mean> > &acc);
00290   EthercatHardwareDiagnostics diagnostics_;
00291   EthercatHardwareDiagnosticsPublisher diagnostics_publisher_;
00292   ros::Time last_published_;
00293   ros::Time last_reset_;
00294 
00295   realtime_tools::RealtimePublisher<std_msgs::Bool> motor_publisher_;
00296 
00297   EthercatOobCom *oob_com_;
00298 
00299   pluginlib::ClassLoader<EthercatDevice> device_loader_;
00300 
00301   bool allow_unprogrammed_; 
00302 };
00303 
00304 #endif /* ETHERCAT_HARDWARE_H */


ros_ethercat_hardware
Author(s): Rob Wheeler , Derek King , Manos Nikolaidis
autogenerated on Thu Aug 27 2015 14:47:15