ethercat_device.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_DEVICE_H
00036 #define ETHERCAT_DEVICE_H
00037 
00038 #include <vector>
00039 
00040 #include <ros_ethercat_eml/ethercat_defs.h>
00041 #include <ros_ethercat_eml/ethercat_slave_handler.h>
00042 #include <ros_ethercat_eml/ethercat_device_addressed_telegram.h>
00043 #include <ros_ethercat_eml/ethercat_logical_addressed_telegram.h>
00044 #include <ros_ethercat_eml/ethercat_frame.h>
00045 
00046 #include <hardware_interface/hardware_interface.h>
00047 
00048 #include <diagnostic_updater/DiagnosticStatusWrapper.h>
00049 
00050 #include <diagnostic_msgs/DiagnosticArray.h>
00051 
00052 #include <ros_ethercat_hardware/ethercat_com.h>
00053 
00054 #include <pluginlib/class_list_macros.h>
00055 
00056 using namespace std;
00057 
00058 struct et1x00_error_counters
00059 {
00060 
00061   struct
00062   {
00063     uint8_t invalid_frame;
00064     uint8_t rx_error;
00065   } __attribute__((__packed__)) port[4];
00066   uint8_t forwarded_rx_error[4];
00067   uint8_t epu_error;
00068   uint8_t pdi_error;
00069   uint8_t res[2];
00070   uint8_t lost_link[4];
00071   static const uint16_t BASE_ADDR = 0x300;
00072   bool isGreaterThan(unsigned value) const;
00073   bool isGreaterThan(const et1x00_error_counters &value) const;
00074   void zero();
00075 } __attribute__((__packed__));
00076 
00077 struct et1x00_dl_status
00078 {
00079   uint16_t status;
00080   bool hasLink(unsigned port);
00081   bool isClosed(unsigned port);
00082   bool hasCommunication(unsigned port);
00083   static const uint16_t BASE_ADDR = 0x110;
00084 } __attribute__((__packed__));
00085 
00086 struct EthercatPortDiagnostics
00087 {
00088   EthercatPortDiagnostics();
00089   void zeroTotals();
00090   bool hasLink;
00091   bool isClosed;
00092   bool hasCommunication;
00093   uint64_t rxErrorTotal;
00094   uint64_t invalidFrameTotal;
00095   uint64_t forwardedRxErrorTotal;
00096   uint64_t lostLinkTotal;
00097 };
00098 
00099 struct EthercatDeviceDiagnostics
00100 {
00101 public:
00102   EthercatDeviceDiagnostics();
00103 
00104   // Collects diagnostic data from specific ethercat slave, and updates object state
00105   //
00106   // com  EtherCAT communication object is used send/recv packets to/from ethercat chain.
00107   // sh   slaveHandler of device to collect Diagnostics from
00108   // prev previously collected diagnostics (can be pointer to this object)
00109   //
00110   // collectDiagnotics will send/recieve multiple packets, and may considerable amount of time complete.
00111   //
00112   void collect(EthercatCom *com, EtherCAT_SlaveHandler *sh);
00113 
00114   // Puts reviously diagnostic collected diagnostic state to DiagnosticStatus object
00115   //
00116   // d         DiagnositcState to add diagnostics to.
00117   // numPorts  Number of ports device is supposed to have.  4 is max, 1 is min.
00118   void publish(diagnostic_updater::DiagnosticStatusWrapper &d, unsigned numPorts = 4) const;
00119 
00120 protected:
00121   void zeroTotals();
00122   void accumulate(const et1x00_error_counters &next, const et1x00_error_counters &prev);
00123   uint64_t pdiErrorTotal_;
00124   uint64_t epuErrorTotal_;
00125   EthercatPortDiagnostics portDiagnostics_[4];
00126   unsigned nodeAddress_;
00127   et1x00_error_counters errorCountersPrev_;
00128   bool errorCountersMayBeCleared_;
00129 
00130   bool diagnosticsFirst_;
00131   bool diagnosticsValid_;
00132   bool resetDetected_;
00133   int devicesRespondingToNodeAddress_;
00134 };
00135 
00136 class EthercatDevice
00137 {
00138 public:
00140   virtual void construct(EtherCAT_SlaveHandler *sh, int &start_address);
00141 
00143   virtual void construct(ros::NodeHandle &nh)
00144   {
00145   }
00146 
00147   EthercatDevice();
00148   virtual ~EthercatDevice()
00149   {
00150     delete sh_->get_fmmu_config();
00151     delete sh_->get_pd_config();
00152   }
00153   virtual int initialize(hardware_interface::HardwareInterface *hw, bool allow_unprogrammed = true)
00154   {
00155     return 0;
00156   }
00161   virtual void packCommand(unsigned char *buffer, bool halt, bool reset)
00162   {
00163   }
00164   virtual bool unpackState(unsigned char *this_buffer, unsigned char *prev_buffer)
00165   {
00166     return true;
00167   }
00168 
00175   virtual void multiDiagnostics(vector<diagnostic_msgs::DiagnosticStatus> &vec,
00176                                 unsigned char *buffer);
00177 
00184   virtual void diagnostics(diagnostic_updater::DiagnosticStatusWrapper &d, unsigned char *buffer);
00185 
00191   void ethercatDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &d, unsigned numPorts);
00192 
00193   virtual void collectDiagnostics(EthercatCom *com);
00201   virtual bool publishTrace(const string &reason, unsigned level, unsigned delay)
00202   {
00203     return false;
00204   }
00205 
00206   enum AddrMode
00207   {
00208     FIXED_ADDR = 0, POSITIONAL_ADDR = 1
00209   };
00210 
00214   static int writeData(EthercatCom *com, EtherCAT_SlaveHandler *sh, uint16_t address,
00215                        void const* buffer, uint16_t length, AddrMode addrMode = FIXED_ADDR);
00216   inline int writeData(EthercatCom *com, uint16_t address, void const* buffer, uint16_t length,
00217                        AddrMode addrMode)
00218   {
00219     return writeData(com, sh_, address, buffer, length, addrMode);
00220   }
00221 
00225   static int readData(EthercatCom *com, EtherCAT_SlaveHandler *sh, uint16_t address, void *buffer,
00226                       uint16_t length, AddrMode addrMode = FIXED_ADDR);
00227   inline int readData(EthercatCom *com, uint16_t address, void *buffer, uint16_t length,
00228                       AddrMode addrMode)
00229   {
00230     return readData(com, sh_, address, buffer, length, addrMode);
00231   }
00232 
00236   static int readWriteData(EthercatCom *com, EtherCAT_SlaveHandler *sh, uint16_t address,
00237                            void *buffer, uint16_t length, AddrMode addrMode = FIXED_ADDR);
00238   inline int readWriteData(EthercatCom *com, uint16_t address, void *buffer, uint16_t length,
00239                            AddrMode addrMode)
00240   {
00241     return readWriteData(com, sh_, address, buffer, length, addrMode);
00242   }
00243 
00244   bool use_ros_;
00245 
00246   EtherCAT_SlaveHandler *sh_;
00247   unsigned int command_size_;
00248   unsigned int status_size_;
00249 
00250   // The device diagnostics are collected with a non-readtime thread that calls collectDiagnostics()
00251   // The device published from the realtime loop by indirectly invoking ethercatDiagnostics()
00252   // To avoid blocking of the realtime thread (for long) a double buffer is used the
00253   // The publisher thread will lock newDiagnosticsIndex when publishing data.
00254   // The collection thread will lock deviceDiagnostics when updating deviceDiagnostics
00255   // The collection thread will also lock newDiagnosticsIndex at end of update, just before swapping buffers.
00256   unsigned newDiagnosticsIndex_;
00257   pthread_mutex_t newDiagnosticsIndexLock_;
00258   EthercatDeviceDiagnostics deviceDiagnostics[2];
00259   pthread_mutex_t diagnosticsLock_;
00260 
00261   // Keep diagnostics status as cache.  Avoids a lot of construction/destruction of status object.
00262   diagnostic_updater::DiagnosticStatusWrapper diagnostic_status_;
00263 };
00264 
00265 #endif /* ETHERCAT_DEVICE_H */


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