35 #ifndef ETHERCAT_HARDWARE__WG_SOFT_PROCESSOR_H 36 #define ETHERCAT_HARDWARE__WG_SOFT_PROCESSOR_H 41 #include "ethercat_hardware/SoftProcessorFirmwareWrite.h" 42 #include "ethercat_hardware/SoftProcessorFirmwareRead.h" 43 #include "ethercat_hardware/SoftProcessorReset.h" 67 const std::string &actuator_name,
68 const std::string &processor_name,
69 unsigned iram_address,
unsigned ctrl_address ) :
79 void add(
WGMailbox *mbx,
const std::string &actuator_name,
const std::string &processor_name,
80 unsigned iram_address,
unsigned ctrl_address);
88 bool writeFirmwareCB(ethercat_hardware::SoftProcessorFirmwareWrite::Request &request,
89 ethercat_hardware::SoftProcessorFirmwareWrite::Response &response);
90 bool readFirmwareCB(ethercat_hardware::SoftProcessorFirmwareRead::Request &request,
91 ethercat_hardware::SoftProcessorFirmwareRead::Response &response);
92 bool resetCB(ethercat_hardware::SoftProcessorReset::Request &request,
93 ethercat_hardware::SoftProcessorReset::Response &response);
106 const WGSoftProcessor::Info*
get(
const std::string &actuator_name,
const std::string &processor_name, std::ostream &err_out)
const;
114 #endif //ETHERCAT_HARDWARE__WG_SOFT_PROCESSOR_H 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)
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
std::string processor_name_
Info(WGMailbox *mbx, const std::string &actuator_name, const std::string &processor_name, unsigned iram_address, unsigned ctrl_address)
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