4 #include <boost/foreach.hpp>     5 #include <boost/static_assert.hpp>    27                           const std::string &actuator_name, 
    28                           const std::string &processor_name,
    29                           unsigned iram_address, 
unsigned ctrl_address)
    31   Info info(mbx, actuator_name, processor_name, iram_address, ctrl_address);
    33   ROS_INFO(
"Processor : %s/%s", actuator_name.c_str(), processor_name.c_str());
    39                                                   const std::string &processor_name,
    40                                                   std::ostream &err_out)
 const    50   err_out << 
"No actuator/processor with name " << actuator_name << 
"/" << processor_name;
    57                                      ethercat_hardware::SoftProcessorFirmwareRead::Response &response)
    59   response.success = 
false;
    60   response.error_msg = 
"";
    62   std::ostringstream err_out;
    64   const Info *info = 
get(request.actuator_name, request.processor_name, err_out);
    67     response.error_msg = err_out.str();
    73   static const unsigned INSTRUCTION_READ_CHUNK = 64;
    74   uint8_t buf[INSTRUCTION_READ_CHUNK*4]; 
    82       response.error_msg = 
"Error reading IRAM data with mailbox";
    87     for (
unsigned jj=0; jj<INSTRUCTION_READ_CHUNK; ++jj)
    90       uint32_t instruction = 
    91         (uint32_t(buf[jj*4+3])<<24) | 
    92         (uint32_t(buf[jj*4+2])<<16) | 
    93         (uint32_t(buf[jj*4+1])<<8 ) | 
    94         (uint32_t(buf[jj*4+0])<<0 ) ;
    96       response.instructions[ii+jj] = instruction;
   100   response.success = 
true;
   107                                       ethercat_hardware::SoftProcessorFirmwareWrite::Response &response)
   109   response.success = 
false;
   110   response.error_msg = 
"";
   112   std::ostringstream err_out;
   114   const Info *info = 
get(request.actuator_name, request.processor_name, err_out);
   117     response.error_msg = err_out.str();
   124     response.error_msg = err_out.str();    
   134     response.error_msg = err_out.str();    
   138   response.success = 
true;
   144                               ethercat_hardware::SoftProcessorReset::Response &response)
   146   response.success = 
false;
   147   response.error_msg = 
"";
   149   std::ostringstream err_out;
   151   const Info *info = 
get(request.actuator_name, request.processor_name, err_out);
   154     response.error_msg = err_out.str();
   160     response.error_msg = err_out.str();    
   166     response.error_msg = err_out.str();    
   170   response.success = 
true;
 void add(WGMailbox *mbx, const std::string &actuator_name, const std::string &processor_name, unsigned iram_address, unsigned ctrl_address)
 
bool initialize(EthercatCom *com)
 
bool assertReset(const Info &info, std::ostream &err_msg)
Puts soft processor in reset. 
 
bool resetCB(ethercat_hardware::SoftProcessorReset::Request &request, ethercat_hardware::SoftProcessorReset::Response &response)
 
const WGSoftProcessor::Info * get(const std::string &actuator_name, const std::string &processor_name, std::ostream &err_out) const 
Get pointer to soft processor by name. Returns NULL if processor d/n exist and create message in err_...
 
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
 
ros::ServiceServer write_firmware_service_
service that allows write of soft processor firmware 
 
bool writeFirmwareCB(ethercat_hardware::SoftProcessorFirmwareWrite::Request &request, ethercat_hardware::SoftProcessorFirmwareWrite::Response &response)
 
ros::ServiceServer reset_service_
service that resets soft-processor 
 
static const unsigned IRAM_INSTRUCTION_LENGTH
 
int readMailbox(EthercatCom *com, unsigned address, void *data, unsigned length)
Read data from WG0X local bus using mailbox communication. 
 
std::string processor_name_
 
bool readFirmwareCB(ethercat_hardware::SoftProcessorFirmwareRead::Request &request, ethercat_hardware::SoftProcessorFirmwareRead::Response &response)
 
bool releaseReset(const Info &info, std::ostream &err_msg)
Takes soft processor out of reset. 
 
std::string actuator_name_
 
std::vector< Info > processors_
 
ros::ServiceServer read_firmware_service_
service that allows read of soft processor firmware