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> 47 #include <boost/crc.hpp> 48 #include <boost/shared_ptr.hpp> 49 #include <boost/static_assert.hpp> 50 #include <boost/make_shared.hpp> 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" 59 #define ERROR_HDR "\033[41mERROR\033[0m" 60 #define WARN_HDR "\033[43mERROR\033[0m" 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),
78 cached_zero_offset_(0)
137 boost::crc_32_type crc32_256, crc32_264;
140 return ((this->crc32_264_ == crc32_264.checksum()) || (this->crc32_256_ == crc32_256.checksum()));
148 boost::crc_32_type crc32;
150 this->crc32_256_ = crc32.checksum();
153 this->crc32_264_ = crc32.checksum();
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),
168 disable_motor_model_checking_(false)
185 ROS_ERROR(
"WG0X : init diagnostics mutex :%s", strerror(error));
192 delete sh_->get_fmmu_config();
193 delete sh_->get_pd_config();
203 fw_major_ = (sh->get_revision() >> 8) & 0xff;
223 out.name = std::string(in.
name_);
239 const string &device_description,
240 double max_pwm_ratio,
241 double board_resistance,
242 bool poor_measured_motor_voltage)
253 unsigned product_code =
sh_->get_product_code();
254 ethercat_hardware::BoardInfo bi;
255 bi.description = device_description;
256 bi.product_code = product_code;
259 bi.serial =
sh_->get_serial();
262 bi.board_resistance = board_resistance;
263 bi.max_pwm_ratio = max_pwm_ratio;
265 bi.poor_measured_motor_voltage = poor_measured_motor_voltage;
287 ROS_WARN(
"Disabling motor model on %s", ai.name.c_str());
303 ROS_FATAL(
"Unable to read motor heating model config parameters from EEPROM");
311 if (allow_unprogrammed)
313 ROS_WARN(
"%s EEPROM does not contain motor heating model parameters",
319 ROS_WARN(
"%s EEPROM does not contain motor heating model parameters",
323 ROS_FATAL(
"%s EEPROM does not contain motor heating model parameters",
343 std::ostringstream hwid;
344 hwid << unsigned(
sh_->get_product_code()) << std::setw(5) << std::setfill(
'0') << unsigned(
sh_->get_serial());
355 ROS_WARN(
"Motor heating model disabled for all devices");
359 ROS_WARN(
"Not loading motor heating model files");
363 ROS_WARN(
"Not saving motor heating model files");
373 boost::make_shared<ethercat_hardware::MotorHeatingModel>(config.
params_,
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,
427 ROS_FATAL(
"Unable to load configuration information");
435 ROS_FATAL(
"Unable to read actuator info from EEPROM");
443 if (allow_unprogrammed)
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());
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());
512 ROS_WARN(
"WARNING: Device #%02d : motor current limit (%f) greater than board current limit (%f)",
517 else if (allow_unprogrammed)
519 ROS_WARN(
"WARNING: Device #%02d (%d%05d) is not programmed",
520 sh_->get_ring_position(),
sh_->get_product_code(),
sh_->get_serial());
528 ROS_FATAL(
"Device #%02d (%d%05d) is not programmed, aborting...",
529 sh_->get_ring_position(),
sh_->get_product_code(),
sh_->get_serial());
536 #define GET_ATTR(a) \ 539 attr = elt->Attribute((a)); \ 541 c = elt->FirstChildElement((a)); \ 542 if (!c || !(attr = c->GetText())) { \ 543 ROS_FATAL("Actuator is missing the attribute "#a); \ 544 exit(EXIT_FAILURE); \ 687 return int32_t(new_timestamp - old_timestamp);
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;
712 return int32_t(new_position - old_position);
722 int32_t old_position, uint32_t old_timestamp)
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);
738 return 0.0078125 * double(raw_temp);
745 uint32_t timestamp_diff = (timestamp - last_timestamp);
746 return (timestamp_diff > amount);
763 s.supply_voltage = supply_voltage;
765 s.programmed_pwm = pwm_ratio;
766 s.executed_current = last_executed_current;
857 const char* reason =
"Publishing manually triggered";
861 reason = (undervoltage) ?
"Undervoltage Lockout" :
"Safety Lockout";
863 int level = (new_error) ? 2 : 0;
888 bool success =
false;
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(),
905 EC_Ethernet_Frame frame(&nprd_telegram);
910 if (nprd_telegram.get_wkc() != 1) {
965 boost::crc_32_type crc32;
966 crc32.process_bytes(&cfg,
sizeof(cfg)-
sizeof(cfg.
crc32_));
967 cfg.
crc32_ = crc32.checksum();
982 boost::crc_32_type crc32;
983 crc32.process_bytes(&cfg,
sizeof(cfg)-
sizeof(cfg.
crc32_));
984 if (cfg.
crc32_ != crc32.checksum()) {
1001 BOOST_STATIC_ASSERT(
sizeof(actuator_info) == 264);
1005 ROS_ERROR(
"Reading acutuator info from eeprom");
1020 BOOST_STATIC_ASSERT(
sizeof(config) == 256);
1024 ROS_ERROR(
"Reading motor heating model config from eeprom");
1055 ROS_ERROR(
"Writing actuator infomation to EEPROM");
1081 ROS_ERROR(
"Writing motor heating model configuration to EEPROM");
1111 fprintf(stderr,
"%s : " ERROR_HDR " getting diagnostics lock\n", __func__);
1122 if (error == EBUSY) {
1125 else if (error != 0) {
1126 fprintf(stderr,
"%s : " ERROR_HDR " getting diagnostics lock\n", __func__);
1138 fprintf(stderr,
"%s : " ERROR_HDR " freeing diagnostics lock\n", __func__);
1163 #define CHECK_SAFETY_BIT(bit) \ 1164 do { if (status & SAFETY_##bit) { \ 1165 str += prefix + #bit; \ 1194 str += prefix +
"ENABLE";
1198 str += prefix +
"CURRENT";
1202 str += prefix +
"UNDERVOLTAGE";
1206 str += prefix +
"SAFETY_RESET";
1210 str += prefix +
"SAFETY_LOCKOUT";
1214 str += prefix +
"RESET";
1238 d.
mergeSummary(d.ERROR,
"Checksum error on status data");
1243 d.
mergeSummary(d.WARN,
"Have not yet collected WG0X diagnostics");
1247 d.
mergeSummary(d.WARN,
"Could not collect WG0X diagnostics");
1266 string prefix(
": ");
1267 string str(
"Safety Lockout");
1299 unsigned product =
sh_->get_product_code();
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);
1313 static const double WG005_SUPPLY_CURRENT_SCALE = ((82.0 * 2.5) / (0.01 * 5100.0 * 32768.0));
1315 d.
addf(
"Supply Current",
"%f", supply_current);
1333 d.hardware_id = serial;
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",
1349 d.
add(
"Serial Number", serial);
1365 d.
addf(
"Calibration Status",
"%s",
bool tryLockWG0XDiagnostics()
bool addActuator(Actuator *actuator)
uint16_t max_bridge_temperature_
double last_measured_effort_
MotorHeatingModelParameters params_
Motor parameters.
uint8_t board_over_temp_count_
uint8_t mbx_command_irq_count_
double last_calibration_rising_edge_
int16_t programmed_pwm_value_
uint32_t pulses_per_revolution_
unsigned int command_size_
void packCommand(unsigned char *buffer, bool halt, bool reset)
static void copyActuatorInfo(ethercat_hardware::ActuatorInfo &out, const WG0XActuatorInfo &in)
Fills in ethercat_hardware::ActuatorInfo from WG0XActuatorInfo.
void publishMailboxDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &d)
WG0XDiagnostics wg0x_publish_diagnostics_
void publishGeneralDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &d)
uint32_t bridge_over_temp_total_
int readMailbox(EthercatCom *com, unsigned address, void *data, unsigned length)
Read data from WG0X local bus using mailbox communication.
bool verify()
Check for errors between sample data and motor model.
static string modeString(uint8_t mode)
bool readActuatorInfoFromEeprom(EthercatCom *com, WG0XActuatorInfo &actuator_info)
Reads actuator info from eeprom.
void summary(unsigned char lvl, const std::string s)
uint8_t bridge_over_temp_count_
int max_consecutive_drops_
static const unsigned ACTUATOR_INFO_PAGE
uint16_t board_temperature_
static boost::shared_ptr< ethercat_hardware::MotorHeatingModelCommon > motor_heating_model_common_
MotorModel * motor_model_
void unlockWG0XDiagnostics()
bool too_many_dropped_packets_
unsigned computeChecksum(void const *data, unsigned length)
void ethercatDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &d, unsigned numPorts)
Adds diagnostic information for EtherCAT ports.
bool verifyCRC(void) const
uint8_t undervoltage_count_
uint8_t safety_disable_status_
double last_executed_effort_
uint8_t safety_disable_status_hold_
uint16_t bridge_temperature_
uint8_t board_major_
Printed circuit board revision (for this value 0=='A', 1=='B')
ethercat_hardware::WGEeprom eeprom_
Access to device eeprom.
bool enforce_
0 if heating model should be not be enforced, 0 otherwise
WG0XDiagnosticsInfo diagnostics_info_
void generateCRC(void)
Calculate CRC of structure and update crc32_256_ and crc32_264_ elements.
int16_t config_offset_current_B_
virtual void construct(EtherCAT_SlaveHandler *sh, int &start_address)
< Construct EtherCAT device
double last_commanded_effort_
float nominal_voltage_scale_
bool status_checksum_error_
static ros::Duration timediffToDuration(int32_t timediff_usec)
uint32_t safety_disable_total_
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.
bool readAppRam(EthercatCom *com, double &zero_offset)
bool publishTrace(const string &reason, unsigned level, unsigned delay)
Asks device to publish (motor) trace. Only works for devices that support it.
bool verifyCRC(void) const
Verify CRC stored in actuator info structure.
virtual void collectDiagnostics(EthercatCom *com)
pr2_hardware_interface::DigitalOut digital_out_
uint8_t board_minor_
Printed circuit assembly revision.
void addf(const std::string &key, const char *format,...)
void clearErrorFlags(void)
bool verifyState(WG0XStatus *this_status, WG0XStatus *prev_status)
double last_executed_current_
virtual void collectDiagnostics(EthercatCom *com)
double motor_torque_constant_
bool fpga_internal_reset_detected_
static double calcEncoderVelocity(int32_t new_position, uint32_t new_timestamp, int32_t old_position, uint32_t old_timestamp)
static bool timestamp_jump(uint32_t timestamp, uint32_t last_timestamp, uint32_t amount)
double cached_zero_offset_
unsigned int rotateRight8(unsigned in)
int32_t last_calibration_falling_edge_
bool writeEepromPage(EthercatCom *com, WGMailbox *mbx, unsigned page, const void *data, unsigned length)
Write data to single eeprom page.
bool timestamp_jump_detected_
double encoder_reduction_
int32_t last_calibration_rising_edge_
uint32_t watchdog_disable_total_
bool unpackState(unsigned char *this_buffer, unsigned char *prev_buffer)
uint32_t operate_disable_total_
void update(const WG0XSafetyDisableStatus &new_status, const WG0XDiagnosticsInfo &new_diagnostics_info)
Use new updates WG0X diagnostics with new safety disable data.
ros::Duration sample_timestamp_
void sample(const ethercat_hardware::MotorTraceSample &s)
Call for each update.
bool readMotorHeatingModelParametersFromEeprom(EthercatCom *com, MotorHeatingModelParametersEepromConfig &config)
Reads actuator info from eeprom.
int16_t config_offset_current_A_
pthread_mutex_t wg0x_diagnostics_lock_
double cached_zero_offset_
ros::Duration sample_timestamp_
int writeMailbox(EthercatCom *com, unsigned address, void const *data, unsigned length)
Write data to WG0X local bus using mailbox communication.
uint16_t absolute_current_limit_
uint32_t over_current_total_
uint32_t checksum_errors_
bool initializeMotorHeatingModel(bool allow_unprogrammed)
bool initialize(const ethercat_hardware::ActuatorInfo &actuator_info, const ethercat_hardware::BoardInfo &board_info)
Initializes motor trace publisher.
ROSCPP_DECL bool get(const std::string &key, std::string &s)
static int32_t positionDiff(int32_t new_position, int32_t old_position)
pr2_hardware_interface::Actuator actuator_
int32_t encoder_index_pos_
int16_t programmed_current_
bool readEepromPage(EthercatCom *com, WGMailbox *mbx, unsigned page, void *data, unsigned length)
Read data from single eeprom page.
uint8_t configuration_status_
uint8_t operate_disable_count_
int16_t programmed_current_
bool initialize(EtherCAT_SlaveHandler *sh)
#define CHECK_SAFETY_BIT(bit)
bool calibration_rising_edge_valid_
ethercat_hardware::MotorTraceSample motor_trace_sample_
uint8_t over_current_count_
WG0XConfigInfo config_info_
static string safetyDisableString(uint8_t status)
bool encoder_errors_detected_
uint8_t pdi_checksum_error_count_
static const unsigned EEPROM_PAGE
uint16_t supply_current_in_
static const unsigned BASE_ADDR
static const unsigned CONFIG_INFO_BASE_ADDR
double max_current_
min(board current limit, actuator current limit)
void diagnostics(diagnostic_updater::DiagnosticStatusWrapper &d, unsigned char *)
For EtherCAT device that only publish one EtherCAT Status message. If sub-class implements multiDiagn...
virtual bool txandrx_once(struct EtherCAT_Frame *frame)=0
EtherCAT_SlaveHandler * sh_
double last_commanded_current_
bool calibration_falling_edge_valid_
uint8_t watchdog_disable_count_
uint32_t last_last_timestamp_
pr2_hardware_interface::DigitalOut publish_motor_trace_
double last_measured_current_
uint8_t safety_disable_count_
static double convertRawTemperature(int16_t raw_temp)
Converts raw 16bit temperature value returned by device into value in degress Celcius.
void checkPublish()
Publishes motor trace if delay time is up.
WG0XSafetyDisableStatus safety_disable_status_
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_
int writeMailbox(EthercatCom *com, unsigned address, void const *data, unsigned length)
Write data to WG0X local bus using mailbox communication.
static const unsigned BASE_ADDR
void construct(EtherCAT_SlaveHandler *sh, int &start_address)
< Construct EtherCAT device
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) ...
uint32_t device_serial_number_
float nominal_current_scale_
uint16_t max_board_temperature_
int readMailbox(EthercatCom *com, unsigned address, void *data, unsigned length)
Read data from WG0X local bus using mailbox communication.
uint8_t pdi_timeout_error_count_
ethercat_hardware::ActuatorInfo actuator_info_msg_
double last_calibration_falling_edge_
int16_t measured_current_
uint32_t board_over_temp_total_
bool verifyChecksum(const void *buffer, unsigned size)
boost::shared_ptr< ethercat_hardware::MotorHeatingModel > motor_heating_model_
WG0XSafetyDisableCounters safety_disable_counters_
bool lockWG0XDiagnostics()
uint32_t undervoltage_total_
ethercat_hardware::WGMailbox mailbox_
Mailbox access to device.
void mergeSummaryf(unsigned char lvl, const char *format,...)
static int32_t timestampDiff(uint32_t new_timestamp, uint32_t old_timestamp)
void add(const std::string &key, const T &val)
bool writeAppRam(EthercatCom *com, double zero_offset)
static double min(double a, double b)
DigitalOutCommand command_
WG0XDiagnostics wg0x_collect_diagnostics_
bool calibration_reading_
bool disable_motor_model_checking_
virtual int initialize(pr2_hardware_interface::HardwareInterface *, bool allow_unprogrammed=true)
bool addDigitalOut(DigitalOut *digital_out)
uint16_t num_encoder_errors_
static const unsigned BASE_ADDR
uint8_t calibration_reading_
WG0XActuatorInfo actuator_info_