$search
00001 #include "riq_hand_ethercat_hardware/ethercat_al.h" 00002 #include "ethercat_hardware/ethercat_device.h" 00003 00004 namespace riq_hand_ethercat_hardware 00005 { 00006 00007 const char* ECatStates::stateString(unsigned state) 00008 { 00009 switch(state) 00010 { 00011 case INIT: return "Init"; 00012 case BOOTSTRAP: return "Bootstap"; 00013 case PREOP: return "PreOP"; 00014 case SAFEOP: return "SafeOP"; 00015 case OP: return "OP"; 00016 default: return "Invalid"; 00017 } 00018 } 00019 00020 00021 const char* ECatALStatusCode::errorCodeString(unsigned code) 00022 { 00023 switch(code) 00024 { 00025 case NO_ERROR: 00026 return "No error"; 00027 case SYNC_MANAGER_WATCHDOG: 00028 return "Sync manager watchdog"; 00029 default: return "Unknown"; 00030 } 00031 } 00032 00033 bool ECatALStatusAll::readData(EthercatCom *com, EtherCAT_SlaveHandler *sh) 00034 { 00035 int result = EthercatDevice::readData(com, sh, BASE_ADDR, this, sizeof(*this), EthercatDevice::FIXED_ADDR); 00036 if (result != 0) 00037 { 00038 return false; 00039 } 00040 return true; 00041 } 00042 00043 void ECatALStatusAll::sizeAssert() 00044 { 00045 BOOST_STATIC_ASSERT(sizeof(ECatALStatusAll) == 6); 00046 } 00047 00048 00049 bool ECatALControl::writeData(EthercatCom *com, EtherCAT_SlaveHandler *sh) const 00050 { 00051 int result = EthercatDevice::writeData(com, sh, BASE_ADDR, this, sizeof(*this), EthercatDevice::FIXED_ADDR); 00052 if (result != 0) 00053 { 00054 return false; 00055 } 00056 return true; 00057 } 00058 00059 void ECatALControl::sizeAssert() 00060 { 00061 BOOST_STATIC_ASSERT(sizeof(ECatALControl) == 2); 00062 } 00063 00064 }; //namespace riq_hand_ethercat_hardware 00065