ioapi.h 2.0 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889909192
  1. /* -*- mode: C++ -*-
  2. * All right reserved, Sure_star Coop.
  3. * @Technic Support: <sdk@isurestar.com>
  4. * $Id$
  5. */
  6. #ifndef _RFANS_IOAPI_H_
  7. #define _RFANS_IOAPI_H_
  8. #include <unistd.h>
  9. #include <stdio.h>
  10. #include <netinet/in.h>
  11. //#include <starros/Packet.h>
  12. //#include <pcap.h>
  13. #include <unistd.h>
  14. #include <sys/socket.h>
  15. #include <arpa/inet.h>
  16. #include <poll.h>
  17. #include <errno.h>
  18. #include <fcntl.h>
  19. #include <sys/file.h>
  20. #include <string>
  21. #include <sstream>
  22. //#include <sensor_msgs/PointCloud2.h>
  23. #include "ssFrameLib.h"
  24. class SSBufferDec;
  25. namespace rfans_driver
  26. {
  27. /** @brief Rfans IOAPI base class */
  28. static uint16_t DATA_PORT_NUMBER = 2014;
  29. class IOAPI
  30. {
  31. public:
  32. IOAPI();
  33. ~IOAPI();
  34. /** @brief Read one Rfans packet.
  35. *
  36. * @param packet from Rfans
  37. *
  38. * @returns 0 if successful,
  39. * -1 if end of file
  40. * > 0 if incomplete packet (is this possible?)
  41. */
  42. /** @brief Write . */
  43. virtual int write(unsigned char *data, int size) = 0;
  44. /** @brief read . */
  45. virtual int read(unsigned char *data, int size) = 0;
  46. /** @brief reset . */
  47. virtual int reset() = 0;
  48. virtual int HW_WRREG(int flag, int regAddress, unsigned int regData);
  49. protected:
  50. SSBufferDec *m_bufferPro;
  51. };
  52. ////////////////////////////////////////////////////////////////////////
  53. // InputSocket class implementation
  54. ////////////////////////////////////////////////////////////////////////
  55. /** @brief Rfans IOAPI from socket. */
  56. class IOSocketAPI : public IOAPI
  57. {
  58. public:
  59. IOSocketAPI(std::string ipstr = DEVICE_IP_STRING,
  60. uint16_t devport = DEVICE_PORT_NUMBER,
  61. int16_t pcport = PC_PORT_NUMBER);
  62. virtual ~IOSocketAPI();
  63. virtual int write(unsigned char *data, int size);
  64. virtual int read(unsigned char *data, int size);
  65. virtual int reset();
  66. private:
  67. int m_sockfd;
  68. in_addr devip_;
  69. sockaddr_in m_devaddr;
  70. // ros::NodeHandle private_nh_;
  71. uint16_t m_devport_;
  72. uint16_t m_pcport_;
  73. std::string devip_str_;
  74. };
  75. }
  76. #endif