wg0x.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2008, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 #include <iomanip>
36 
37 #include <math.h>
38 #include <stddef.h>
39 
40 #include <ethercat_hardware/wg0x.h>
41 
42 #include <dll/ethercat_dll.h>
43 #include <al/ethercat_AL.h>
44 #include <dll/ethercat_device_addressed_telegram.h>
45 #include <dll/ethercat_frame.h>
46 
47 #include <boost/crc.hpp>
48 #include <boost/shared_ptr.hpp>
49 #include <boost/static_assert.hpp>
50 #include <boost/make_shared.hpp>
51 
52 // Temporary,, need 'log' fuction that can switch between fprintf and ROS_LOG.
53 #define ERR_MODE "\033[41m"
54 #define STD_MODE "\033[0m"
55 #define WARN_MODE "\033[43m"
56 #define GOOD_MODE "\033[42m"
57 #define INFO_MODE "\033[44m"
58 
59 #define ERROR_HDR "\033[41mERROR\033[0m"
60 #define WARN_HDR "\033[43mERROR\033[0m"
61 
63 
64 
66  first_(true),
67  valid_(false),
68  safety_disable_total_(0),
69  undervoltage_total_(0),
70  over_current_total_(0),
71  board_over_temp_total_(0),
72  bridge_over_temp_total_(0),
73  operate_disable_total_(0),
74  watchdog_disable_total_(0),
75  lock_errors_(0),
76  checksum_errors_(0),
77  zero_offset_(0),
78  cached_zero_offset_(0)
79 {
81  memset(&diagnostics_info_, 0, sizeof(diagnostics_info_));
82 }
83 
90 void WG0XDiagnostics::update(const WG0XSafetyDisableStatus &new_status, const WG0XDiagnosticsInfo &new_diagnostics_info)
91 {
92  first_ = false;
94  {
95  const WG0XSafetyDisableCounters &new_counters(new_diagnostics_info.safety_disable_counters_);
97  undervoltage_total_ += 0xFF & ((uint32_t)(new_counters.undervoltage_count_ - old_counters.undervoltage_count_));
98  over_current_total_ += 0xFF & ((uint32_t)(new_counters.over_current_count_ - old_counters.over_current_count_));
99  board_over_temp_total_ += 0xFF & ((uint32_t)(new_counters.board_over_temp_count_ - old_counters.board_over_temp_count_));
100  bridge_over_temp_total_ += 0xFF & ((uint32_t)(new_counters.bridge_over_temp_count_ - old_counters.bridge_over_temp_count_));
101  operate_disable_total_ += 0xFF & ((uint32_t)(new_counters.operate_disable_count_ - old_counters.operate_disable_count_));
102  watchdog_disable_total_ += 0xFF & ((uint32_t)(new_counters.watchdog_disable_count_ - old_counters.watchdog_disable_count_));
103  }
104 
105  safety_disable_status_ = new_status;
106  diagnostics_info_ = new_diagnostics_info;
107 }
108 
109 
132 {
133  // Actuator info contains two CRCs
134  BOOST_STATIC_ASSERT(sizeof(WG0XActuatorInfo) == 264);
135  BOOST_STATIC_ASSERT( offsetof(WG0XActuatorInfo, crc32_256_) == (256-4));
136  BOOST_STATIC_ASSERT( offsetof(WG0XActuatorInfo, crc32_264_) == (264-4));
137  boost::crc_32_type crc32_256, crc32_264;
138  crc32_256.process_bytes(this, offsetof(WG0XActuatorInfo, crc32_256_));
139  crc32_264.process_bytes(this, offsetof(WG0XActuatorInfo, crc32_264_));
140  return ((this->crc32_264_ == crc32_264.checksum()) || (this->crc32_256_ == crc32_256.checksum()));
141 }
142 
147 {
148  boost::crc_32_type crc32;
149  crc32.process_bytes(this, offsetof(WG0XActuatorInfo, crc32_256_));
150  this->crc32_256_ = crc32.checksum();
151  crc32.reset();
152  crc32.process_bytes(this, offsetof(WG0XActuatorInfo, crc32_264_));
153  this->crc32_264_ = crc32.checksum();
154 }
155 
156 
158  max_current_(0.0),
159  too_many_dropped_packets_(false),
160  status_checksum_error_(false),
161  timestamp_jump_detected_(false),
162  fpga_internal_reset_detected_(false),
163  encoder_errors_detected_(false),
165  calibration_status_(NO_CALIBRATION),
166  app_ram_status_(APP_RAM_MISSING),
167  motor_model_(NULL),
168  disable_motor_model_checking_(false)
169 {
170 
171  last_timestamp_ = 0;
173  drops_ = 0;
174  consecutive_drops_ = 0;
178  in_lockout_ = false;
179  resetting_ = false;
180  has_error_ = false;
181 
182  int error;
183  if ((error = pthread_mutex_init(&wg0x_diagnostics_lock_, NULL)) != 0)
184  {
185  ROS_ERROR("WG0X : init diagnostics mutex :%s", strerror(error));
186  }
187 
188 }
189 
191 {
192  delete sh_->get_fmmu_config();
193  delete sh_->get_pd_config();
194  delete motor_model_;
195 }
196 
197 
198 void WG0X::construct(EtherCAT_SlaveHandler *sh, int &start_address)
199 {
200  EthercatDevice::construct(sh, start_address);
201 
202  // WG EtherCAT devices (WG05,WG06,WG21) revisioning scheme
203  fw_major_ = (sh->get_revision() >> 8) & 0xff;
204  fw_minor_ = sh->get_revision() & 0xff;
205  board_major_ = ((sh->get_revision() >> 24) & 0xff) - 1;
206  board_minor_ = (sh->get_revision() >> 16) & 0xff;
207 
208  // Would normally configure EtherCAT initialize EtherCAT communication settings here.
209  // However, since all WG devices are slightly different doesn't make sense to do it here.
210  // Instead make sub-classes handle this.
211 }
212 
213 
220 void WG0X::copyActuatorInfo(ethercat_hardware::ActuatorInfo &out, const WG0XActuatorInfo &in)
221 {
222  out.id = in.id_;
223  out.name = std::string(in.name_);
224  out.robot_name = in.robot_name_;
225  out.motor_make = in.motor_make_;
226  out.motor_model = in.motor_model_;
227  out.max_current = in.max_current_;
228  out.speed_constant = in.speed_constant_;
229  out.motor_resistance = in.resistance_;
230  out.motor_torque_constant = in.motor_torque_constant_;
231  out.encoder_reduction = in.encoder_reduction_;
232  out.pulses_per_revolution = in.pulses_per_revolution_;
233 }
234 
235 
239  const string &device_description,
240  double max_pwm_ratio,
241  double board_resistance,
242  bool poor_measured_motor_voltage)
243 {
244  if (!hw)
245  return true;
246 
247  motor_model_ = new MotorModel(1000);
248  if (motor_model_ == NULL)
249  return false;
250 
251  const ethercat_hardware::ActuatorInfo &ai(actuator_info_msg_);
252 
253  unsigned product_code = sh_->get_product_code();
254  ethercat_hardware::BoardInfo bi;
255  bi.description = device_description;
256  bi.product_code = product_code;
257  bi.pcb = board_major_;
258  bi.pca = board_minor_;
259  bi.serial = sh_->get_serial();
260  bi.firmware_major = fw_major_;
261  bi.firmware_minor = fw_minor_;
262  bi.board_resistance = board_resistance;
263  bi.max_pwm_ratio = max_pwm_ratio;
265  bi.poor_measured_motor_voltage = poor_measured_motor_voltage;
266 
267  if (!motor_model_->initialize(ai,bi))
268  return false;
269 
270  // Create digital out that can be used to force trigger of motor trace
271  publish_motor_trace_.name_ = string(actuator_info_.name_) + "_publish_motor_trace";
274  if (!hw->addDigitalOut(&publish_motor_trace_)) {
275  ROS_FATAL("A digital out of the name '%s' already exists", publish_motor_trace_.name_.c_str());
276  return false;
277  }
278 
279  // When working with experimental setups we don't want motor model to halt motors when it detects a problem.
280  // Allow rosparam to disable motor model halting for a specific motor.
281  if (!ros::param::get("~/" + ai.name + "/disable_motor_model_checking", disable_motor_model_checking_))
282  {
284  }
286  {
287  ROS_WARN("Disabling motor model on %s", ai.name.c_str());
288  }
289 
290  return true;
291 }
292 
293 
295 
296 bool WG0X::initializeMotorHeatingModel(bool allow_unprogrammed)
297 {
298 
299  EthercatDirectCom com(EtherCAT_DataLinkLayer::instance());
302  {
303  ROS_FATAL("Unable to read motor heating model config parameters from EEPROM");
304  return false;
305  }
306 
307  // All devices need to have motor model heating model parameters stored in them...
308  // Even if device doesn't use paramers, they should be there.
309  if (!config.verifyCRC())
310  {
311  if (allow_unprogrammed)
312  {
313  ROS_WARN("%s EEPROM does not contain motor heating model parameters",
315  return true;
316  }
317  else
318  {
319  ROS_WARN("%s EEPROM does not contain motor heating model parameters",
321  return true;
322  // TODO: once there is ability to update all MCB iwth motorconf, this is will become a fatal error
323  ROS_FATAL("%s EEPROM does not contain motor heating model parameters",
325  return false;
326  }
327  }
328 
329  // Even though all devices should contain motor heating model parameters,
330  // The heating model does not need to be used.
331  if (config.enforce_ == 0)
332  {
333  return true;
334  }
335 
336  // Don't need motor model if we are not using ROS (motorconf)
337  if (!use_ros_)
338  {
339  return true;
340  }
341 
342  // Generate hwid for motor model
343  std::ostringstream hwid;
344  hwid << unsigned(sh_->get_product_code()) << std::setw(5) << std::setfill('0') << unsigned(sh_->get_serial());
345 
346  // All motor heating models use shared settings structure
347  if (motor_heating_model_common_.get() == NULL)
348  {
349  ros::NodeHandle nh("~motor_heating_model");
350  motor_heating_model_common_ = boost::make_shared<ethercat_hardware::MotorHeatingModelCommon>(nh);
351  motor_heating_model_common_->initialize();
352  // Only display following warnings once.
353  if (!motor_heating_model_common_->enable_model_)
354  {
355  ROS_WARN("Motor heating model disabled for all devices");
356  }
357  if (!motor_heating_model_common_->load_save_files_)
358  {
359  ROS_WARN("Not loading motor heating model files");
360  }
361  if (!motor_heating_model_common_->update_save_files_)
362  {
363  ROS_WARN("Not saving motor heating model files");
364  }
365  }
366 
367  if (!motor_heating_model_common_->enable_model_)
368  {
369  return true;
370  }
371 
373  boost::make_shared<ethercat_hardware::MotorHeatingModel>(config.params_,
375  hwid.str(),
376  motor_heating_model_common_->save_directory_);
377  // have motor heating model load last saved temperaures from filesystem
378  if (motor_heating_model_common_->load_save_files_)
379  {
380  if (!motor_heating_model_->loadTemperatureState())
381  {
382  ROS_WARN("Could not load motor temperature state for %s", actuator_info_.name_);
383  }
384  }
385  if (motor_heating_model_common_->publish_temperature_)
386  {
387  motor_heating_model_->startTemperaturePublisher();
388  }
390 
391  return true;
392 }
393 
394 
396 {
397  ROS_DEBUG("Device #%02d: WG0%d (%#08x) Firmware Revision %d.%02d, PCB Revision %c.%02d, Serial #: %d",
398  sh_->get_ring_position(),
399  sh_->get_product_code() % 100,
400  sh_->get_product_code(), fw_major_, fw_minor_,
401  'A' + board_major_, board_minor_,
402  sh_->get_serial());
403 
404  EthercatDirectCom com(EtherCAT_DataLinkLayer::instance());
405 
407 
408  if (sh_->get_product_code() == WG05_PRODUCT_CODE)
409  {
410  if (fw_major_ != 1 || fw_minor_ < 7)
411  {
412  ROS_FATAL("Unsupported firmware revision %d.%02d", fw_major_, fw_minor_);
413  return -1;
414  }
415  }
416  else
417  {
418  if ((fw_major_ == 0 && fw_minor_ < 4) /*|| (fw_major_ == 1 && fw_minor_ < 0)*/)
419  {
420  ROS_FATAL("Unsupported firmware revision %d.%02d", fw_major_, fw_minor_);
421  return -1;
422  }
423  }
424 
426  {
427  ROS_FATAL("Unable to load configuration information");
428  return -1;
429  }
430  ROS_DEBUG(" Serial #: %05d", config_info_.device_serial_number_);
431  double board_max_current = double(config_info_.absolute_current_limit_) * config_info_.nominal_current_scale_;
432 
434  {
435  ROS_FATAL("Unable to read actuator info from EEPROM");
436  return -1;
437  }
438 
440  {
441  if (actuator_info_.major_ != 0 || actuator_info_.minor_ != 2)
442  {
443  if (allow_unprogrammed)
444  ROS_WARN("Unsupported actuator info version (%d.%d != 0.2). Please reprogram device #%02d", actuator_info_.major_, actuator_info_.minor_, sh_->get_ring_position());
445  else
446  {
447  ROS_FATAL("Unsupported actuator info version (%d.%d != 0.2). Please reprogram device #%02d", actuator_info_.major_, actuator_info_.minor_, sh_->get_ring_position());
448  return -1;
449  }
450  }
451 
453  ROS_DEBUG(" Name: %s", actuator_info_.name_);
454 
455  // Copy actuator info read from eeprom, into msg type
457 
458  if (!initializeMotorHeatingModel(allow_unprogrammed))
459  {
460  return -1;
461  }
462 
463 
464  bool isWG021 = sh_->get_product_code() == WG021_PRODUCT_CODE;
465  if (!isWG021)
466  {
467  // Register actuator with pr2_hardware_interface::HardwareInterface
468  if (hw && !hw->addActuator(&actuator_))
469  {
470  ROS_FATAL("An actuator of the name '%s' already exists. Device #%02d has a duplicate name", actuator_.name_.c_str(), sh_->get_ring_position());
471  return -1;
472  }
473 
474  }
475 
476  // Register digital out with pr2_hardware_interface::HardwareInterface
478  if (hw && !hw->addDigitalOut(&digital_out_))
479  {
480  ROS_FATAL("A digital out of the name '%s' already exists. Device #%02d has a duplicate name", digital_out_.name_.c_str(), sh_->get_ring_position());
481  return -1;
482  }
483 
484  // If it is supported, read application ram data.
486  {
487  double zero_offset;
488  if (readAppRam(&com, zero_offset))
489  {
490  ROS_DEBUG("Read calibration from device %s: %f", actuator_info_.name_, zero_offset);
491  actuator_.state_.zero_offset_ = zero_offset;
492  cached_zero_offset_ = zero_offset;
494  }
495  else
496  {
497  ROS_DEBUG("No calibration offset was stored on device %s", actuator_info_.name_);
498  }
499  }
500  else if (app_ram_status_ == APP_RAM_MISSING)
501  {
502  ROS_WARN("Device %s does not support storing calibration offsets", actuator_info_.name_);
503  }
505  {
506  // don't produce warning
507  }
508 
509  // Make sure motor current limit is less than board current limit
510  if (actuator_info_.max_current_ > board_max_current)
511  {
512  ROS_WARN("WARNING: Device #%02d : motor current limit (%f) greater than board current limit (%f)",
513  sh_->get_ring_position(), actuator_info_.max_current_, board_max_current);
514  }
515  max_current_ = std::min(board_max_current, actuator_info_.max_current_);
516  }
517  else if (allow_unprogrammed)
518  {
519  ROS_WARN("WARNING: Device #%02d (%d%05d) is not programmed",
520  sh_->get_ring_position(), sh_->get_product_code(), sh_->get_serial());
521  //actuator_info_.crc32_264_ = 0;
522  //actuator_info_.crc32_256_ = 0;
523 
524  max_current_ = board_max_current;
525  }
526  else
527  {
528  ROS_FATAL("Device #%02d (%d%05d) is not programmed, aborting...",
529  sh_->get_ring_position(), sh_->get_product_code(), sh_->get_serial());
530  return -1;
531  }
532 
533  return 0;
534 }
535 
536 #define GET_ATTR(a) \
537 { \
538  TiXmlElement *c; \
539  attr = elt->Attribute((a)); \
540  if (!attr) { \
541  c = elt->FirstChildElement((a)); \
542  if (!c || !(attr = c->GetText())) { \
543  ROS_FATAL("Actuator is missing the attribute "#a); \
544  exit(EXIT_FAILURE); \
545  } \
546  } \
547 }
548 
550 {
551  has_error_ = false;
553  status_checksum_error_ = false;
554  timestamp_jump_detected_ = false;
555  encoder_errors_detected_ = false;
557  if (motor_heating_model_.get() != NULL)
558  {
559  motor_heating_model_->reset();
560  }
561 }
562 
563 void WG0X::packCommand(unsigned char *buffer, bool halt, bool reset)
564 {
566 
567  if (halt)
568  {
569  cmd.effort_ = 0;
570  }
571 
572  if (reset)
573  {
574  clearErrorFlags();
575  }
576  resetting_ = reset;
577 
578  // If zero_offset was changed, give it to non-realtime thread
579  double zero_offset = actuator_.state_.zero_offset_;
580  if (zero_offset != cached_zero_offset_)
581  {
583  {
584  ROS_DEBUG("Calibration change of %s, new %f, old %f", actuator_info_.name_, zero_offset, cached_zero_offset_);
585  cached_zero_offset_ = zero_offset;
589  }
590  else
591  {
592  // It is OK if trylock failed, this will still try again next cycle.
593  }
594  }
595 
596  // Compute the current
600 
601  // Truncate the current to limit
602  current = max(min(current, max_current_), -max_current_);
603 
604  // Pack command structures into EtherCAT buffer
605  WG0XCommand *c = (WG0XCommand *)buffer;
606  memset(c, 0, command_size_);
608  c->mode_ = (cmd.enable_ && !halt && !has_error_) ? (MODE_ENABLE | MODE_CURRENT) : MODE_OFF;
609  c->mode_ |= (reset ? MODE_SAFETY_RESET : 0);
612 }
613 
614 bool WG0X::unpackState(unsigned char *this_buffer, unsigned char *prev_buffer)
615 {
617  WG0XStatus *this_status, *prev_status;
618 
619  this_status = (WG0XStatus *)(this_buffer + command_size_);
620  prev_status = (WG0XStatus *)(prev_buffer + command_size_);
621 
622  digital_out_.state_.data_ = this_status->digital_out_;
623 
624  // Do not report timestamp directly to controllers because 32bit integer
625  // value in microseconds will overflow every 72 minutes.
626  // Instead a accumulate small time differences into a ros::Duration variable
627  int32_t timediff = WG0X::timestampDiff(this_status->timestamp_, prev_status->timestamp_);
629  state.sample_timestamp_ = sample_timestamp_; //ros::Duration is preferred source of time for controllers
630  state.timestamp_ = sample_timestamp_.toSec(); //double value is for backwards compatibility
631 
632  state.device_id_ = sh_->get_ring_position();
633 
634  state.encoder_count_ = this_status->encoder_count_;
635  state.position_ = double(this_status->encoder_count_) / actuator_info_.pulses_per_revolution_ * 2 * M_PI - state.zero_offset_;
636 
637  state.encoder_velocity_ =
638  calcEncoderVelocity(this_status->encoder_count_, this_status->timestamp_,
639  prev_status->encoder_count_, prev_status->timestamp_);
641 
647  state.is_enabled_ = bool(this_status->mode_ & MODE_ENABLE);
648 
651 
654 
655  state.num_encoder_errors_ = this_status->num_encoder_errors_;
656 
658 
660 
661  return verifyState(this_status, prev_status);
662 }
663 
664 
665 bool WG0X::verifyChecksum(const void* buffer, unsigned size)
666 {
667  bool success = wg_util::computeChecksum(buffer, size) == 0;
668  if (!success) {
669  if (tryLockWG0XDiagnostics()) {
672  }
673  }
674  return success;
675 }
676 
677 
678 
685 int32_t WG0X::timestampDiff(uint32_t new_timestamp, uint32_t old_timestamp)
686 {
687  return int32_t(new_timestamp - old_timestamp);
688 }
689 
697 {
698  static const int USEC_PER_SEC = 1000000;
699  int sec = timediff_usec / USEC_PER_SEC;
700  int nsec = (timediff_usec % USEC_PER_SEC)*1000;
701  return ros::Duration(sec,nsec);
702 }
703 
704 
710 int32_t WG0X::positionDiff(int32_t new_position, int32_t old_position)
711 {
712  return int32_t(new_position - old_position);
713 }
714 
721 double WG0X::calcEncoderVelocity(int32_t new_position, uint32_t new_timestamp,
722  int32_t old_position, uint32_t old_timestamp)
723 {
724  double timestamp_diff = double(timestampDiff(new_timestamp, old_timestamp)) * 1e-6;
725  double position_diff = double(positionDiff(new_position, old_position));
726  return (position_diff / timestamp_diff);
727 }
728 
729 
736 double WG0X::convertRawTemperature(int16_t raw_temp)
737 {
738  return 0.0078125 * double(raw_temp);
739 }
740 
741 
742 // Returns true if timestamp changed by more than (amount) or time goes in reverse.
743 bool WG0X::timestamp_jump(uint32_t timestamp, uint32_t last_timestamp, uint32_t amount)
744 {
745  uint32_t timestamp_diff = (timestamp - last_timestamp);
746  return (timestamp_diff > amount);
747 }
748 
749 bool WG0X::verifyState(WG0XStatus *this_status, WG0XStatus *prev_status)
750 {
752  bool rv = true;
753 
754  if ((motor_model_ != NULL) || (motor_heating_model_ != NULL))
755  {
756  // Both motor model and motor heating model use MotorTraceSample
757  ethercat_hardware::MotorTraceSample &s(motor_trace_sample_);
758  double last_executed_current = this_status->programmed_current_ * config_info_.nominal_current_scale_;
759  double supply_voltage = double(prev_status->supply_voltage_) * config_info_.nominal_voltage_scale_;
760  double pwm_ratio = double(this_status->programmed_pwm_value_) / double(PWM_MAX);
761  s.timestamp = state.timestamp_;
762  s.enabled = state.is_enabled_;
763  s.supply_voltage = supply_voltage;
764  s.measured_motor_voltage = state.motor_voltage_;
765  s.programmed_pwm = pwm_ratio;
766  s.executed_current = last_executed_current;
767  s.measured_current = state.last_measured_current_;
768  s.velocity = state.velocity_;
769  s.encoder_position = state.position_;
770  s.encoder_error_count = state.num_encoder_errors_;
771 
772  if (motor_model_ != NULL)
773  {
774  // Collect data for motor model
775  motor_model_->sample(s);
777  }
778  if (motor_heating_model_ != NULL)
779  {
780  double ambient_temperature = convertRawTemperature(this_status->board_temperature_);
781  double duration = double(timestampDiff(this_status->timestamp_, prev_status->timestamp_)) * 1e-6;
782  motor_heating_model_->update(s, actuator_info_msg_, ambient_temperature, duration);
783 
784  if ((!motor_heating_model_common_->disable_halt_) && (motor_heating_model_->hasOverheated()))
785  {
786  rv = false;
787  }
788  }
789  }
790 
793 
794  if (this_status->timestamp_ == last_timestamp_ ||
795  this_status->timestamp_ == last_last_timestamp_) {
796  ++drops_;
799  } else {
800  consecutive_drops_ = 0;
801  }
802  // Detect timestamps going in reverse or changing by more than 10 seconds = 10,000,000 usec
803  if ( timestamp_jump(this_status->timestamp_,last_timestamp_,10000000) )
804  {
806  }
808  last_timestamp_ = this_status->timestamp_;
809 
810  if (consecutive_drops_ > 10)
811  {
813  rv = false;
814  goto end;
815  }
816 
817  in_lockout_ = bool(this_status->mode_ & MODE_SAFETY_LOCKOUT);
818  if (in_lockout_ && !resetting_)
819  {
820  rv = false;
821  goto end;
822  }
823 
825  {
826  rv = false;
827  goto end;
828  }
829 
830  if (this_status->num_encoder_errors_ != prev_status->num_encoder_errors_)
831  {
833  }
834 
835  if (state.is_enabled_ && motor_model_)
836  {
838  {
839  if(!motor_model_->verify())
840  {
841  // Motor model will automatically publish a motor trace when there is an error
842  rv = false;
843  goto end;
844  }
845  }
846  }
847 
848 end:
849  if (motor_model_)
850  {
851  // Publish trace when:
852  // * device goes into safety lockout
853  // * controller request motor trace to be published
854  bool new_error = in_lockout_ && !resetting_ && !has_error_;
855  if (new_error || publish_motor_trace_.command_.data_)
856  {
857  const char* reason = "Publishing manually triggered";
858  if (new_error)
859  {
860  bool undervoltage = (this_status->mode_ & MODE_UNDERVOLTAGE);
861  reason = (undervoltage) ? "Undervoltage Lockout" : "Safety Lockout";
862  }
863  int level = (new_error) ? 2 : 0;
864  motor_model_->flagPublish(reason, level , 100);
866  }
867  }
868  bool is_error = !rv;
869  has_error_ = is_error || has_error_;
870  actuator_.state_.halted_ = has_error_ || this_status->mode_ == MODE_OFF;
871  return rv;
872 }
873 
874 bool WG0X::publishTrace(const string &reason, unsigned level, unsigned delay)
875 {
876  if (motor_model_)
877  {
878  motor_model_->flagPublish(reason, level, delay);
879  return true;
880  }
881  return false;
882 }
883 
884 
886 {
887  //Collect safety disable information through mailbox
888  bool success = false;
889 
890  // Have parent collect diagnositcs
892 
893  // Send a packet with both a Fixed address read (NPRW) to device to make sure it is present in chain.
894  // This avoids wasting time trying to read mailbox of device that it not present on chain.
895  {
896  EC_Logic *logic = EC_Logic::instance();
897  unsigned char buf[1];
898  EC_UINT address = 0x0000;
899  NPRD_Telegram nprd_telegram(logic->get_idx(),
900  sh_->get_station_address(),
901  address,
902  0 /*working counter*/,
903  sizeof(buf),
904  buf);
905  EC_Ethernet_Frame frame(&nprd_telegram);
906  if (!com->txandrx_once(&frame)) {
907  // packet didn't come back
908  goto end;
909  }
910  if (nprd_telegram.get_wkc() != 1) {
911  // packet came back, but device didn't not respond
912  goto end;
913  }
914  }
915 
917  if (readMailbox(com, s.BASE_ADDR, &s, sizeof(s)) != 0) {
918  goto end;
919  }
920 
922  if (readMailbox(com, di.BASE_ADDR, &di, sizeof(di)) != 0) {
923  goto end;
924  }
925 
926  { // Try writing zero offset to to WG0X devices that have application ram
928 
930  {
931  if (writeAppRam(com, dg.zero_offset_)){
932  ROS_DEBUG("Writing new calibration to device %s, new %f, old %f", actuator_info_.name_, dg.zero_offset_, dg.cached_zero_offset_);
934  }
935  else{
936  ROS_ERROR("Failed to write new calibration to device %s, new %f, old %f", actuator_info_.name_, dg.zero_offset_, dg.cached_zero_offset_);
937  // Diagnostics thread will try again next update cycle
938  }
939  }
940  }
941 
942  success = true;
943 
944  end:
945  if (!lockWG0XDiagnostics()) {
946  wg0x_collect_diagnostics_.valid_ = false; // change these values even if we did't get the lock
948  return;
949  }
950 
952  if (success) {
954  }
955 
957 }
958 
959 
960 bool WG0X::writeAppRam(EthercatCom *com, double zero_offset)
961 {
962  WG0XUserConfigRam cfg;
963  cfg.version_ = 1;
964  cfg.zero_offset_ = zero_offset;
965  boost::crc_32_type crc32;
966  crc32.process_bytes(&cfg, sizeof(cfg)-sizeof(cfg.crc32_));
967  cfg.crc32_ = crc32.checksum();
968  return (writeMailbox(com, WG0XUserConfigRam::BASE_ADDR, &cfg, sizeof(cfg)) == 0);
969 }
970 
971 bool WG0X::readAppRam(EthercatCom *com, double &zero_offset)
972 {
973  WG0XUserConfigRam cfg;
974  if (!readMailbox(com, WG0XUserConfigRam::BASE_ADDR, &cfg, sizeof(cfg)) == 0)
975  {
976  return false;
977  }
978  if (cfg.version_ != 1)
979  {
980  return false;
981  }
982  boost::crc_32_type crc32;
983  crc32.process_bytes(&cfg, sizeof(cfg)-sizeof(cfg.crc32_));
984  if (cfg.crc32_ != crc32.checksum()) {
985  return false;
986  }
987  zero_offset = cfg.zero_offset_;
988  return true;
989 }
990 
991 
1000 {
1001  BOOST_STATIC_ASSERT(sizeof(actuator_info) == 264);
1002 
1003  if (!eeprom_.readEepromPage(com, &mailbox_, ACTUATOR_INFO_PAGE, &actuator_info, sizeof(actuator_info)))
1004  {
1005  ROS_ERROR("Reading acutuator info from eeprom");
1006  return false;
1007  }
1008  return true;
1009 }
1010 
1019 {
1020  BOOST_STATIC_ASSERT(sizeof(config) == 256);
1021 
1022  if (!eeprom_.readEepromPage(com, &mailbox_, config.EEPROM_PAGE, &config, sizeof(config)))
1023  {
1024  ROS_ERROR("Reading motor heating model config from eeprom");
1025  return false;
1026  }
1027  return true;
1028 }
1029 
1030 
1031 
1032 
1051 bool WG0X::program(EthercatCom *com, const WG0XActuatorInfo &actutor_info)
1052 {
1053  if (!eeprom_.writeEepromPage(com, &mailbox_, ACTUATOR_INFO_PAGE, &actutor_info, sizeof(actutor_info)))
1054  {
1055  ROS_ERROR("Writing actuator infomation to EEPROM");
1056  return false;
1057  }
1058 
1059  return true;
1060 }
1061 
1062 
1078 {
1079  if (!eeprom_.writeEepromPage(com, &mailbox_, heating_config.EEPROM_PAGE, &heating_config, sizeof(heating_config)))
1080  {
1081  ROS_ERROR("Writing motor heating model configuration to EEPROM");
1082  return false;
1083  }
1084 
1085  return true;
1086 }
1087 
1088 
1102 int WG0X::readMailbox(EthercatCom *com, unsigned address, void *data, unsigned length)
1103 {
1104  return mailbox_.readMailbox(com, address, data, length);
1105 }
1106 
1108 {
1109  int error = pthread_mutex_lock(&wg0x_diagnostics_lock_);
1110  if (error != 0) {
1111  fprintf(stderr, "%s : " ERROR_HDR " getting diagnostics lock\n", __func__);
1112  // update error counters even if we didn't get lock
1114  return false;
1115  }
1116  return true;
1117 }
1118 
1120 {
1121  int error = pthread_mutex_trylock(&wg0x_diagnostics_lock_);
1122  if (error == EBUSY) {
1123  return false;
1124  }
1125  else if (error != 0) {
1126  fprintf(stderr, "%s : " ERROR_HDR " getting diagnostics lock\n", __func__);
1127  // update error counters even if we didn't get lock
1129  return false;
1130  }
1131  return true;
1132 }
1133 
1135 {
1136  int error = pthread_mutex_unlock(&wg0x_diagnostics_lock_);
1137  if (error != 0) {
1138  fprintf(stderr, "%s : " ERROR_HDR " freeing diagnostics lock\n", __func__);
1140  }
1141 }
1142 
1143 
1156 int WG0X::writeMailbox(EthercatCom *com, unsigned address, void const *data, unsigned length)
1157 {
1158  return mailbox_.writeMailbox(com,address,data,length);
1159 }
1160 
1161 
1162 
1163 #define CHECK_SAFETY_BIT(bit) \
1164  do { if (status & SAFETY_##bit) { \
1165  str += prefix + #bit; \
1166  prefix = ", "; \
1167  } } while(0)
1168 
1170 {
1171  string str, prefix;
1172 
1173  if (status & SAFETY_DISABLED)
1174  {
1175  CHECK_SAFETY_BIT(DISABLED);
1176  CHECK_SAFETY_BIT(UNDERVOLTAGE);
1177  CHECK_SAFETY_BIT(OVER_CURRENT);
1178  CHECK_SAFETY_BIT(BOARD_OVER_TEMP);
1179  CHECK_SAFETY_BIT(HBRIDGE_OVER_TEMP);
1180  CHECK_SAFETY_BIT(OPERATIONAL);
1181  CHECK_SAFETY_BIT(WATCHDOG);
1182  }
1183  else
1184  str = "ENABLED";
1185 
1186  return str;
1187 }
1188 
1189 string WG0X::modeString(uint8_t mode)
1190 {
1191  string str, prefix;
1192  if (mode) {
1193  if (mode & MODE_ENABLE) {
1194  str += prefix + "ENABLE";
1195  prefix = ", ";
1196  }
1197  if (mode & MODE_CURRENT) {
1198  str += prefix + "CURRENT";
1199  prefix = ", ";
1200  }
1201  if (mode & MODE_UNDERVOLTAGE) {
1202  str += prefix + "UNDERVOLTAGE";
1203  prefix = ", ";
1204  }
1205  if (mode & MODE_SAFETY_RESET) {
1206  str += prefix + "SAFETY_RESET";
1207  prefix = ", ";
1208  }
1209  if (mode & MODE_SAFETY_LOCKOUT) {
1210  str += prefix + "SAFETY_LOCKOUT";
1211  prefix = ", ";
1212  }
1213  if (mode & MODE_RESET) {
1214  str += prefix + "RESET";
1215  prefix = ", ";
1216  }
1217  } else {
1218  str = "OFF";
1219  }
1220  return str;
1221 }
1222 
1224 {
1225  // If possible, copy new diagnositics from collection thread, into diagnostics thread
1226  if (tryLockWG0XDiagnostics()) {
1229  }
1230 
1232  {
1233  d.mergeSummary(d.ERROR, "Too many dropped packets");
1234  }
1235 
1237  {
1238  d.mergeSummary(d.ERROR, "Checksum error on status data");
1239  }
1240 
1242  {
1243  d.mergeSummary(d.WARN, "Have not yet collected WG0X diagnostics");
1244  }
1245  else if (!wg0x_publish_diagnostics_.valid_)
1246  {
1247  d.mergeSummary(d.WARN, "Could not collect WG0X diagnostics");
1248  }
1249 
1252  d.addf("Status Checksum Error Count", "%d", p.checksum_errors_);
1253  d.addf("Safety Disable Status", "%s (%02x)", safetyDisableString(s.safety_disable_status_).c_str(), s.safety_disable_status_);
1254  d.addf("Safety Disable Status Hold", "%s (%02x)", safetyDisableString(s.safety_disable_status_hold_).c_str(), s.safety_disable_status_hold_);
1255  d.addf("Safety Disable Count", "%d", p.safety_disable_total_);
1256  d.addf("Undervoltage Count", "%d", p.undervoltage_total_);
1257  d.addf("Over Current Count", "%d", p.over_current_total_);
1258  d.addf("Board Over Temp Count", "%d", p.board_over_temp_total_);
1259  d.addf("Bridge Over Temp Count", "%d", p.bridge_over_temp_total_);
1260  d.addf("Operate Disable Count", "%d", p.operate_disable_total_);
1261  d.addf("Watchdog Disable Count", "%d", p.watchdog_disable_total_);
1262 
1263  if (in_lockout_)
1264  {
1265  uint8_t status = s.safety_disable_status_hold_;
1266  string prefix(": ");
1267  string str("Safety Lockout");
1268  CHECK_SAFETY_BIT(UNDERVOLTAGE);
1269  CHECK_SAFETY_BIT(OVER_CURRENT);
1270  CHECK_SAFETY_BIT(BOARD_OVER_TEMP);
1271  CHECK_SAFETY_BIT(HBRIDGE_OVER_TEMP);
1272  CHECK_SAFETY_BIT(OPERATIONAL);
1273  CHECK_SAFETY_BIT(WATCHDOG);
1274  d.mergeSummary(d.ERROR, str);
1275  }
1276 
1278  {
1280  }
1281 
1283  {
1284  d.mergeSummaryf(d.ERROR, "FPGA internal reset detected");
1285  }
1286 
1288  {
1289  d.mergeSummaryf(d.WARN, "Timestamp jumped");
1290  }
1291 
1292  {
1293 
1295  //d.addf("PDO Command IRQ Count", "%d", di.pdo_command_irq_count_);
1296  d.addf("MBX Command IRQ Count", "%d", di.mbx_command_irq_count_);
1297  d.addf("PDI Timeout Error Count", "%d", di.pdi_timeout_error_count_);
1298  d.addf("PDI Checksum Error Count", "%d", di.pdi_checksum_error_count_);
1299  unsigned product = sh_->get_product_code();
1300 
1301  // Current scale
1302  if ((product == WG05_PRODUCT_CODE) && (board_major_ == 1))
1303  {
1304  // WG005B measure current going into and out-of H-bridge (not entire board)
1305  static const double WG005B_SUPPLY_CURRENT_SCALE = (1.0 / (8152.0 * 0.851)) * 4.0;
1306  double bridge_supply_current = double(di.supply_current_in_) * WG005B_SUPPLY_CURRENT_SCALE;
1307  d.addf("Bridge Supply Current", "%f", bridge_supply_current);
1308  }
1309  else if ((product == WG05_PRODUCT_CODE) || (product == WG021_PRODUCT_CODE))
1310  {
1311  // WG005[CDEF] measures curret going into entire board. It cannot measure negative (regenerative) current values.
1312  // WG021A == WG005E, WG021B == WG005F
1313  static const double WG005_SUPPLY_CURRENT_SCALE = ((82.0 * 2.5) / (0.01 * 5100.0 * 32768.0));
1314  double supply_current = double(di.supply_current_in_) * WG005_SUPPLY_CURRENT_SCALE;
1315  d.addf("Supply Current", "%f", supply_current);
1316  }
1317  d.addf("Configured Offset A", "%f", config_info_.nominal_current_scale_ * di.config_offset_current_A_);
1318  d.addf("Configured Offset B", "%f", config_info_.nominal_current_scale_ * di.config_offset_current_B_);
1319  }
1320 }
1321 
1322 
1323 
1325 {
1326  WG0XStatus *status = (WG0XStatus *)(buffer + command_size_);
1327 
1328  stringstream str;
1329  str << "EtherCAT Device (" << actuator_info_.name_ << ")";
1330  d.name = str.str();
1331  char serial[32];
1332  snprintf(serial, sizeof(serial), "%d-%05d-%05d", config_info_.product_id_ / 100000 , config_info_.product_id_ % 100000, config_info_.device_serial_number_);
1333  d.hardware_id = serial;
1334 
1335  d.summary(d.OK, "OK");
1336 
1337  d.clear();
1338  d.add("Configuration", config_info_.configuration_status_ ? "good" : "error loading configuration");
1339  d.add("Name", actuator_info_.name_);
1340  d.addf("Position", "%02d", sh_->get_ring_position());
1341  d.addf("Product code",
1342  "WG0%d (%d) Firmware Revision %d.%02d, PCB Revision %c.%02d",
1343  sh_->get_product_code() == WG05_PRODUCT_CODE ? 5 : 6,
1344  sh_->get_product_code(), fw_major_, fw_minor_,
1345  'A' + board_major_, board_minor_);
1346 
1347  d.add("Robot", actuator_info_.robot_name_);
1349  d.add("Serial Number", serial);
1350  d.addf("Nominal Current Scale", "%f", config_info_.nominal_current_scale_);
1351  d.addf("Nominal Voltage Scale", "%f", config_info_.nominal_voltage_scale_);
1353 
1354  d.addf("SW Max Current", "%f", actuator_info_.max_current_);
1355  d.addf("Speed Constant", "%f", actuator_info_.speed_constant_);
1356  d.addf("Resistance", "%f", actuator_info_.resistance_);
1357  d.addf("Motor Torque Constant", "%f", actuator_info_.motor_torque_constant_);
1358  d.addf("Pulses Per Revolution", "%d", actuator_info_.pulses_per_revolution_);
1359  d.addf("Encoder Reduction", "%f", actuator_info_.encoder_reduction_);
1360 
1363 
1364  d.addf("Calibration Offset", "%f", cached_zero_offset_);
1365  d.addf("Calibration Status", "%s",
1366  (calibration_status_ == NO_CALIBRATION) ? "No calibration" :
1367  (calibration_status_ == CONTROLLER_CALIBRATION) ? "Calibrated by controller" :
1368  (calibration_status_ == SAVED_CALIBRATION) ? "Using saved calibration" : "UNKNOWN");
1369 
1370  d.addf("Watchdog Limit", "%dms", config_info_.watchdog_limit_);
1371  d.add("Mode", modeString(status->mode_));
1372  d.addf("Digital out", "%d", status->digital_out_);
1373  d.addf("Programmed pwm value", "%d", status->programmed_pwm_value_);
1374  d.addf("Programmed current", "%f", status->programmed_current_ * config_info_.nominal_current_scale_);
1375  d.addf("Measured current", "%f", status->measured_current_ * config_info_.nominal_current_scale_);
1376  d.addf("Timestamp", "%u", status->timestamp_);
1377  d.addf("Encoder count", "%d", status->encoder_count_);
1378  d.addf("Encoder index pos", "%d", status->encoder_index_pos_);
1379  d.addf("Num encoder_errors", "%d", status->num_encoder_errors_);
1380  d.addf("Encoder status", "%d", status->encoder_status_);
1381  d.addf("Calibration reading", "%d", status->calibration_reading_);
1382  d.addf("Last calibration rising edge", "%d", status->last_calibration_rising_edge_);
1383  d.addf("Last calibration falling edge", "%d", status->last_calibration_falling_edge_);
1384  d.addf("Board temperature", "%f", 0.0078125 * status->board_temperature_);
1385  d.addf("Max board temperature", "%f", 0.0078125 * max_board_temperature_);
1386  d.addf("Bridge temperature", "%f", 0.0078125 * status->bridge_temperature_);
1387  d.addf("Max bridge temperature", "%f", 0.0078125 * max_bridge_temperature_);
1388  d.addf("Supply voltage", "%f", status->supply_voltage_ * config_info_.nominal_voltage_scale_);
1389  d.addf("Motor voltage", "%f", status->motor_voltage_ * config_info_.nominal_voltage_scale_);
1390  d.addf("Current Loop Kp", "%d", config_info_.current_loop_kp_);
1391  d.addf("Current Loop Ki", "%d", config_info_.current_loop_ki_);
1392 
1393  if (motor_model_)
1394  {
1397  {
1398  d.mergeSummaryf(d.WARN, "Motor model disabled");
1399  }
1400  }
1401 
1402  if (motor_heating_model_.get() != NULL)
1403  {
1404  motor_heating_model_->diagnostics(d);
1405  }
1406 
1408  {
1409  d.mergeSummaryf(d.WARN, "Encoder errors detected");
1410  }
1411 
1412  d.addf("Packet count", "%d", status->packet_count_);
1413 
1414  d.addf("Drops", "%d", drops_);
1415  d.addf("Consecutive Drops", "%d", consecutive_drops_);
1416  d.addf("Max Consecutive Drops", "%d", max_consecutive_drops_);
1417 
1418  unsigned numPorts = (sh_->get_product_code()==WG06_PRODUCT_CODE) ? 1 : 2; // WG006 has 1 port, WG005 has 2
1420 }
1421 
bool tryLockWG0XDiagnostics()
Definition: wg0x.cpp:1119
bool addActuator(Actuator *actuator)
char name_[64]
Definition: wg0x.h:141
uint16_t max_bridge_temperature_
Definition: wg0x.h:296
MotorHeatingModelParameters params_
Motor parameters.
uint8_t board_over_temp_count_
Definition: wg0x.h:63
uint8_t mbx_command_irq_count_
Definition: wg0x.h:87
uint16_t supply_voltage_
Definition: wg0x.h:177
int16_t programmed_pwm_value_
Definition: wg0x.h:164
#define ROS_FATAL(...)
uint32_t pulses_per_revolution_
Definition: wg0x.h:150
unsigned int command_size_
void packCommand(unsigned char *buffer, bool halt, bool reset)
Definition: wg0x.cpp:563
static void copyActuatorInfo(ethercat_hardware::ActuatorInfo &out, const WG0XActuatorInfo &in)
Fills in ethercat_hardware::ActuatorInfo from WG0XActuatorInfo.
Definition: wg0x.cpp:220
void publishMailboxDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &d)
Definition: wg_mailbox.cpp:993
WG0XDiagnostics()
Definition: wg0x.cpp:65
uint16_t length
Definition: wg_util.h:119
WG0XDiagnostics wg0x_publish_diagnostics_
Definition: wg0x.h:406
int consecutive_drops_
Definition: wg0x.h:399
virtual ~WG0X()
Definition: wg0x.cpp:190
void publishGeneralDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &d)
Definition: wg0x.cpp:1223
uint32_t bridge_over_temp_total_
Definition: wg0x.h:222
int readMailbox(EthercatCom *com, unsigned address, void *data, unsigned length)
Read data from WG0X local bus using mailbox communication.
Definition: wg0x.cpp:1102
double zero_offset_
Definition: wg0x.h:130
void reset()
Definition: motor_model.cpp:27
bool verify()
Check for errors between sample data and motor model.
bool resetting_
Definition: wg0x.h:294
static string modeString(uint8_t mode)
Definition: wg0x.cpp:1189
bool first_
Definition: wg0x.h:212
uint32_t product_id_
Definition: wg0x.h:98
bool readActuatorInfoFromEeprom(EthercatCom *com, WG0XActuatorInfo &actuator_info)
Reads actuator info from eeprom.
Definition: wg0x.cpp:999
void summary(unsigned char lvl, const std::string s)
uint8_t bridge_over_temp_count_
Definition: wg0x.h:64
string cmd
double speed_constant_
Definition: wg0x.h:146
int max_consecutive_drops_
Definition: wg0x.h:400
static const unsigned ACTUATOR_INFO_PAGE
Definition: wg0x.h:383
uint16_t board_temperature_
Definition: wg0x.h:175
static boost::shared_ptr< ethercat_hardware::MotorHeatingModelCommon > motor_heating_model_common_
Definition: wg0x.h:392
MotorModel * motor_model_
Definition: wg0x.h:386
void unlockWG0XDiagnostics()
Definition: wg0x.cpp:1134
char motor_model_[32]
Definition: wg0x.h:144
double max_current_
Definition: wg0x.h:145
bool too_many_dropped_packets_
Definition: wg0x.h:297
uint16_t watchdog_limit_
Definition: wg0x.h:121
unsigned computeChecksum(void const *data, unsigned length)
Definition: wg_util.cpp:49
void ethercatDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &d, unsigned numPorts)
Adds diagnostic information for EtherCAT ports.
uint8_t undervoltage_count_
Definition: wg0x.h:61
int32_t encoder_count_
Definition: wg0x.h:168
XmlRpcServer s
char robot_name_[32]
Definition: wg0x.h:142
uint8_t safety_disable_status_
Definition: wg0x.h:52
bool has_error_
Definition: wg0x.h:295
uint32_t timestamp_
Definition: wg0x.h:167
uint8_t safety_disable_status_hold_
Definition: wg0x.h:53
uint16_t bridge_temperature_
Definition: wg0x.h:176
uint8_t board_major_
Printed circuit board revision (for this value 0==&#39;A&#39;, 1==&#39;B&#39;)
Definition: wg0x.h:260
ethercat_hardware::WGEeprom eeprom_
Access to device eeprom.
Definition: wg0x.h:354
bool enforce_
0 if heating model should be not be enforced, 0 otherwise
WG0XDiagnosticsInfo diagnostics_info_
Definition: wg0x.h:216
void generateCRC(void)
Calculate CRC of structure and update crc32_256_ and crc32_264_ elements.
Definition: wg0x.cpp:146
int16_t config_offset_current_B_
Definition: wg0x.h:73
virtual void construct(EtherCAT_SlaveHandler *sh, int &start_address)
< Construct EtherCAT device
float nominal_voltage_scale_
Definition: wg0x.h:115
bool status_checksum_error_
Definition: wg0x.h:298
uint8_t checksum_
Definition: wg0x.h:194
static ros::Duration timediffToDuration(int32_t timediff_usec)
Definition: wg0x.cpp:696
uint32_t safety_disable_total_
Definition: wg0x.h:218
double resistance_
Definition: wg0x.h:147
void diagnostics(diagnostic_updater::DiagnosticStatusWrapper &d)
Collects and publishes device diagnostics.
bool program(EthercatCom *com, const WG0XActuatorInfo &actutor_info)
Programs acutator and heating parameters into device EEPROM.
Definition: wg0x.cpp:1051
uint8_t mode
Definition: wg_util.h:48
bool readAppRam(EthercatCom *com, double &zero_offset)
Definition: wg0x.cpp:971
#define ROS_WARN(...)
bool publishTrace(const string &reason, unsigned level, unsigned delay)
Asks device to publish (motor) trace. Only works for devices that support it.
Definition: wg0x.cpp:874
bool verifyCRC(void) const
Verify CRC stored in actuator info structure.
Definition: wg0x.cpp:131
virtual void collectDiagnostics(EthercatCom *com)
Definition: wg0x.cpp:885
pr2_hardware_interface::DigitalOut digital_out_
Definition: wg0x.h:271
uint8_t board_minor_
Printed circuit assembly revision.
Definition: wg0x.h:261
uint8_t current_loop_kp_
Definition: wg0x.h:111
void addf(const std::string &key, const char *format,...)
void clearErrorFlags(void)
Definition: wg0x.cpp:549
bool verifyState(WG0XStatus *this_status, WG0XStatus *prev_status)
Definition: wg0x.cpp:749
virtual void collectDiagnostics(EthercatCom *com)
uint8_t current_loop_ki_
Definition: wg0x.h:112
double motor_torque_constant_
Definition: wg0x.h:148
bool fpga_internal_reset_detected_
Definition: wg0x.h:300
static double calcEncoderVelocity(int32_t new_position, uint32_t new_timestamp, int32_t old_position, uint32_t old_timestamp)
Definition: wg0x.cpp:721
uint8_t version_
Definition: wg0x.h:128
static bool timestamp_jump(uint32_t timestamp, uint32_t last_timestamp, uint32_t amount)
Definition: wg0x.cpp:743
double cached_zero_offset_
Definition: wg0x.h:305
unsigned int rotateRight8(unsigned in)
Definition: wg_util.cpp:41
int32_t last_calibration_falling_edge_
Definition: wg0x.h:174
bool writeEepromPage(EthercatCom *com, WGMailbox *mbx, unsigned page, const void *data, unsigned length)
Write data to single eeprom page.
Definition: wg_eeprom.cpp:289
bool timestamp_jump_detected_
Definition: wg0x.h:299
double encoder_reduction_
Definition: wg0x.h:149
int32_t last_calibration_rising_edge_
Definition: wg0x.h:173
uint32_t watchdog_disable_total_
Definition: wg0x.h:224
bool unpackState(unsigned char *this_buffer, unsigned char *prev_buffer)
Definition: wg0x.cpp:614
uint32_t operate_disable_total_
Definition: wg0x.h:223
void update(const WG0XSafetyDisableStatus &new_status, const WG0XDiagnosticsInfo &new_diagnostics_info)
Use new updates WG0X diagnostics with new safety disable data.
Definition: wg0x.cpp:90
double zero_offset_
Definition: wg0x.h:254
static const int PWM_MAX
Definition: wg0x.h:347
bool valid_
Definition: wg0x.h:213
void sample(const ethercat_hardware::MotorTraceSample &s)
Call for each update.
int calibration_status_
Definition: wg0x.h:307
bool readMotorHeatingModelParametersFromEeprom(EthercatCom *com, MotorHeatingModelParametersEepromConfig &config)
Reads actuator info from eeprom.
Definition: wg0x.cpp:1018
int16_t config_offset_current_A_
Definition: wg0x.h:72
pthread_mutex_t wg0x_diagnostics_lock_
Definition: wg0x.h:405
double cached_zero_offset_
Definition: wg0x.h:231
ros::Duration sample_timestamp_
Definition: wg0x.h:314
uint32_t id_
Definition: wg0x.h:140
int writeMailbox(EthercatCom *com, unsigned address, void const *data, unsigned length)
Write data to WG0X local bus using mailbox communication.
Definition: wg_mailbox.cpp:939
uint16_t absolute_current_limit_
Definition: wg0x.h:113
uint32_t over_current_total_
Definition: wg0x.h:220
uint32_t checksum_errors_
Definition: wg0x.h:227
bool initializeMotorHeatingModel(bool allow_unprogrammed)
Definition: wg0x.cpp:296
uint8_t digital_out_
Definition: wg0x.h:163
bool initialize(const ethercat_hardware::ActuatorInfo &actuator_info, const ethercat_hardware::BoardInfo &board_info)
Initializes motor trace publisher.
Definition: motor_model.cpp:53
uint8_t mode_
Definition: wg0x.h:189
ROSCPP_DECL bool get(const std::string &key, std::string &s)
#define ERROR_HDR
Definition: wg0x.cpp:59
static int32_t positionDiff(int32_t new_position, int32_t old_position)
Definition: wg0x.cpp:710
pr2_hardware_interface::Actuator actuator_
Definition: wg0x.h:270
uint16_t status
int32_t encoder_index_pos_
Definition: wg0x.h:169
int16_t programmed_current_
Definition: wg0x.h:192
bool readEepromPage(EthercatCom *com, WGMailbox *mbx, unsigned page, void *data, unsigned length)
Read data from single eeprom page.
Definition: wg_eeprom.cpp:223
uint8_t configuration_status_
Definition: wg0x.h:117
uint8_t operate_disable_count_
Definition: wg0x.h:65
int16_t programmed_current_
Definition: wg0x.h:165
bool initialize(EtherCAT_SlaveHandler *sh)
Definition: wg_mailbox.cpp:236
uint16_t packet_count_
Definition: wg0x.h:179
int16_t motor_voltage_
Definition: wg0x.h:178
#define CHECK_SAFETY_BIT(bit)
Definition: wg0x.cpp:1163
ethercat_hardware::MotorTraceSample motor_trace_sample_
Definition: wg0x.h:388
uint8_t mode_
Definition: wg0x.h:162
uint8_t over_current_count_
Definition: wg0x.h:62
WG0XConfigInfo config_info_
Definition: wg0x.h:264
static string safetyDisableString(uint8_t status)
Definition: wg0x.cpp:1169
bool encoder_errors_detected_
Definition: wg0x.h:301
uint8_t pdi_checksum_error_count_
Definition: wg0x.h:92
uint16_t supply_current_in_
Definition: wg0x.h:74
int drops_
Definition: wg0x.h:398
uint16_t major_
Definition: wg0x.h:138
static const unsigned BASE_ADDR
Definition: wg0x.h:133
uint16_t minor_
Definition: wg0x.h:139
static const unsigned CONFIG_INFO_BASE_ADDR
Definition: wg0x.h:123
double max_current_
min(board current limit, actuator current limit)
Definition: wg0x.h:265
void diagnostics(diagnostic_updater::DiagnosticStatusWrapper &d, unsigned char *)
For EtherCAT device that only publish one EtherCAT Status message. If sub-class implements multiDiagn...
Definition: wg0x.cpp:1324
virtual bool txandrx_once(struct EtherCAT_Frame *frame)=0
double zero_offset_
Definition: wg0x.h:230
uint8_t encoder_status_
Definition: wg0x.h:171
EtherCAT_SlaveHandler * sh_
uint8_t watchdog_disable_count_
Definition: wg0x.h:66
uint32_t last_last_timestamp_
Definition: wg0x.h:397
pr2_hardware_interface::DigitalOut publish_motor_trace_
Definition: wg0x.h:389
uint8_t fw_minor_
Definition: wg0x.h:259
uint8_t safety_disable_count_
Definition: wg0x.h:54
static double convertRawTemperature(int16_t raw_temp)
Converts raw 16bit temperature value returned by device into value in degress Celcius.
Definition: wg0x.cpp:736
void checkPublish()
Publishes motor trace if delay time is up.
Definition: motor_model.cpp:87
WG0XSafetyDisableStatus safety_disable_status_
Definition: wg0x.h:214
void flagPublish(const std::string &reason, int level, int delay)
flags delayed publish of motor trace.
void mergeSummary(unsigned char lvl, const std::string s)
AppRamStatus app_ram_status_
Definition: wg0x.h:324
int writeMailbox(EthercatCom *com, unsigned address, void const *data, unsigned length)
Write data to WG0X local bus using mailbox communication.
Definition: wg0x.cpp:1156
static const unsigned BASE_ADDR
Definition: wg0x.h:55
void construct(EtherCAT_SlaveHandler *sh, int &start_address)
< Construct EtherCAT device
Definition: wg0x.cpp:198
bool initializeMotorModel(pr2_hardware_interface::HardwareInterface *hw, const string &device_description, double max_pwm_ratio, double board_resistance, bool poor_measured_motor_voltage)
Allocates and initialized motor trace for WG0X devices than use it (WG006, WG005) ...
Definition: wg0x.cpp:238
uint32_t lock_errors_
Definition: wg0x.h:226
uint32_t device_serial_number_
Definition: wg0x.h:110
float nominal_current_scale_
Definition: wg0x.h:114
uint16_t max_board_temperature_
Definition: wg0x.h:296
int readMailbox(EthercatCom *com, unsigned address, void *data, unsigned length)
Read data from WG0X local bus using mailbox communication.
Definition: wg_mailbox.cpp:812
uint8_t pdi_timeout_error_count_
Definition: wg0x.h:91
ethercat_hardware::ActuatorInfo actuator_info_msg_
Definition: wg0x.h:267
int16_t measured_current_
Definition: wg0x.h:166
uint32_t board_over_temp_total_
Definition: wg0x.h:221
uint8_t fw_major_
Definition: wg0x.h:258
bool verifyChecksum(const void *buffer, unsigned size)
Definition: wg0x.cpp:665
boost::shared_ptr< ethercat_hardware::MotorHeatingModel > motor_heating_model_
Definition: wg0x.h:393
WG0XSafetyDisableCounters safety_disable_counters_
Definition: wg0x.h:89
bool lockWG0XDiagnostics()
Definition: wg0x.cpp:1107
uint32_t undervoltage_total_
Definition: wg0x.h:219
ethercat_hardware::WGMailbox mailbox_
Mailbox access to device.
Definition: wg0x.h:351
void mergeSummaryf(unsigned char lvl, const char *format,...)
uint8_t digital_out_
Definition: wg0x.h:190
WG0X()
Definition: wg0x.cpp:157
static int32_t timestampDiff(uint32_t new_timestamp, uint32_t old_timestamp)
Definition: wg0x.cpp:685
void add(const std::string &key, const T &val)
bool writeAppRam(EthercatCom *com, double zero_offset)
Definition: wg0x.cpp:960
static double min(double a, double b)
Definition: motor_model.cpp:4
uint32_t crc32_
Definition: wg0x.h:131
WG0XDiagnostics wg0x_collect_diagnostics_
Definition: wg0x.h:407
#define ROS_ERROR(...)
uint32_t last_timestamp_
Definition: wg0x.h:396
bool in_lockout_
Definition: wg0x.h:293
bool disable_motor_model_checking_
Definition: wg0x.h:387
virtual int initialize(pr2_hardware_interface::HardwareInterface *, bool allow_unprogrammed=true)
Definition: wg0x.cpp:395
char motor_make_[32]
Definition: wg0x.h:143
bool addDigitalOut(DigitalOut *digital_out)
uint16_t num_encoder_errors_
Definition: wg0x.h:170
static const unsigned BASE_ADDR
Definition: wg0x.h:93
#define ROS_DEBUG(...)
uint8_t calibration_reading_
Definition: wg0x.h:172
WG0XActuatorInfo actuator_info_
Definition: wg0x.h:263


ethercat_hardware
Author(s): Rob Wheeler , Derek King
autogenerated on Thu Mar 4 2021 03:10:21