ethercat_device.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_device.h"
00036 
00037 #include <tinyxml.h>
00038 
00039 #include <iomanip>
00040 
00041 bool et1x00_error_counters::isGreaterThan(unsigned value) const
00042 {
00043   if ((pdi_error > value) || (epu_error > value))
00044   {
00045     return true;
00046   }
00047 
00048   for (unsigned i = 0; i < 4; ++i)
00049   {
00050     if ((port[i].rx_error > value) ||
00051         (forwarded_rx_error[i] > value) ||
00052         (lost_link[i] > value) ||
00053         (port[i].invalid_frame > value))
00054     {
00055       return true;
00056     }
00057   }
00058   return false;
00059 }
00060 
00061 bool et1x00_error_counters::isGreaterThan(const et1x00_error_counters &v) const
00062 {
00063   if ((pdi_error > v.pdi_error) || (epu_error > v.epu_error))
00064   {
00065     return true;
00066   }
00067 
00068   for (unsigned i = 0; i < 4; ++i)
00069   {
00070     if ((port[i].rx_error > v.port[i].rx_error) ||
00071         (forwarded_rx_error[i] > v.forwarded_rx_error[i]) ||
00072         (lost_link[i] > v.lost_link[i]) ||
00073         (port[i].invalid_frame > v.port[i].invalid_frame))
00074     {
00075       return true;
00076     }
00077   }
00078   return false;
00079 }
00080 
00081 bool et1x00_dl_status::hasLink(unsigned port)
00082 {
00083   assert(port < 4);
00084   return status & (1 << (4 + port));
00085 }
00086 
00087 bool et1x00_dl_status::hasCommunication(unsigned port)
00088 {
00089   assert(port < 4);
00090   return status & (1 << (9 + port * 2));
00091 }
00092 
00093 bool et1x00_dl_status::isClosed(unsigned port)
00094 {
00095   assert(port < 4);
00096   return status & (1 << (8 + port * 2));
00097 }
00098 
00099 void et1x00_error_counters::zero()
00100 {
00101   memset(this, 0, sizeof (et1x00_error_counters));
00102 }
00103 
00104 EthercatPortDiagnostics::EthercatPortDiagnostics() :
00105   hasLink(false),
00106   isClosed(false),
00107   hasCommunication(false)
00108 {
00109   zeroTotals();
00110 }
00111 
00112 void EthercatPortDiagnostics::zeroTotals()
00113 {
00114   rxErrorTotal = 0;
00115   invalidFrameTotal = 0;
00116   forwardedRxErrorTotal = 0;
00117   lostLinkTotal = 0;
00118 }
00119 
00120 EthercatDeviceDiagnostics::EthercatDeviceDiagnostics() :
00121   errorCountersMayBeCleared_(false),
00122   diagnosticsFirst_(true),
00123   diagnosticsValid_(false),
00124   resetDetected_(false),
00125   devicesRespondingToNodeAddress_(-1)
00126 {
00127   zeroTotals();
00128   errorCountersPrev_.zero();
00129 }
00130 
00131 void EthercatDeviceDiagnostics::zeroTotals()
00132 {
00133   pdiErrorTotal_ = 0;
00134   epuErrorTotal_ = 0;
00135   portDiagnostics_[0].zeroTotals();
00136   portDiagnostics_[1].zeroTotals();
00137   portDiagnostics_[2].zeroTotals();
00138   portDiagnostics_[3].zeroTotals();
00139 }
00140 
00141 void EthercatDeviceDiagnostics::accumulate(const et1x00_error_counters &n, const et1x00_error_counters &p)
00142 {
00143   pdiErrorTotal_ += n.pdi_error - p.pdi_error;
00144   epuErrorTotal_ += n.epu_error - p.epu_error;
00145   for (unsigned i = 0; i < 4; ++i)
00146   {
00147     EthercatPortDiagnostics & pt(portDiagnostics_[i]);
00148     pt.rxErrorTotal += n.port[i].rx_error - p.port[i].rx_error;
00149     pt.forwardedRxErrorTotal += n.forwarded_rx_error[i] - p.forwarded_rx_error[i];
00150     pt.lostLinkTotal += n.lost_link[i] - p.lost_link[i];
00151     pt.invalidFrameTotal += n.port[i].invalid_frame - p.port[i].invalid_frame;
00152   }
00153 }
00154 
00155 void EthercatDeviceDiagnostics::collect(EthercatCom *com, EtherCAT_SlaveHandler *sh)
00156 {
00157   diagnosticsValid_ = false;
00158   diagnosticsFirst_ = false;
00159 
00160   // Check if device has been reset/power cycled using its node address
00161   // Node address initialize to 0 after device reset.
00162   // EML library will configure each node address to non-zero when it first starts
00163   // Device should respond to its node address, if it does not either:
00164   //  1. communication to device is not possible (lost/broken link)
00165   //  2. device was reset, and its fixed address setting is now 0
00166   {
00167     // Send a packet with both a Fixed address read (NPRW) and a positional read (APRD)
00168     // If the NPRD has a working counter == 0, but the APRD sees the correct number of devices,
00169     // then the node has likely been reset.
00170     // Also, get DL status register with nprd telegram
00171 
00172     // This is for the case of non-ethercat device where SlaveHandler is NULL
00173     if (sh == NULL)
00174     {
00175       diagnosticsValid_ = true;
00176       return;
00177     }
00178 
00179     EC_Logic *logic = sh->m_logic_instance;
00180     et1x00_dl_status dl_status;
00181     NPRD_Telegram nprd_telegram(logic->get_idx(),
00182                                 sh->get_station_address(),
00183                                 dl_status.BASE_ADDR,
00184                                 logic->get_wkc(),
00185                                 sizeof (dl_status),
00186                                 (unsigned char*) &dl_status);
00187     // Use positional read to re-count number of devices on chain
00188     unsigned char buf[1];
00189     uint16_t address = 0x0000;
00190     APRD_Telegram aprd_telegram(logic->get_idx(), // Index
00191                                 0, // Slave position on ethercat chain (auto increment address) (
00192                                 address, // ESC physical memory address (start address)
00193                                 logic->get_wkc(), // Working counter
00194                                 sizeof (buf), // Data Length,
00195                                 buf); // Buffer to put read result into
00196 
00197 
00198 
00199     // Chain both telegrams together
00200     nprd_telegram.attach(&aprd_telegram);
00201 
00202     EC_Ethernet_Frame frame(&nprd_telegram);
00203 
00204     // Send/Recv data from slave
00205     if (!com->txandrx_once(&frame))
00206     {
00207       // no response - broken link to device
00208       goto end;
00209     }
00210 
00211     devicesRespondingToNodeAddress_ = nprd_telegram.get_wkc();
00212     if (devicesRespondingToNodeAddress_ == 0)
00213     {
00214       // Device has not responded to its node address.
00215       if (aprd_telegram.get_adp() >= sh->m_router_instance->m_al_instance->get_num_slaves())
00216       {
00217         resetDetected_ = true;
00218         goto end;
00219       }
00220     }
00221     else if (devicesRespondingToNodeAddress_ > 1)
00222     {
00223       // Can't determine much if two (or more) devices are responding to same request.
00224       goto end;
00225     }
00226     else
00227     {
00228       resetDetected_ = false;
00229     }
00230 
00231     // fill in port status information
00232     for (unsigned i = 0; i < 4; ++i)
00233     {
00234       EthercatPortDiagnostics & pt(portDiagnostics_[i]);
00235       pt.hasLink = dl_status.hasLink(i);
00236       pt.isClosed = dl_status.isClosed(i);
00237       pt.hasCommunication = dl_status.hasCommunication(i);
00238     }
00239   }
00240 
00241   { // read and accumulate communication error counters
00242     et1x00_error_counters e;
00243     assert(sizeof (e) == (0x314 - 0x300));
00244     if (0 != EthercatDevice::readData(com, sh, e.BASE_ADDR, &e, sizeof (e), EthercatDevice::FIXED_ADDR))
00245     {
00246       goto end;
00247     }
00248 
00249     // If this previously tried to clear the error counters but d/n get a response
00250     // then use the newly read values to guess if they got cleared or not.
00251     if (errorCountersMayBeCleared_)
00252     {
00253       if (!e.isGreaterThan(errorCountersPrev_))
00254       {
00255         errorCountersPrev_.zero();
00256       }
00257       errorCountersMayBeCleared_ = false;
00258     }
00259     if (errorCountersPrev_.isGreaterThan(e))
00260     {
00261       ROS_ERROR("Device %d : previous port error counters less current values", sh->get_ring_position());
00262     }
00263 
00264     // Accumulate
00265     this->accumulate(e, errorCountersPrev_);
00266     errorCountersPrev_ = e;
00267 
00268     // re-read and clear communication error counters
00269     if (e.isGreaterThan(50))
00270     {
00271       if (0 != EthercatDevice::readWriteData(com, sh, e.BASE_ADDR, &e, sizeof (e), EthercatDevice::FIXED_ADDR))
00272       {
00273         // Packet got lost... Can't know for sure that error counters got cleared
00274         errorCountersMayBeCleared_ = true;
00275         goto end;
00276       }
00277       // We read and cleared error counters in same packet, accumulate any error counter differences
00278       this->accumulate(e, errorCountersPrev_);
00279       errorCountersPrev_.zero();
00280     }
00281   }
00282 
00283   // Everything was read successfully
00284   diagnosticsValid_ = true;
00285 
00286 end:
00287   return;
00288 }
00289 
00290 void EthercatDeviceDiagnostics::publish(diagnostic_updater::DiagnosticStatusWrapper &d, unsigned numPorts) const
00291 {
00292   if (numPorts > 4)
00293   {
00294     assert(numPorts < 4);
00295     numPorts = 4;
00296   }
00297   assert(numPorts > 0);
00298 
00299   d.addf("Reset detected", "%s", (resetDetected_ ? "Yes" : "No"));
00300   d.addf("Valid", "%s", (diagnosticsValid_ ? "Yes" : "No"));
00301 
00302   d.addf("EPU Errors", "%lld", epuErrorTotal_);
00303   d.addf("PDI Errors", "%lld", pdiErrorTotal_);
00304   ostringstream os, port;
00305   for (unsigned i = 0; i < numPorts; ++i)
00306   {
00307     const EthercatPortDiagnostics & pt(portDiagnostics_[i]);
00308     port.str("");
00309     port << " Port " << i;
00310     os.str("");
00311     os << "Status" << port.str();
00312     d.addf(os.str(), "%s Link, %s, %s Comm",
00313            pt.hasLink ? "Has" : "No",
00314            pt.isClosed ? "Closed" : "Open",
00315            pt.hasCommunication ? "Has" : "No");
00316     os.str("");
00317     os << "RX Error" << port.str();
00318     d.addf(os.str(), "%lld", pt.rxErrorTotal);
00319     os.str("");
00320     os << "Forwarded RX Error" << port.str();
00321     d.addf(os.str(), "%lld", pt.forwardedRxErrorTotal);
00322     os.str("");
00323     os << "Invalid Frame" << port.str();
00324     d.addf(os.str(), "%lld", pt.invalidFrameTotal);
00325     os.str("");
00326     os << "Lost Link" << port.str();
00327     d.addf(os.str(), "%lld", pt.lostLinkTotal);
00328   }
00329 
00330   if (resetDetected_)
00331   {
00332     d.mergeSummaryf(d.ERROR, "Device reset likely");
00333   }
00334   else if (devicesRespondingToNodeAddress_ > 1)
00335   {
00336     d.mergeSummaryf(d.ERROR, "More than one device (%d) responded to node address", devicesRespondingToNodeAddress_);
00337   }
00338   else
00339   {
00340     if (diagnosticsFirst_)
00341     {
00342       d.mergeSummaryf(d.WARN, "Have not yet collected diagnostics");
00343     }
00344     else if (!diagnosticsValid_)
00345     {
00346       d.mergeSummaryf(d.WARN, "Could not collect diagnostics");
00347     }
00348     else
00349     {
00350       if (!portDiagnostics_[0].hasLink)
00351       {
00352         d.mergeSummaryf(d.WARN, "No link on port 0");
00353       }
00354     }
00355   }
00356 }
00357 
00358 void EthercatDevice::construct(EtherCAT_SlaveHandler *sh, int &start_address)
00359 {
00360   sh_ = sh;
00361   sh->set_fmmu_config(new EtherCAT_FMMU_Config(0));
00362   sh->set_pd_config(new EtherCAT_PD_Config(0));
00363 }
00364 
00365 EthercatDevice::EthercatDevice() : use_ros_(true)
00366 {
00367   sh_ = NULL;
00368   command_size_ = 0;
00369   status_size_ = 0;
00370   newDiagnosticsIndex_ = 0;
00371 
00372   int error = pthread_mutex_init(&newDiagnosticsIndexLock_, NULL);
00373   if (error != 0)
00374   {
00375     ROS_FATAL("Initializing indexLock failed : %s", strerror(error));
00376     sleep(1); // wait for ros to flush rosconsole output
00377     exit(EXIT_FAILURE);
00378   }
00379 
00380   error = pthread_mutex_init(&diagnosticsLock_, NULL);
00381   if (error != 0)
00382   {
00383     ROS_FATAL("Initializing diagnositcsLock failed : %s", strerror(error));
00384     sleep(1); // wait for ros to flush rosconsole output
00385     exit(EXIT_FAILURE);
00386   }
00387 }
00388 
00389 void EthercatDevice::collectDiagnostics(EthercatCom *com)
00390 {
00391   // Really, should not need this lock, since there should only be one thread updating diagnostics.
00392   pthread_mutex_lock(&diagnosticsLock_);
00393 
00394   // Get references to diagnostics... code is easier to read
00395   unsigned oldDiagnosticsIndex = (newDiagnosticsIndex_ + 1)&1;
00396   const EthercatDeviceDiagnostics &newDiag = deviceDiagnostics[newDiagnosticsIndex_];
00397   EthercatDeviceDiagnostics &oldDiag = deviceDiagnostics[oldDiagnosticsIndex];
00398 
00399   // copy new diagnostics values in old diagnostics, because diagnostic data use accumumlators
00400   oldDiag = newDiag;
00401 
00402   // Collect diagnostics data into "old" buffer.
00403   // This way the "new" buffer is never changed while the publishing thread may be using it.
00404   oldDiag.collect(com, sh_);
00405 
00406   // Got new diagnostics... swap buffers.
00407   // Publisher thread uses "new" buffer.  New to lock while swapping buffers.
00408   // Note : this is just changing an integer value, so it only takes a couple of instructions.
00409   pthread_mutex_lock(&newDiagnosticsIndexLock_);
00410   newDiagnosticsIndex_ = oldDiagnosticsIndex;
00411   pthread_mutex_unlock(&newDiagnosticsIndexLock_);
00412 
00413   // Done, unlock
00414   pthread_mutex_unlock(&diagnosticsLock_);
00415 }
00416 
00417 int EthercatDevice::readWriteData(EthercatCom *com, EtherCAT_SlaveHandler *sh, uint16_t address, void* buffer, uint16_t length, AddrMode addrMode)
00418 {
00419   unsigned char *p = (unsigned char *) buffer;
00420   EC_Logic *logic = sh->m_logic_instance;
00421 
00422   NPRW_Telegram nprw_telegram(logic->get_idx(),
00423                               sh->get_station_address(),
00424                               address,
00425                               logic->get_wkc(),
00426                               length,
00427                               p);
00428 
00429   APRW_Telegram aprw_telegram(logic->get_idx(), // Index
00430                               -sh->get_ring_position(), // Slave position on ethercat chain (auto increment address) (
00431                               address, // ESC physical memory address (start address)
00432                               logic->get_wkc(), // Working counter
00433                               length, // Data Length,
00434                               p); // Buffer to put read result into
00435 
00436   // Put read telegram in ros_ethercat_eml/ethernet frame
00437   EC_Telegram * telegram = NULL;
00438   if (addrMode == FIXED_ADDR)
00439   {
00440     telegram = &nprw_telegram;
00441   }
00442   else if (addrMode == POSITIONAL_ADDR)
00443   {
00444     telegram = &aprw_telegram;
00445   }
00446   else
00447   {
00448     assert(0);
00449     return -1;
00450   }
00451 
00452   // Put telegram in ros_ethercat_eml/ethernet frame
00453   EC_Ethernet_Frame frame(telegram);
00454 
00455   // Send/Recv data from slave
00456   if (!com->txandrx_once(&frame))
00457   {
00458     return -1;
00459   }
00460 
00461   // In some cases (clearing status mailbox) this is expected to occur
00462   if (telegram->get_wkc() != 3)
00463   {
00464     return -2;
00465   }
00466 
00467   return 0;
00468 }
00469 
00470 int EthercatDevice::readData(EthercatCom *com, EtherCAT_SlaveHandler *sh, uint16_t address, void* buffer, uint16_t length, AddrMode addrMode)
00471 {
00472   unsigned char *p = (unsigned char *) buffer;
00473   EC_Logic *logic = sh->m_logic_instance;
00474 
00475   NPRD_Telegram nprd_telegram(logic->get_idx(),
00476                               sh->get_station_address(),
00477                               address,
00478                               logic->get_wkc(),
00479                               length,
00480                               p);
00481 
00482   APRD_Telegram aprd_telegram(logic->get_idx(), // Index
00483                               -sh->get_ring_position(), // Slave position on ethercat chain (auto increment address) (
00484                               address, // ESC physical memory address (start address)
00485                               logic->get_wkc(), // Working counter
00486                               length, // Data Length,
00487                               p); // Buffer to put read result into
00488 
00489   // Put read telegram in ros_ethercat_eml/ethernet frame
00490   EC_Telegram * telegram = NULL;
00491   if (addrMode == FIXED_ADDR)
00492   {
00493     telegram = &nprd_telegram;
00494   }
00495   else if (addrMode == POSITIONAL_ADDR)
00496   {
00497     telegram = &aprd_telegram;
00498   }
00499   else
00500   {
00501     assert(0);
00502     return -1;
00503   }
00504 
00505   // Put telegram in ros_ethercat_eml/ethernet frame
00506   EC_Ethernet_Frame frame(telegram);
00507 
00508   // Send/Recv data from slave
00509   if (!com->txandrx(&frame))
00510   {
00511     return -1;
00512   }
00513 
00514   // In some cases (clearing status mailbox) this is expected to occur
00515   if (telegram->get_wkc() != 1)
00516   {
00517     return -2;
00518   }
00519 
00520   return 0;
00521 }
00522 
00523 int EthercatDevice::writeData(EthercatCom *com, EtherCAT_SlaveHandler *sh, uint16_t address, void const* buffer, uint16_t length, AddrMode addrMode)
00524 {
00525   unsigned char const *p = (unsigned char const*) buffer;
00526   EC_Logic *logic = sh->m_logic_instance;
00527 
00528   NPWR_Telegram npwr_telegram(logic->get_idx(),
00529                               sh->get_station_address(),
00530                               address,
00531                               logic->get_wkc(),
00532                               length,
00533                               p);
00534 
00535   APWR_Telegram apwr_telegram(logic->get_idx(), // Index
00536                               -sh->get_ring_position(), // Slave position on ethercat chain (auto increment address) (
00537                               address, // ESC physical memory address (start address)
00538                               logic->get_wkc(), // Working counter
00539                               length, // Data Length,
00540                               p); // Buffer to put read result into
00541 
00542   // Put read telegram in ros_ethercat_eml/ethernet frame
00543   EC_Telegram * telegram = NULL;
00544   if (addrMode == FIXED_ADDR)
00545   {
00546     telegram = &npwr_telegram;
00547   }
00548   else if (addrMode == POSITIONAL_ADDR)
00549   {
00550     telegram = &apwr_telegram;
00551   }
00552   else
00553   {
00554     assert(0);
00555     return -1;
00556   }
00557 
00558   // Put telegram in ros_ethercat_eml/ethernet frame
00559   EC_Ethernet_Frame frame(telegram);
00560 
00561   // Send/Recv data from slave
00562   if (!com->txandrx(&frame))
00563   {
00564     return -1;
00565   }
00566 
00567   if (telegram->get_wkc() != 1)
00568   {
00569     return -2;
00570   }
00571 
00572   return 0;
00573 }
00574 
00575 void EthercatDevice::ethercatDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &d, unsigned numPorts)
00576 {
00577   if (numPorts > 4)
00578   {
00579     assert(numPorts < 4);
00580     numPorts = 4;
00581   }
00582 
00583   // By locking index, diagnostics double-buffer cannot be swapped.
00584   // Update thread is only allowed to change 'old' diagnostics buffer,
00585   //  so new buffer data cannot be changed while index lock is held.
00586   pthread_mutex_lock(&newDiagnosticsIndexLock_);
00587 
00588   const EthercatDeviceDiagnostics &newDiag = deviceDiagnostics[newDiagnosticsIndex_];
00589   newDiag.publish(d, numPorts);
00590 
00591   pthread_mutex_unlock(&newDiagnosticsIndexLock_);
00592 }
00593 
00594 void EthercatDevice::diagnostics(diagnostic_updater::DiagnosticStatusWrapper &d, unsigned char *buffer)
00595 {
00596   stringstream str;
00597   str << "EtherCAT Device (" << std::setw(2) << std::setfill('0') << sh_->get_ring_position() << ")";
00598   d.name = str.str();
00599   str.str("");
00600   str << sh_->get_product_code() << '-' << sh_->get_serial();
00601   d.hardware_id = str.str();
00602 
00603   d.message = "";
00604   d.level = 0;
00605 
00606   d.clear();
00607   d.addf("Position", "%02d", sh_->get_ring_position());
00608   d.addf("Product code", "%08x", sh_->get_product_code());
00609   d.addf("Serial", "%08x", sh_->get_serial());
00610   d.addf("Revision", "%08x", sh_->get_revision());
00611 
00612   this->ethercatDiagnostics(d, 4); //assume unknown device has 4 ports
00613 }
00614 
00615 void EthercatDevice::multiDiagnostics(vector<diagnostic_msgs::DiagnosticStatus> &vec, unsigned char *buffer)
00616 {
00617   // Clean up recycled status object before reusing it.
00618   diagnostic_status_.clearSummary();
00619   diagnostic_status_.clear();
00620 
00621   // If child-class does not implement multiDiagnostics(), fall back to using slave's diagnostic() function
00622   diagnostics(diagnostic_status_, buffer);
00623   vec.push_back(diagnostic_status_);
00624 }


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