45   sh->set_fmmu_config( 
new EtherCAT_FMMU_Config(0) );
    46   sh->set_pd_config( 
new EtherCAT_PD_Config(0) );
    51   delete sh_->get_fmmu_config();
    52   delete sh_->get_pd_config();
    57   ROS_DEBUG(
"Device #%02d: EK1122 (%#08x)", 
sh_->get_ring_position(), 
sh_->get_product_code());
    63   str << 
"EtherCAT Device #" << setw(2) << setfill(
'0') << 
sh_->get_ring_position() << 
" (EK1122)";
    67   snprintf(serial, 
sizeof(serial), 
"%d-%05d-%05d", 
sh_->get_product_code()/ 100000 , 
sh_->get_product_code() % 100000, 
sh_->get_serial());
    68   d.hardware_id = serial;
    71   d.
addf(
"Product code", 
"EK1122 (%u)", 
sh_->get_product_code());
 
void summary(unsigned char lvl, const std::string s)
 
void ethercatDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &d, unsigned numPorts)
Adds diagnostic information for EtherCAT ports. 
 
int initialize(pr2_hardware_interface::HardwareInterface *, bool)
 
virtual void construct(EtherCAT_SlaveHandler *sh, int &start_address)
< Construct EtherCAT device 
 
void addf(const std::string &key, const char *format,...)
 
PLUGINLIB_EXPORT_CLASS(EK1122, EthercatDevice)
 
void construct(EtherCAT_SlaveHandler *sh, int &start_address)
< Construct EtherCAT device 
 
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...