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