/* -*- mode: C++ -*- * All right reserved, Sure_star Coop. * @Technic Support: * $Id$ */ #ifndef _RFANS_IOAPI_H_ #define _RFANS_IOAPI_H_ #include #include #include //#include //#include #include #include #include #include #include #include #include #include #include //#include #include "ssFrameLib.h" class SSBufferDec; namespace rfans_driver { /** @brief Rfans IOAPI base class */ static uint16_t DATA_PORT_NUMBER = 2014; class IOAPI { public: IOAPI(); ~IOAPI(); /** @brief Read one Rfans packet. * * @param packet from Rfans * * @returns 0 if successful, * -1 if end of file * > 0 if incomplete packet (is this possible?) */ /** @brief Write . */ virtual int write(unsigned char *data, int size) = 0; /** @brief read . */ virtual int read(unsigned char *data, int size) = 0; /** @brief reset . */ virtual int reset() = 0; virtual int HW_WRREG(int flag, int regAddress, unsigned int regData); protected: SSBufferDec *m_bufferPro; }; //////////////////////////////////////////////////////////////////////// // InputSocket class implementation //////////////////////////////////////////////////////////////////////// /** @brief Rfans IOAPI from socket. */ class IOSocketAPI : public IOAPI { public: IOSocketAPI(std::string ipstr = DEVICE_IP_STRING, uint16_t devport = DEVICE_PORT_NUMBER, int16_t pcport = PC_PORT_NUMBER); virtual ~IOSocketAPI(); virtual int write(unsigned char *data, int size); virtual int read(unsigned char *data, int size); virtual int reset(); private: int m_sockfd; in_addr devip_; sockaddr_in m_devaddr; // ros::NodeHandle private_nh_; uint16_t m_devport_; uint16_t m_pcport_; std::string devip_str_; }; } #endif