Go to the documentation of this file.00001
00026 #ifndef SR_EDC_ETHERCAT_DRIVERS_SR0X_H
00027 #define SR_EDC_ETHERCAT_DRIVERS_SR0X_H
00028
00029 #include <ros_ethercat_hardware/ethercat_hardware.h>
00030 #include <sr_edc_ethercat_drivers/motor_trace_buffer.h>
00031 #include <string>
00032
00033 class SR0X :
00034 public EthercatDevice
00035 {
00036 public:
00037 virtual int initialize(hardware_interface::HardwareInterface *hw, bool allow_unprogrammed = true);
00038
00039 protected:
00040 uint8_t fw_major_;
00041 uint8_t fw_minor_;
00042 uint8_t board_major_;
00043 uint8_t board_minor_;
00044
00045 enum
00046 {
00047 MODE_OFF = 0x00,
00048 MODE_ENABLE = (1 << 0),
00049 MODE_CURRENT = (1 << 1),
00050 MODE_SAFETY_RESET = (1 << 4),
00051 MODE_SAFETY_LOCKOUT = (1 << 5),
00052 MODE_UNDERVOLTAGE = (1 << 6),
00053 MODE_RESET = (1 << 7)
00054 };
00055
00056 enum
00057 {
00058 EC_PRODUCT_ID_BRIDGE = 0,
00059 EC_PRODUCT_ID_SHADOWCAN = 2,
00060 EC_PRODUCT_ID_DUALMOTOR = 3,
00061 };
00062
00063 string reason_;
00064 int level_;
00065 int device_offset_;
00066
00067 protected:
00068 int command_base_;
00069 int status_base_;
00070 };
00071
00072 #endif // SR_EDC_ETHERCAT_DRIVERS_SR0X_H
00073