ethercat_hardware.cpp
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 #include "ros_ethercat_hardware/ethercat_hardware.h"
00036 
00037 #include <ros_ethercat_eml/ethercat_xenomai_drv.h>
00038 
00039 #include <sstream>
00040 
00041 #include <net/if.h>
00042 #include <sys/ioctl.h>
00043 #include <boost/foreach.hpp>
00044 #include <boost/regex.hpp>
00045 
00046 EthercatHardwareDiagnostics::EthercatHardwareDiagnostics() :
00047   txandrx_errors_(0),
00048   device_count_(0),
00049   pd_error_(false),
00050   halt_after_reset_(false),
00051   reset_motors_service_count_(0),
00052   halt_motors_service_count_(0),
00053   halt_motors_error_count_(0),
00054   motors_halted_(false),
00055   motors_halted_reason_("")
00056 {
00057   resetMaxTiming();
00058 }
00059 
00060 void EthercatHardwareDiagnostics::resetMaxTiming()
00061 {
00062   max_pack_command_ = 0.0;
00063   max_txandrx_ = 0.0;
00064   max_unpack_state_ = 0.0;
00065   max_publish_ = 0.0;
00066 }
00067 
00068 EthercatHardware::EthercatHardware(const std::string& name,
00069                                    hardware_interface::HardwareInterface *hw,
00070                                    const std::string& eth,
00071                                    bool allow_unprogrammed) :
00072   hw_(hw),
00073   node_(ros::NodeHandle(name)),
00074   ni_(NULL),
00075   interface_(eth),
00076   pd_buffer_(&m_logic_instance_, &m_dll_instance_),
00077   this_buffer_(NULL),
00078   prev_buffer_(NULL),
00079   buffer_size_(0),
00080   halt_motors_(true),
00081   reset_state_(0),
00082   max_pd_retries_(10),
00083   diagnostics_publisher_(node_),
00084   motor_publisher_(node_, "motors_halted", 1, true),
00085   device_loader_("ros_ethercat_hardware", "EthercatDevice"),
00086   allow_unprogrammed_(allow_unprogrammed),
00087   start_address_(0x00010000)
00088 {
00089   node_.setParam("EtherCAT_Initialized", false);
00090   if (!interface_.empty())
00091     init();
00092   else
00093     ROS_DEBUG("No ethercat interface given. EthercatHardware will not be initialized");
00094 }
00095 
00096 EthercatHardware::~EthercatHardware()
00097 {
00098   diagnostics_publisher_.stop();
00099   for (uint32_t i = 0; i < slaves_.size(); ++i)
00100   {
00101     EC_FixedStationAddress fsa(i + 1);
00102     EtherCAT_SlaveHandler *sh = ethercat_master_->get_slave_handler(fsa);
00103     if (sh)
00104       sh->to_state(EC_PREOP_STATE);
00105   }
00106   if (ni_)
00107   {
00108     close_socket(ni_);
00109   }
00110   delete[] buffers_;
00111   motor_publisher_.stop();
00112   delete oob_com_;
00113   delete ethercat_master_;
00114   delete m_router_;
00115   delete application_layer_;
00116 }
00117 
00118 bool EthercatHardware::setRouterToSlaveHandlers()
00119 {
00120   unsigned int n_slaves = application_layer_->get_num_slaves();
00121   EtherCAT_SlaveHandler **slaves = application_layer_->get_slaves();
00122   for (unsigned int i = 0; i < n_slaves; ++i)
00123     slaves[i]->setRouter(m_router_);
00124   return true;
00125 }
00126 
00127 void EthercatHardware::changeState(EtherCAT_SlaveHandler *sh, EC_State new_state)
00128 {
00129   unsigned product_code = sh->get_product_code();
00130   unsigned serial = sh->get_serial();
00131   uint32_t revision = sh->get_revision();
00132   unsigned slave = sh->get_station_address() - 1;
00133 
00134   if (!sh->to_state(new_state))
00135   {
00136     ROS_FATAL("Cannot goto state %d for slave #%d, product code: %u (0x%X), serial: %u (0x%X), revision: %d (0x%X)",
00137               new_state,
00138               slave, product_code, product_code, serial, serial, revision, revision);
00139     if ((product_code == 0xbaddbadd) || (serial == 0xbaddbadd) || (revision == 0xbaddbadd))
00140       ROS_FATAL("Note: 0xBADDBADD indicates that the value was not read correctly from device.");
00141     exit(EXIT_FAILURE);
00142   }
00143 }
00144 
00145 std::vector<EtherCAT_SlaveHandler> EthercatHardware::scanPort(const std::string& eth)
00146 {
00147   std::vector<EtherCAT_SlaveHandler> detected_devices;
00148   int sock = socket(PF_INET, SOCK_DGRAM, 0);
00149   if (sock < 0)
00150   {
00151     int error = errno;
00152     ROS_FATAL("Couldn't open temp socket : %s", strerror(error));
00153     return detected_devices;
00154   }
00155 
00156   struct ifreq ifr;
00157   strncpy(ifr.ifr_name, eth.c_str(), IFNAMSIZ);
00158   if (ioctl(sock, SIOCGIFFLAGS, &ifr) < 0)
00159   {
00160     int error = errno;
00161     ROS_FATAL("Cannot get interface_.c_str() flags for %s: %s", eth.c_str(),
00162               strerror(error));
00163     return detected_devices;
00164   }
00165 
00166   close(sock);
00167   sock = -1;
00168 
00169   if (!(ifr.ifr_flags & IFF_UP))
00170   {
00171     ROS_FATAL("Interface %s is not UP. Try : ifup %s", eth.c_str(), eth.c_str());
00172     return detected_devices;
00173   }
00174   if (!(ifr.ifr_flags & IFF_RUNNING))
00175   {
00176     ROS_FATAL("Interface %s is not RUNNING. Is cable plugged in and device powered?",
00177               eth.c_str());
00178     return detected_devices;
00179   }
00180 
00181   // Initialize network interface
00182   struct netif *ni(NULL);
00183   if ((ni = init_ec(eth.c_str())) == NULL)
00184   {
00185     ROS_FATAL_STREAM("Unable to initialize interface_: " << eth);
00186     return detected_devices;
00187   }
00188   EC_Logic logic_instance;
00189   EtherCAT_DataLinkLayer dll_instance;
00190   EtherCAT_PD_Buffer pd_buffer(&logic_instance, &dll_instance);
00191   boost::scoped_ptr<EtherCAT_AL> application_layer;
00192   boost::scoped_ptr<EtherCAT_Router> router;
00193 
00194   dll_instance.attach(ni);
00195   application_layer.reset(new EtherCAT_AL(&dll_instance, &logic_instance, &pd_buffer));
00196   router.reset(new EtherCAT_Router(application_layer.get(), &logic_instance, &dll_instance));
00197 
00198   unsigned int n_slaves = application_layer->get_num_slaves();
00199   EtherCAT_SlaveHandler **slaves = application_layer->get_slaves();
00200   for (unsigned int i = 0; i < n_slaves; ++i)
00201   {
00202       detected_devices.push_back(EtherCAT_SlaveHandler(*slaves[i]));
00203   }
00204   if (ni)
00205   {
00206     close_socket(ni);
00207   }
00208   return detected_devices;
00209 }
00210 
00211 void EthercatHardware::init()
00212 {
00213   // open temporary socket to use with ioctl
00214   int sock = socket(PF_INET, SOCK_DGRAM, 0);
00215   if (sock < 0)
00216   {
00217     int error = errno;
00218     ROS_FATAL("Couldn't open temp socket : %s", strerror(error));
00219     sleep(1);
00220     exit(EXIT_FAILURE);
00221   }
00222 
00223   struct ifreq ifr;
00224   strncpy(ifr.ifr_name, interface_.c_str(), IFNAMSIZ);
00225   if (ioctl(sock, SIOCGIFFLAGS, &ifr) < 0)
00226   {
00227     int error = errno;
00228     ROS_FATAL("Cannot get interface_.c_str() flags for %s: %s", interface_.c_str(),
00229               strerror(error));
00230     sleep(1);
00231     exit(EXIT_FAILURE);
00232   }
00233 
00234   close(sock);
00235   sock = -1;
00236 
00237   if (!(ifr.ifr_flags & IFF_UP))
00238   {
00239     ROS_FATAL("Interface %s is not UP. Try : ifup %s", interface_.c_str(), interface_.c_str());
00240     sleep(1);
00241     exit(EXIT_FAILURE);
00242   }
00243   if (!(ifr.ifr_flags & IFF_RUNNING))
00244   {
00245     ROS_FATAL("Interface %s is not RUNNING. Is cable plugged in and device powered?",
00246               interface_.c_str());
00247     sleep(1);
00248     exit(EXIT_FAILURE);
00249   }
00250 
00251   // Initialize network interface
00252   if ((ni_ = init_ec(interface_.c_str())) == NULL)
00253   {
00254     ROS_FATAL_STREAM("Unable to initialize interface_: " << interface_);
00255     sleep(1);
00256     exit(EXIT_FAILURE);
00257   }
00258 
00259   m_dll_instance_.attach(ni_);
00260   application_layer_ = new EtherCAT_AL(&m_dll_instance_, &m_logic_instance_, &pd_buffer_);
00261   m_router_ = new EtherCAT_Router(application_layer_, &m_logic_instance_, &m_dll_instance_);
00262   setRouterToSlaveHandlers();
00263   ethercat_master_ = new EtherCAT_Master(application_layer_, m_router_, &pd_buffer_, &m_logic_instance_, &m_dll_instance_);
00264   oob_com_ = new EthercatOobCom(ni_);
00265 
00266   int num_ethercat_devices_ = application_layer_->get_num_slaves();
00267   if (num_ethercat_devices_ == 0)
00268   {
00269     ROS_FATAL("Unable to locate any slaves");
00270     sleep(1);
00271     exit(EXIT_FAILURE);
00272   }
00273 
00274   // Size slaves vector to hold appropriate number of device pointers
00275   slaves_.resize(num_ethercat_devices_);
00276 
00277   // Make temporary list of slave handles
00278   std::vector<EtherCAT_SlaveHandler*> slave_handles;
00279   for (unsigned int slave = 0; slave < slaves_.size(); ++slave)
00280   {
00281     EC_FixedStationAddress fsa(slave + 1);
00282     EtherCAT_SlaveHandler *sh = ethercat_master_->get_slave_handler(fsa);
00283     if (sh == NULL)
00284     {
00285       ROS_FATAL("Unable to get slave handler #%d", slave);
00286       sleep(1);
00287       exit(EXIT_FAILURE);
00288     }
00289     slave_handles.push_back(sh);
00290   }
00291 
00292   // Configure EtherCAT slaves
00293 
00294   BOOST_FOREACH(EtherCAT_SlaveHandler *sh, slave_handles)
00295   {
00296     unsigned slave = sh->get_station_address() - 1;
00297     if ((slaves_[slave] = configSlave(sh)) == NULL)
00298     {
00299       ROS_FATAL("Unable to configure slave #%d", slave);
00300       sleep(1);
00301       exit(EXIT_FAILURE);
00302     }
00303     buffer_size_ += slaves_[slave]->command_size_ + slaves_[slave]->status_size_;
00304   }
00305 
00306   // Configure any non-ethercat slaves (appends devices to slaves_ vector)
00307   loadNonEthercatDevices();
00308 
00309   // Move slave from INIT to PREOP
00310 
00311   BOOST_FOREACH(EtherCAT_SlaveHandler *sh, slave_handles)
00312   {
00313     changeState(sh, EC_PREOP_STATE);
00314   }
00315 
00316   // Move slave from PREOP to SAFEOP
00317 
00318   BOOST_FOREACH(EtherCAT_SlaveHandler *sh, slave_handles)
00319   {
00320     changeState(sh, EC_SAFEOP_STATE);
00321   }
00322 
00323   // Move slave from SAFEOP to OP
00324   // TODO : move to OP after initializing slave process data
00325 
00326   BOOST_FOREACH(EtherCAT_SlaveHandler *sh, slave_handles)
00327   {
00328     changeState(sh, EC_OP_STATE);
00329   }
00330 
00331   // Allocate buffers to send and receive commands
00332   buffers_ = new unsigned char[2 * buffer_size_];
00333   this_buffer_ = buffers_;
00334   prev_buffer_ = buffers_ + buffer_size_;
00335 
00336   // Make sure motors are disabled, also collect status data
00337   memset(this_buffer_, 0, 2 * buffer_size_);
00338   if (!txandrx_PD(buffer_size_, this_buffer_, 20))
00339   {
00340     ROS_FATAL("No communication with devices");
00341     sleep(1);
00342     exit(EXIT_FAILURE);
00343   }
00344 
00345   // prev_buffer should contain valid status data when update function is first used
00346   memcpy(prev_buffer_, this_buffer_, buffer_size_);
00347 
00348   last_published_ = ros::Time::now();
00349 
00350   // Initialize slaves
00351   //set<string> actuator_names;
00352   for (unsigned int slave = 0; slave < slaves_.size(); ++slave)
00353   {
00354     if (slaves_[slave]->initialize(hw_, allow_unprogrammed_) < 0)
00355     {
00356       EtherCAT_SlaveHandler *sh = slaves_[slave]->sh_;
00357       if (sh != NULL)
00358       {
00359         ROS_FATAL("Unable to initialize slave #%d, product code: %d, revision: %d, serial: %d",
00360                   slave,
00361                   sh->get_product_code(), sh->get_revision(), sh->get_serial());
00362         sleep(1);
00363       }
00364       else
00365       {
00366         ROS_FATAL("Unable to initialize slave #%d", slave);
00367       }
00368       exit(EXIT_FAILURE);
00369     }
00370   }
00371 
00372   { // Initialization is now complete. Reduce timeout of EtherCAT txandrx for better realtime performance
00373     // Allow timeout to be configured at program load time with rosparam.
00374     // This will allow tweaks for systems with different realtime performance
00375     static const int MAX_TIMEOUT = 100000; // 100ms = 100,000us
00376     static const int DEFAULT_TIMEOUT = 20000; // default to timeout to 20000us = 20ms
00377     int timeout;
00378     if (!node_.getParam("realtime_socket_timeout", timeout))
00379     {
00380       timeout = DEFAULT_TIMEOUT;
00381     }
00382     if ((timeout <= 1) || (timeout > MAX_TIMEOUT))
00383     {
00384       int old_timeout = timeout;
00385       timeout = std::max(1, std::min(MAX_TIMEOUT, timeout));
00386       ROS_WARN("Invalid timeout (%d) for socket, using %d", old_timeout, timeout);
00387     }
00388     if (set_socket_timeout(ni_, timeout))
00389     {
00390       ROS_FATAL("Error setting socket timeout to %d", timeout);
00391       sleep(1);
00392       exit(EXIT_FAILURE);
00393     }
00394     timeout_ = timeout;
00395 
00396     // When packet containing process data is does not return after a given timeout, it is
00397     // assumed to be dropped and the process data will automatically get re-sent.
00398     // After a number of retries, the driver will halt motors as a safety precaution.
00399     //
00400     // The following code allows the number of process data retries to be changed with a rosparam.
00401     // This is needed because lowering the txandrx timeout makes it more likely that a
00402     // performance glitch in network or OS causes will cause the motors to halt.
00403     //
00404     // If number of retries is not specified, use a formula that allows 100ms of dropped packets
00405     int max_pd_retries = MAX_TIMEOUT / timeout; // timeout is in nanoseconds : 20msec = 20000usec
00406     static const int MAX_RETRIES = 50, MIN_RETRIES = 1;
00407     node_.getParam("max_pd_retries", max_pd_retries);
00408     // Make sure motor halt due to dropped packet takes less than 1/10 of a second
00409     if ((max_pd_retries * timeout) > (MAX_TIMEOUT))
00410     {
00411       max_pd_retries = MAX_TIMEOUT / timeout;
00412       ROS_WARN("Max PD retries is too large for given timeout.  Limiting value to %d",
00413                max_pd_retries);
00414     }
00415     if ((max_pd_retries < MIN_RETRIES) || (max_pd_retries > MAX_RETRIES))
00416     {
00417       max_pd_retries = std::max(MIN_RETRIES, std::min(MAX_RETRIES, max_pd_retries));
00418       ROS_WARN("Limiting max PD retries to %d", max_pd_retries);
00419     }
00420     max_pd_retries = std::max(MIN_RETRIES, std::min(MAX_RETRIES, max_pd_retries));
00421     max_pd_retries_ = max_pd_retries;
00422   }
00423 
00424   diagnostics_publisher_.initialize(interface_, buffer_size_, slaves_, num_ethercat_devices_,
00425                                     timeout_,
00426                                     max_pd_retries_);
00427 
00428   node_.setParam("EtherCAT_Initialized", true);
00429 }
00430 
00431 EthercatHardwareDiagnosticsPublisher::EthercatHardwareDiagnosticsPublisher(ros::NodeHandle &node) :
00432   node_(node),
00433   diagnostics_ready_(false),
00434   publisher_(node_.advertise<diagnostic_msgs::DiagnosticArray>("/diagnostics", 1)),
00435   diagnostics_buffer_(NULL),
00436   last_dropped_packet_count_(0),
00437   last_dropped_packet_time_(0)
00438 {
00439 }
00440 
00441 EthercatHardwareDiagnosticsPublisher::~EthercatHardwareDiagnosticsPublisher()
00442 {
00443   delete[] diagnostics_buffer_;
00444 }
00445 
00446 void EthercatHardwareDiagnosticsPublisher::initialize(const string &interface, unsigned int buffer_size,
00447                                                       const std::vector<boost::shared_ptr<EthercatDevice> > &slaves,
00448                                                       unsigned int num_ethercat_devices,
00449                                                       unsigned timeout,
00450                                                       unsigned max_pd_retries)
00451 {
00452   interface_ = interface;
00453   buffer_size_ = buffer_size;
00454   slaves_ = slaves;
00455   num_ethercat_devices_ = num_ethercat_devices;
00456   timeout_ = timeout;
00457   max_pd_retries_ = max_pd_retries;
00458 
00459   diagnostics_buffer_ = new unsigned char[buffer_size_];
00460 
00461   // Initialize diagnostic data structures
00462   diagnostic_array_.status.reserve(slaves_.size() + 1);
00463   values_.reserve(10);
00464 
00465   ethernet_interface_info_.initialize(interface);
00466 
00467   diagnostics_thread_ = boost::thread(boost::bind(&EthercatHardwareDiagnosticsPublisher::diagnosticsThreadFunc, this));
00468 }
00469 
00470 void EthercatHardwareDiagnosticsPublisher::publish(const unsigned char *buffer,
00471                                                    const EthercatHardwareDiagnostics &diagnostics)
00472 {
00473   boost::try_to_lock_t try_lock;
00474   boost::unique_lock<boost::mutex> lock(diagnostics_mutex_, try_lock);
00475   if (lock.owns_lock())
00476   {
00477     // Make copies of diagnostic data for diagnostic thread
00478     memcpy(diagnostics_buffer_, buffer, buffer_size_);
00479     diagnostics_ = diagnostics;
00480     // Trigger diagnostics publish thread
00481     diagnostics_ready_ = true;
00482     diagnostics_cond_.notify_one();
00483   }
00484 }
00485 
00486 void EthercatHardwareDiagnosticsPublisher::stop()
00487 {
00488   diagnostics_thread_.interrupt();
00489   diagnostics_thread_.join();
00490   publisher_.shutdown();
00491 }
00492 
00493 void EthercatHardwareDiagnosticsPublisher::diagnosticsThreadFunc()
00494 {
00495   try
00496   {
00497     while (1)
00498     {
00499       boost::unique_lock<boost::mutex> lock(diagnostics_mutex_);
00500       while (!diagnostics_ready_)
00501       {
00502         diagnostics_cond_.wait(lock);
00503       }
00504       diagnostics_ready_ = false;
00505       publishDiagnostics();
00506     }
00507   }
00508   catch (boost::thread_interrupted const&)
00509   {
00510     return;
00511   }
00512 }
00513 
00514 void EthercatHardwareDiagnosticsPublisher::timingInformation(diagnostic_updater::DiagnosticStatusWrapper &status,
00515                                                              const string &key,
00516                                                              const accumulator_set<double, stats<tag::max, tag::mean> > &acc,
00517                                                              double max)
00518 {
00519   status.addf(key + " Avg (us)", "%5.4f", extract_result<tag::mean>(acc) * 1e6); // Average over last 1 second
00520   status.addf(key + " 1 Sec Max (us)", "%5.4f", extract_result<tag::max>(acc) * 1e6); // Max over last 1 second
00521   status.addf(key + " Max (us)", "%5.4f", max * 1e6); // Max since start
00522 }
00523 
00524 void EthercatHardwareDiagnosticsPublisher::publishDiagnostics()
00525 {
00526   ros::Time now(ros::Time::now());
00527 
00528   // Publish status of EtherCAT master
00529   status_.clearSummary();
00530   status_.clear();
00531 
00532   status_.name = "EtherCAT Master";
00533 //  if (diagnostics_.motors_halted_)
00534 //  {
00535 //    std::ostringstream desc;
00536 //    desc << "Motors halted";
00537 //    if (diagnostics_.halt_after_reset_)
00538 //    {
00539 //      desc << " soon after reset";
00540 //    }
00541 //    desc << " (" << diagnostics_.motors_halted_reason_ << ")";
00542 //    status_.summary(status_.ERROR, desc.str());
00543 //  }
00544 //  else
00545 //  {
00546   status_.summary(status_.OK, "OK");
00547 //  }
00548 
00549   if (diagnostics_.pd_error_)
00550   {
00551     status_.mergeSummary(status_.ERROR, "Error sending proccess data");
00552   }
00553 
00554   //status_.add("Motors halted", diagnostics_.motors_halted_ ? "true" : "false");
00555   status_.addf("EtherCAT devices (expected)", "%d", num_ethercat_devices_);
00556   status_.addf("EtherCAT devices (current)", "%d", diagnostics_.device_count_);
00557   ethernet_interface_info_.publishDiagnostics(status_);
00558   //status_.addf("Reset state", "%d", reset_state_);
00559 
00560   status_.addf("Timeout (us)", "%d", timeout_);
00561   status_.addf("Max PD Retries", "%d", max_pd_retries_);
00562 
00563   // Produce warning if number of devices changed after device initialization
00564   if (num_ethercat_devices_ != diagnostics_.device_count_)
00565   {
00566     status_.mergeSummary(status_.WARN, "Number of EtherCAT devices changed");
00567   }
00568 
00569   timingInformation(status_, "Roundtrip time", diagnostics_.txandrx_acc_,
00570                     diagnostics_.max_txandrx_);
00571   if (diagnostics_.collect_extra_timing_)
00572   {
00573     timingInformation(status_, "Pack command time", diagnostics_.pack_command_acc_,
00574                       diagnostics_.max_pack_command_);
00575     timingInformation(status_, "Unpack state time", diagnostics_.unpack_state_acc_,
00576                       diagnostics_.max_unpack_state_);
00577     timingInformation(status_, "Publish time", diagnostics_.publish_acc_,
00578                       diagnostics_.max_publish_);
00579   }
00580 
00581   status_.addf("EtherCAT Process Data txandrx errors", "%d", diagnostics_.txandrx_errors_);
00582 
00583   status_.addf("Reset motors service count", "%d", diagnostics_.reset_motors_service_count_);
00584   status_.addf("Halt motors service count", "%d", diagnostics_.halt_motors_service_count_);
00585   status_.addf("Halt motors error count", "%d", diagnostics_.halt_motors_error_count_);
00586 
00587   { // Publish ethercat network interface counters
00588     const struct netif_counters *c = &diagnostics_.counters_;
00589     status_.add("Input Thread", (diagnostics_.input_thread_is_stopped_ ? "Stopped" : "Running"));
00590     status_.addf("Sent Packets", "%llu", (unsigned long long) c->sent);
00591     status_.addf("Received Packets", "%llu", (unsigned long long) c->received);
00592     status_.addf("Collected Packets", "%llu", (unsigned long long) c->collected);
00593     status_.addf("Dropped Packets", "%llu", (unsigned long long) c->dropped);
00594     status_.addf("TX Errors", "%llu", (unsigned long long) c->tx_error);
00595     status_.addf("TX Network Down", "%llu", (unsigned long long) c->tx_net_down);
00596     status_.addf("TX Would Block", "%llu", (unsigned long long) c->tx_would_block);
00597     status_.addf("TX No Buffers", "%llu", (unsigned long long) c->tx_no_bufs);
00598     status_.addf("TX Queue Full", "%llu", (unsigned long long) c->tx_full);
00599     status_.addf("RX Runt Packet", "%llu", (unsigned long long) c->rx_runt_pkt);
00600     status_.addf("RX Not EtherCAT", "%llu", (unsigned long long) c->rx_not_ecat);
00601     status_.addf("RX Other EML", "%llu", (unsigned long long) c->rx_other_eml);
00602     status_.addf("RX Bad Index", "%llu", (unsigned long long) c->rx_bad_index);
00603     status_.addf("RX Bad Sequence", "%llu", (unsigned long long) c->rx_bad_seqnum);
00604     status_.addf("RX Duplicate Sequence", "%llu", (unsigned long long) c->rx_dup_seqnum);
00605     status_.addf("RX Duplicate Packet", "%llu", (unsigned long long) c->rx_dup_pkt);
00606     status_.addf("RX Bad Order", "%llu", (unsigned long long) c->rx_bad_order);
00607     status_.addf("RX Late Packet", "%llu", (unsigned long long) c->rx_late_pkt);
00608     status_.addf("RX Late Packet RTT", "%llu", (unsigned long long) c->rx_late_pkt_rtt_us);
00609 
00610     double rx_late_pkt_rtt_us_avg = 0.0;
00611     if (c->rx_late_pkt > 0)
00612     {
00613       rx_late_pkt_rtt_us_avg = ((double) c->rx_late_pkt_rtt_us_sum) / ((double) c->rx_late_pkt);
00614     }
00615     status_.addf("RX Late Packet Avg RTT", "%f", rx_late_pkt_rtt_us_avg);
00616 
00617     // Check for newly dropped packets
00618     if (c->dropped > last_dropped_packet_count_)
00619     {
00620       last_dropped_packet_time_ = now;
00621       last_dropped_packet_count_ = c->dropped;
00622     }
00623   }
00624 
00625   // Create error message if packet has been dropped recently
00626   if ((last_dropped_packet_count_ > 0)
00627       && ((now - last_dropped_packet_time_).toSec() < dropped_packet_warning_hold_time_))
00628   {
00629     status_.mergeSummaryf(status_.WARN, "Dropped packets in last %d seconds",
00630                           dropped_packet_warning_hold_time_);
00631   }
00632 
00633   diagnostic_array_.status.clear();
00634   diagnostic_array_.status.push_back(status_);
00635 
00636   // Also, collect diagnostic statuses of all EtherCAT device
00637   unsigned char *current = diagnostics_buffer_;
00638   for (unsigned int s = 0; s < slaves_.size(); ++s)
00639   {
00640     slaves_[s]->multiDiagnostics(diagnostic_array_.status, current);
00641     current += slaves_[s]->command_size_ + slaves_[s]->status_size_;
00642   }
00643 
00644   // Publish status of each EtherCAT device
00645   diagnostic_array_.header.stamp = ros::Time::now();
00646   publisher_.publish(diagnostic_array_);
00647 }
00648 
00649 void EthercatHardware::update(bool reset, bool halt)
00650 {
00651   // Update current time
00652   ros::Time update_start_time(ros::Time::now());
00653 
00654   unsigned char *this_buffer, *prev_buffer;
00655 
00656   // Convert HW Interface commands to MCB-specific buffers
00657   this_buffer = this_buffer_;
00658 
00659   if (halt)
00660   {
00661     ++diagnostics_.halt_motors_service_count_;
00662     haltMotors(false /*no error*/, "service request");
00663   }
00664 
00665   // Resetting devices should clear device errors and release devices from halt.
00666   // To reduce load on power system, release devices from halt, one at a time
00667   const unsigned CYCLES_PER_HALT_RELEASE = 2; // Wait two cycles between releasing each device
00668   if (reset)
00669   {
00670     ++diagnostics_.reset_motors_service_count_;
00671     reset_state_ = CYCLES_PER_HALT_RELEASE * slaves_.size() + 5;
00672     last_reset_ = update_start_time;
00673     diagnostics_.halt_after_reset_ = false;
00674   }
00675   bool reset_devices = reset_state_ == CYCLES_PER_HALT_RELEASE * slaves_.size() + 3;
00676   if (reset_devices)
00677   {
00678     halt_motors_ = false;
00679     diagnostics_.motors_halted_ = false;
00680     diagnostics_.motors_halted_reason_ = "";
00681     diagnostics_.resetMaxTiming();
00682     diagnostics_.pd_error_ = false;
00683   }
00684 
00685   for (unsigned int s = 0; s < slaves_.size(); ++s)
00686   {
00687     // Pack the command structures into the EtherCAT buffer
00688     // Disable the motor if they are halted or coming out of reset
00689     bool halt_device = halt_motors_ || ((s * CYCLES_PER_HALT_RELEASE + 1) < reset_state_);
00690     slaves_[s]->packCommand(this_buffer, halt_device, reset_devices);
00691     this_buffer += slaves_[s]->command_size_ + slaves_[s]->status_size_;
00692   }
00693 
00694   // Transmit process data
00695   ros::Time txandrx_start_time(ros::Time::now()); // Also end time for pack_command_stage
00696   diagnostics_.pack_command_acc_((txandrx_start_time - update_start_time).toSec());
00697 
00698   // Send/receive device process data
00699   bool success = txandrx_PD(buffer_size_, this_buffer_, max_pd_retries_);
00700 
00701   ros::Time txandrx_end_time(ros::Time::now()); // Also start unpack_state
00702   diagnostics_.txandrx_acc_((txandrx_end_time - txandrx_start_time).toSec());
00703 
00704   if (!success)
00705   {
00706     // If process data didn't get sent after multiple retries, stop motors
00707     haltMotors(true /*error*/, "communication error");
00708     diagnostics_.pd_error_ = true;
00709   }
00710   else
00711   {
00712     // Convert status back to HW Interface
00713     this_buffer = this_buffer_;
00714     prev_buffer = prev_buffer_;
00715     for (unsigned int s = 0; s < slaves_.size(); ++s)
00716     {
00717       if (!slaves_[s]->unpackState(this_buffer, prev_buffer) && !reset_devices)
00718       {
00719         haltMotors(true /*error*/, "device error");
00720       }
00721       this_buffer += slaves_[s]->command_size_ + slaves_[s]->status_size_;
00722       prev_buffer += slaves_[s]->command_size_ + slaves_[s]->status_size_;
00723     }
00724 
00725     if (reset_state_)
00726       --reset_state_;
00727 
00728     unsigned char *tmp = this_buffer_;
00729     this_buffer_ = prev_buffer_;
00730     prev_buffer_ = tmp;
00731   }
00732 
00733   ros::Time unpack_end_time;
00734   if (diagnostics_.collect_extra_timing_)
00735   {
00736     unpack_end_time = ros::Time::now(); // also start of publish time
00737     diagnostics_.unpack_state_acc_((unpack_end_time - txandrx_end_time).toSec());
00738   }
00739 
00740   if ((update_start_time - last_published_) > ros::Duration(1.0))
00741   {
00742     last_published_ = update_start_time;
00743     publishDiagnostics();
00744     motor_publisher_.lock();
00745     motor_publisher_.msg_.data = halt_motors_;
00746     motor_publisher_.unlockAndPublish();
00747   }
00748 
00749   if (diagnostics_.collect_extra_timing_)
00750   {
00751     ros::Time publish_end_time(ros::Time::now());
00752     diagnostics_.publish_acc_((publish_end_time - unpack_end_time).toSec());
00753   }
00754 }
00755 
00756 void EthercatHardware::haltMotors(bool error, const char* reason)
00757 {
00758   if (!halt_motors_)
00759   {
00760     // wasn't already halted
00761     motor_publisher_.lock();
00762     motor_publisher_.msg_.data = halt_motors_;
00763     motor_publisher_.unlockAndPublish();
00764 
00765     diagnostics_.motors_halted_reason_ = reason;
00766     if (error)
00767     {
00768       ++diagnostics_.halt_motors_error_count_;
00769       if ((ros::Time::now() - last_reset_) < ros::Duration(0.5))
00770       {
00771         // halted soon after reset
00772         diagnostics_.halt_after_reset_ = true;
00773       }
00774     }
00775   }
00776 
00777   diagnostics_.motors_halted_ = true;
00778   halt_motors_ = true;
00779 }
00780 
00781 void EthercatHardware::updateAccMax(double &max,
00782                                     const accumulator_set<double, stats<tag::max, tag::mean> > &acc)
00783 {
00784   max = std::max(max, extract_result<tag::max>(acc));
00785 }
00786 
00787 void EthercatHardware::publishDiagnostics()
00788 {
00789   // Update max timing values
00790   updateAccMax(diagnostics_.max_pack_command_, diagnostics_.pack_command_acc_);
00791   updateAccMax(diagnostics_.max_txandrx_, diagnostics_.txandrx_acc_);
00792   updateAccMax(diagnostics_.max_unpack_state_, diagnostics_.unpack_state_acc_);
00793   updateAccMax(diagnostics_.max_publish_, diagnostics_.publish_acc_);
00794 
00795   // Grab stats and counters from input thread
00796   diagnostics_.counters_ = ni_->counters;
00797   diagnostics_.input_thread_is_stopped_ = bool(ni_->is_stopped);
00798 
00799   diagnostics_.motors_halted_ = halt_motors_;
00800 
00801   // Pass diagnostic data to publisher thread
00802   diagnostics_publisher_.publish(this_buffer_, diagnostics_);
00803 
00804   // Clear statistics accumulators
00805   static accumulator_set<double, stats<tag::max, tag::mean> > blank;
00806   diagnostics_.pack_command_acc_ = blank;
00807   diagnostics_.txandrx_acc_ = blank;
00808   diagnostics_.unpack_state_acc_ = blank;
00809   diagnostics_.publish_acc_ = blank;
00810 }
00811 
00812 boost::shared_ptr<EthercatDevice>
00813 EthercatHardware::configSlave(EtherCAT_SlaveHandler *sh)
00814 {
00815   boost::shared_ptr<EthercatDevice> p;
00816   unsigned product_code = sh->get_product_code();
00817   unsigned serial = sh->get_serial();
00818   uint32_t revision = sh->get_revision();
00819   unsigned slave = sh->get_station_address() - 1;
00820 
00821   // The point of this code to find a class whose name matches the EtherCAT
00822   // product ID for a given device.
00823   // Thus device plugins would register themselves with PLUGINLIB_EXPORT_CLASS
00824   //
00825   //    PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
00826   //
00827   // and in the plugin.xml, specify name="" inside the <class> tag:
00828   //
00829   //    <class name="package/serial"
00830   //           base_class_type="ethercat_hardware::EthercatDevice" />
00831   //
00832   //
00833   // For the WG05 driver (productID = 6805005), this statement would look
00834   // something like:
00835   //
00836   //    PLUGINLIB_EXPORT_CLASS(WG05, EthercatDevice)
00837   //
00838   // and in the plugin.xml:
00839   //
00840   //    <class name="ethercat_hardware/6805005" type="WG05"
00841   //           base_class_type="EthercatDevice">
00842   //      <description>
00843   //        WG05 - Generic Motor Control Board
00844   //      </description>
00845   //    </class>
00846   //
00847   //
00848   // Unfortunately, we don't know which ROS package that a particular driver is defined in.
00849   // To account for this, we search through the list of class names, one-by-one and find string where
00850   // last part of string matches product ID of device.
00851   stringstream class_name_regex_str;
00852   class_name_regex_str << "(.*/)?" << product_code;
00853   boost::regex class_name_regex(class_name_regex_str.str(), boost::regex::extended);
00854 
00855   std::vector<std::string> classes = device_loader_.getDeclaredClasses();
00856   std::string matching_class_name;
00857 
00858   BOOST_FOREACH(const std::string &class_name, classes)
00859   {
00860     if (regex_match(class_name, class_name_regex))
00861     {
00862       if (matching_class_name.size() != 0)
00863       {
00864         ROS_ERROR("Found more than 1 EtherCAT driver for device with product code : %d", product_code);
00865         ROS_ERROR("First class name = '%s'.  Second class name = '%s'",
00866                   class_name.c_str(), matching_class_name.c_str());
00867       }
00868       matching_class_name = class_name;
00869     }
00870   }
00871 
00872   if (matching_class_name.size() != 0)
00873   {
00874     ROS_WARN("Using device '%s' with product code %d",
00875              device_loader_.getClassDescription(matching_class_name).c_str(),
00876              product_code);
00877     try
00878     {
00879       p = device_loader_.createInstance(matching_class_name);
00880     }
00881     catch (pluginlib::LibraryLoadException &e)
00882     {
00883       p.reset();
00884       ROS_FATAL("Unable to load plugin for slave #%d, product code: %u (0x%X), serial: %u (0x%X), revision: %d (0x%X)",
00885                 slave,
00886                 product_code, product_code, serial, serial, revision, revision);
00887       ROS_FATAL("%s", e.what());
00888     }
00889   }
00890   else
00891   {
00892     if ((product_code == 0xbaddbadd) || (serial == 0xbaddbadd) || (revision == 0xbaddbadd))
00893     {
00894       ROS_FATAL("Note: 0xBADDBADD indicates that the value was not read correctly from device.");
00895       ROS_FATAL("Perhaps you should power-cycle the MCBs");
00896     }
00897     else
00898     {
00899       ROS_ERROR("Unable to load plugin for slave #%d, product code: %u (0x%X), serial: %u (0x%X), revision: %d (0x%X)",
00900                 slave,
00901                 product_code, product_code, serial, serial, revision, revision);
00902       ROS_ERROR("Possible classes:");
00903 
00904       BOOST_FOREACH(const std::string &class_name, classes)
00905       {
00906         ROS_ERROR("  %s", class_name.c_str());
00907       }
00908 
00909       // TODO, use default plugin for ethercat devices that have no driver.
00910       // This way, the EtherCAT chain still works.
00911     }
00912   }
00913 
00914   if (p != NULL)
00915   {
00916     p->construct(sh, start_address_);
00917   }
00918 
00919   return p;
00920 }
00921 
00922 boost::shared_ptr<EthercatDevice>
00923 EthercatHardware::configNonEthercatDevice(const std::string &name, const std::string &type)
00924 {
00925   boost::shared_ptr<EthercatDevice> p;
00926   try
00927   {
00928     p = device_loader_.createInstance(type);
00929   }
00930   catch (pluginlib::LibraryLoadException &e)
00931   {
00932     p.reset();
00933     ROS_FATAL("Unable to load plugin for non-EtherCAT device '%s' with type: %s : %s",
00934               name.c_str(), type.c_str(), e.what());
00935   }
00936   if (p)
00937   {
00938     ROS_INFO("Creating non-EtherCAT device '%s' of type '%s'", name.c_str(), type.c_str());
00939     ros::NodeHandle nh(node_, "non_ethercat_devices/" + name);
00940     p->construct(nh);
00941   }
00942   return p;
00943 }
00944 
00945 // Do this to get access to Struct (std::map) element of XmlRpcValue
00946 
00947 class MyXmlRpcValue : public XmlRpc::XmlRpcValue
00948 {
00949 public:
00950 
00951   MyXmlRpcValue(XmlRpc::XmlRpcValue &value) :
00952     XmlRpc::XmlRpcValue(value)
00953   {
00954   }
00955 
00956   XmlRpcValue::ValueStruct &getMap()
00957   {
00958     return *_value.asStruct;
00959   }
00960 };
00961 
00962 void EthercatHardware::loadNonEthercatDevices()
00963 {
00964   // non-EtherCAT device drivers are descibed via struct named "non_ethercat_devices"
00965   // Each element of "non_ethercat_devices" must be a struct that contains a "type" field.
00966   // The element struct can also contain other elements that are used as configuration parameters
00967   // for the device plugin.
00968   // Example:
00969   //   non_ethercat_devices:
00970   //     netft1:
00971   //       type: NetFT
00972   //       address: 192.168.1.1
00973   //       publish_period: 0.01
00974   //     netft2:
00975   //       type: NetFT
00976   //       address: 192.168.1.2
00977   //       publish_period: 0.01
00978   //     dummy_device:
00979   //       type: Dummy
00980   //       msg: "This a dummy device"
00981   //
00982   //   The name of the device is used to create a ros::NodeHandle that is
00983   //    that is passed to construct function of device class.
00984   //   NOTE: construct function is not the same as C++ construtor
00985   if (!node_.hasParam("non_ethercat_devices"))
00986   {
00987     // It is perfectly fine if there is no list of non-ethercat devices
00988     return;
00989   }
00990 
00991   XmlRpc::XmlRpcValue devices;
00992   node_.getParam("non_ethercat_devices", devices);
00993   if (devices.getType() != XmlRpc::XmlRpcValue::TypeStruct)
00994   {
00995     ROS_ERROR("Rosparam 'non_ethercat_devices' is not a struct type");
00996     return;
00997   }
00998 
00999   MyXmlRpcValue my_devices(devices);
01000   typedef XmlRpc::XmlRpcValue::ValueStruct::value_type map_item_t;
01001 
01002   BOOST_FOREACH(map_item_t &item, my_devices.getMap())
01003   {
01004     const std::string & name(item.first);
01005     XmlRpc::XmlRpcValue & device_info(item.second);
01006 
01007     if (device_info.getType() != XmlRpc::XmlRpcValue::TypeStruct)
01008     {
01009       ROS_ERROR("non_ethercat_devices/%s is not a struct type", name.c_str());
01010       continue;
01011     }
01012 
01013     if (!device_info.hasMember("type"))
01014     {
01015       ROS_ERROR("non_ethercat_devices/%s 'type' element", name.c_str());
01016       continue;
01017     }
01018 
01019     std::string type(static_cast<std::string> (device_info["type"]));
01020 
01021     boost::shared_ptr<EthercatDevice> new_device =
01022       configNonEthercatDevice(name, type);
01023     if (new_device != NULL)
01024     {
01025       slaves_.push_back(new_device);
01026     }
01027   }
01028 }
01029 
01030 void EthercatHardware::collectDiagnostics()
01031 {
01032   if (NULL == oob_com_)
01033     return;
01034 
01035   { // Count number of devices
01036     unsigned char p[1];
01037     uint16_t length = sizeof (p);
01038 
01039     // Build read telegram, use slave position
01040     APRD_Telegram status(m_logic_instance_.get_idx(), // Index
01041                          0, // Slave position on ethercat chain (auto increment address)
01042                          0, // ESC physical memory address (start address)
01043                          m_logic_instance_.get_wkc(), // Working counter
01044                          length, // Data Length,
01045                          p); // Buffer to put read result into
01046 
01047     // Put read telegram in ros_ethercat_eml/ethernet frame
01048     EC_Ethernet_Frame frame(&status);
01049     oob_com_->txandrx(&frame);
01050 
01051     // Worry about locking for single value?
01052     diagnostics_.device_count_ = status.get_adp();
01053   }
01054 
01055   for (unsigned i = 0; i < slaves_.size(); ++i)
01056   {
01057     boost::shared_ptr<EthercatDevice> d(slaves_[i]);
01058     d->collectDiagnostics(oob_com_);
01059   }
01060 }
01061 
01062 // Prints (error) counter information of network interface driver
01063 
01064 void EthercatHardware::printCounters(std::ostream &os)
01065 {
01066   const struct netif_counters & c(ni_->counters);
01067   os << "netif counters :" << endl
01068     << " sent          = " << c.sent << endl
01069     << " received      = " << c.received << endl
01070     << " collected     = " << c.collected << endl
01071     << " dropped       = " << c.dropped << endl
01072     << " tx_error      = " << c.tx_error << endl
01073     << " tx_net_down   = " << c.tx_net_down << endl
01074     << " tx_would_block= " << c.tx_would_block << endl
01075     << " tx_no_bufs    = " << c.tx_no_bufs << endl
01076     << " tx_full       = " << c.tx_full << endl
01077     << " rx_runt_pkt   = " << c.rx_runt_pkt << endl
01078     << " rx_not_ecat   = " << c.rx_not_ecat << endl
01079     << " rx_other_eml  = " << c.rx_other_eml << endl
01080     << " rx_bad_index  = " << c.rx_bad_index << endl
01081     << " rx_bad_seqnum = " << c.rx_bad_seqnum << endl
01082     << " rx_dup_seqnum = " << c.rx_dup_seqnum << endl
01083     << " rx_dup_pkt    = " << c.rx_dup_pkt << endl
01084     << " rx_bad_order  = " << c.rx_bad_order << endl
01085     << " rx_late_pkt   = " << c.rx_late_pkt << endl;
01086 }
01087 
01088 bool EthercatHardware::txandrx_PD(unsigned buffer_size, unsigned char* buffer, unsigned tries)
01089 {
01090   // Try multiple times to get process data to device
01091   bool success = false;
01092   for (unsigned i = 0; i < tries && !success; ++i)
01093   {
01094     // Try transmitting process data
01095     success = ethercat_master_->txandrx_PD(buffer_size_, this_buffer_);
01096     if (!success)
01097     {
01098       ++diagnostics_.txandrx_errors_;
01099     }
01100     // Transmit new OOB data
01101     oob_com_->tx();
01102   }
01103   return success;
01104 }
01105 
01106 bool EthercatHardware::publishTrace(int position, const string &reason, unsigned level,
01107                                     unsigned delay)
01108 {
01109   if (position >= (int) slaves_.size())
01110   {
01111     ROS_WARN("Invalid device position %d.  Use 0-%d, or -1.", position, int(slaves_.size()) - 1);
01112     return false;
01113   }
01114 
01115   if (level > 2)
01116   {
01117     ROS_WARN("Invalid level : %d.  Using level=2 (ERROR).", level);
01118     level = 2;
01119   }
01120 
01121   string new_reason("Manually triggered : " + reason);
01122 
01123   bool retval = false;
01124   if (position < 0)
01125   {
01126     for (unsigned i = 0; i < slaves_.size(); ++i)
01127     {
01128       if (slaves_[i]->publishTrace(new_reason, level, delay))
01129       {
01130         retval = true;
01131       }
01132     }
01133   }
01134   else
01135   {
01136     retval = slaves_[position]->publishTrace(new_reason, level, delay);
01137     if (!retval)
01138     {
01139       ROS_WARN("Device %d does not support publishing trace", position);
01140     }
01141   }
01142   return retval;
01143 }


ros_ethercat_hardware
Author(s): Rob Wheeler , Derek King , Manos Nikolaidis
autogenerated on Thu Jul 4 2019 20:01:53