input.h 3.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137
  1. // Copyright (C) 2007, 2009, 2010, 2012, 2015Yaxin Liu, Patrick Beeson, Austin Robot Technology, Jack O'Quin
  2. // All rights reserved.
  3. //
  4. // Software License Agreement (BSD License 2.0)
  5. //
  6. // Redistribution and use in source and binary forms, with or without
  7. // modification, are permitted provided that the following conditions
  8. // are met:
  9. //
  10. // * Redistributions of source code must retain the above copyright
  11. // notice, this list of conditions and the following disclaimer.
  12. // * Redistributions in binary form must reproduce the above
  13. // copyright notice, this list of conditions and the following
  14. // disclaimer in the documentation and/or other materials provided
  15. // with the distribution.
  16. // * Neither the name of {copyright_holder} nor the names of its
  17. // contributors may be used to endorse or promote products derived
  18. // from this software without specific prior written permission.
  19. //
  20. // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
  21. // "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
  22. // LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
  23. // FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
  24. // COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
  25. // INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
  26. // BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
  27. // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
  28. // CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
  29. // LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
  30. // ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
  31. // POSSIBILITY OF SUCH DAMAGE.
  32. /** @file
  33. *
  34. * Velodyne 3D LIDAR data input classes
  35. *
  36. * These classes provide raw Velodyne LIDAR input packets from
  37. * either a live socket interface or a previously-saved PCAP dump
  38. * file.
  39. *
  40. * Classes:
  41. *
  42. * velodyne::Input -- base class for accessing the data
  43. * independently of its source
  44. *
  45. * velodyne::InputSocket -- derived class reads live data from the
  46. * device via a UDP socket
  47. *
  48. * velodyne::InputPCAP -- derived class provides a similar interface
  49. * from a PCAP dump file
  50. */
  51. #ifndef VELODYNE_DRIVER_INPUT_H
  52. #define VELODYNE_DRIVER_INPUT_H
  53. #include <unistd.h>
  54. #include <stdio.h>
  55. #include <netinet/in.h>
  56. #include <string>
  57. #include <vector>
  58. #include <glog/logging.h>
  59. // #include <Eigen/Core>
  60. const int HDL_NUM_ROT_ANGLES = 36001;
  61. const int HDL_LASER_PER_FIRING = 32;
  62. const int VLP_LASER_PER_FIRING = 16;
  63. const int HDL_MAX_NUM_LASERS = 64;
  64. const int HDL_FIRING_PER_PKT = 12;
  65. const int PACKET_SIZE = 1206;
  66. // #pragma pack(push, 1)
  67. // struct HDLLaserReturn
  68. // {
  69. // unsigned short distance;
  70. // unsigned char intensity;
  71. // };
  72. // struct HDLFiringData
  73. // {
  74. // unsigned short blockIdentifier;
  75. // unsigned short rotationalPosition;
  76. // HDLLaserReturn laserReturns[HDL_LASER_PER_FIRING];
  77. // };
  78. // enum HDLBlock
  79. // {
  80. // BLOCK_0_TO_31 = 0xeeff,
  81. // BLOCK_32_TO_63 = 0xddff
  82. // };
  83. // struct HDLDataPacket
  84. // {
  85. // HDLFiringData firingData[HDL_FIRING_PER_PKT];
  86. // unsigned int gpsTimestamp;
  87. // unsigned char blank1;
  88. // unsigned char blank2;
  89. // };
  90. // #pragma pack(pop)
  91. namespace velodyne_driver
  92. {
  93. static uint16_t DATA_PORT_NUMBER = 2368; // default data port
  94. /** @brief Live Velodyne input from socket. */
  95. class InputSocket
  96. {
  97. public:
  98. /** @brief constructor
  99. *
  100. * @param ip desired ip for lidar, input empty string to listen any data from assigned udp port.
  101. * @param port UDP port number
  102. */
  103. InputSocket(){}
  104. ~InputSocket(){}
  105. bool init(std::string ip, uint16_t port = DATA_PORT_NUMBER);
  106. void uninit();
  107. // return 0 success, -1 error
  108. int getPacket(unsigned char* pkt);
  109. private:
  110. uint16_t m_port;
  111. std::string m_devip_str;
  112. int m_sockfd;
  113. in_addr m_devip;
  114. };
  115. } // namespace velodyne_driver
  116. #endif // VELODYNE_DRIVER_INPUT_H