45 sh->set_fmmu_config(
new EtherCAT_FMMU_Config(0) );
46 sh->set_pd_config(
new EtherCAT_PD_Config(0) );
48 fw_major_ = (sh->get_revision() >> 8) & 0xff;
56 delete sh_->get_fmmu_config();
57 delete sh_->get_pd_config();
62 ROS_DEBUG(
"Device #%02d: WG014 (%#08x)",
sh_->get_ring_position(),
sh_->get_product_code());
69 str <<
"EtherCAT Device #" << setw(2) << setfill(
'0') <<
sh_->get_ring_position() <<
" (WG014)";
73 snprintf(serial,
sizeof(serial),
"%d-%05d-%05d",
sh_->get_product_code()/ 100000 ,
sh_->get_product_code() % 100000,
sh_->get_serial());
74 d.hardware_id = serial;
77 d.
addf(
"Product code",
"WG014 (%d), Ports %s, PCB Revision %c.%02d",
78 sh_->get_product_code(),
83 d.
addf(
"Serial Number",
"%s", serial);
void summary(unsigned char lvl, const std::string s)
void ethercatDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &d, unsigned numPorts)
Adds diagnostic information for EtherCAT ports.
virtual void construct(EtherCAT_SlaveHandler *sh, int &start_address)
< Construct EtherCAT device
void construct(EtherCAT_SlaveHandler *sh, int &start_address)
< Construct EtherCAT device
void addf(const std::string &key, const char *format,...)
EtherCAT_SlaveHandler * sh_
void diagnostics(diagnostic_updater::DiagnosticStatusWrapper &d, unsigned char *)
For EtherCAT device that only publish one EtherCAT Status message. If sub-class implements multiDiagn...
PLUGINLIB_EXPORT_CLASS(WG014, EthercatDevice)
int initialize(pr2_hardware_interface::HardwareInterface *, bool)