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