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