rawdata.h 11 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349
  1. // Copyright (C) 2007, 2009, 2010, 2012, 2019 Yaxin Liu, Patrick Beeson, Jack O'Quin, Joshua Whitley
  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. * @brief Interfaces for interpreting raw packets from the Velodyne 3D LIDAR.
  35. *
  36. * @author Yaxin Liu
  37. * @author Patrick Beeson
  38. * @author Jack O'Quin
  39. * @author Youchen Tang
  40. */
  41. #ifndef VELODYNE_POINTCLOUD_RAWDATA_H
  42. #define VELODYNE_POINTCLOUD_RAWDATA_H
  43. #include <errno.h>
  44. #include <stdint.h>
  45. #include <string>
  46. #include <math.h>
  47. #include <vector>
  48. #include <mutex>
  49. #include <atomic>
  50. #include <chrono>
  51. #include <glog/logging.h>
  52. #include <Eigen/Core>
  53. // #include <pcl/point_types.h>
  54. // #include <pcl/point_cloud.h>
  55. #include "calibration.h"
  56. struct Lidar_point
  57. {
  58. double x;
  59. double y;
  60. double z;
  61. uint16_t ring;
  62. uint16_t azimuth;
  63. float distance;
  64. float intensity;
  65. float timestamp;
  66. Lidar_point()
  67. {
  68. x = y = z = distance = 0.0;
  69. intensity = 0;
  70. ring = 0;
  71. azimuth = 0;
  72. timestamp = 0;
  73. }
  74. Lidar_point(double x, double y, double z, uint16_t ring, uint16_t azimuth, float distance, float intensity, float timestamp)
  75. {
  76. this->x = x;
  77. this->y = y;
  78. this->z = z;
  79. this->ring = ring;
  80. this->azimuth = azimuth;
  81. this->distance = distance;
  82. this->intensity = intensity;
  83. this->timestamp = timestamp;
  84. }
  85. Lidar_point(const Lidar_point &point)
  86. {
  87. *this = point;
  88. }
  89. Lidar_point &operator=(const Lidar_point &point)
  90. {
  91. x = point.x;
  92. y = point.y;
  93. z = point.z;
  94. intensity = point.intensity;
  95. ring = point.ring;
  96. azimuth = point.azimuth;
  97. distance = point.distance;
  98. timestamp = point.timestamp;
  99. return *this;
  100. }
  101. void transform(Eigen::Matrix<double, 4, 4> transform_matrix)
  102. {
  103. Eigen::Vector4d point{x, y, z, 1};
  104. point = transform_matrix * point;
  105. x = point.x() / point.w();
  106. y = point.y() / point.w();
  107. z = point.z() / point.w();
  108. // printf("point: %.6f %.6f %.6f %.6f \n", x, y, z, point.w());
  109. }
  110. };
  111. // struct PointXYZIRT
  112. // {
  113. // PCL_ADD_POINT4D; // quad-word XYZ
  114. // float intensity; ///< laser intensity reading
  115. // uint16_t ring; ///< laser ring number
  116. // float time; ///< laser time reading
  117. // EIGEN_MAKE_ALIGNED_OPERATOR_NEW // ensure proper alignment
  118. // } EIGEN_ALIGN16;
  119. // POINT_CLOUD_REGISTER_POINT_STRUCT(PointXYZIRT,
  120. // (float, x, x)(float, y, y)(float, z, z)(float, intensity, intensity)(uint16_t, ring, ring)(float, time, time))
  121. namespace velodyne_rawdata
  122. {
  123. /**
  124. * Raw Velodyne packet constants and structures.
  125. */
  126. static const int SIZE_BLOCK = 100;
  127. static const int RAW_SCAN_SIZE = 3;
  128. static const int SCANS_PER_BLOCK = 32;
  129. static const int BLOCK_DATA_SIZE = (SCANS_PER_BLOCK * RAW_SCAN_SIZE);
  130. static const float ROTATION_RESOLUTION = 0.01f; // [deg]
  131. static const uint16_t ROTATION_MAX_UNITS = 36000u; // [deg/100]
  132. /** @todo make this work for both big and little-endian machines */
  133. static const uint16_t UPPER_BANK = 0xeeff;
  134. static const uint16_t LOWER_BANK = 0xddff;
  135. /** Special Defines for VLP16 support **/
  136. static const int VLP16_FIRINGS_PER_BLOCK = 2;
  137. static const int VLP16_SCANS_PER_FIRING = 16;
  138. static const float VLP16_BLOCK_TDURATION = 110.592f; // [µs]
  139. static const float VLP16_DSR_TOFFSET = 2.304f; // [µs]
  140. static const float VLP16_FIRING_TOFFSET = 55.296f; // [µs]
  141. /** \brief Raw Velodyne data block.
  142. *
  143. * Each block contains data from either the upper or lower laser
  144. * bank. The device returns three times as many upper bank blocks.
  145. *
  146. * use stdint.h types, so things work with both 64 and 32-bit machines
  147. */
  148. typedef struct raw_block
  149. {
  150. uint16_t header; ///< UPPER_BANK or LOWER_BANK
  151. uint16_t rotation; ///< 0-35999, divide by 100 to get degrees
  152. uint8_t data[BLOCK_DATA_SIZE];
  153. } raw_block_t;
  154. /** used for unpacking the first two data bytes in a block
  155. *
  156. * They are packed into the actual data stream misaligned. I doubt
  157. * this works on big endian machines.
  158. */
  159. union two_bytes
  160. {
  161. uint16_t uint;
  162. uint8_t bytes[2];
  163. };
  164. static const int PACKET_SIZE = 1206;
  165. static const int BLOCKS_PER_PACKET = 12;
  166. static const int PACKET_STATUS_SIZE = 4;
  167. static const int SCANS_PER_PACKET = (SCANS_PER_BLOCK * BLOCKS_PER_PACKET);
  168. /** Special Definitions for VLS128 support **/
  169. // These are used to detect which bank of 32 lasers is in this block
  170. static const uint16_t VLS128_BANK_1 = 0xeeff;
  171. static const uint16_t VLS128_BANK_2 = 0xddff;
  172. static const uint16_t VLS128_BANK_3 = 0xccff;
  173. static const uint16_t VLS128_BANK_4 = 0xbbff;
  174. static const float VLS128_CHANNEL_TDURATION = 2.665f; // [µs] Channels corresponds to one laser firing
  175. static const float VLS128_SEQ_TDURATION = 53.3f; // [µs] Sequence is a set of laser firings including recharging
  176. static const float VLS128_TOH_ADJUSTMENT = 8.7f; // [µs] μs. Top Of the Hour is aligned with the fourth firing group in a firing sequence.
  177. static const float VLS128_DISTANCE_RESOLUTION = 0.004f; // [m]
  178. static const float VLS128_MODEL_ID = 161;
  179. /** \brief Raw Velodyne packet.
  180. *
  181. * revolution is described in the device manual as incrementing
  182. * (mod 65536) for each physical turn of the device. Our device
  183. * seems to alternate between two different values every third
  184. * packet. One value increases, the other decreases.
  185. *
  186. * \todo figure out if revolution is only present for one of the
  187. * two types of status fields
  188. *
  189. * status has either a temperature encoding or the microcode level
  190. */
  191. typedef struct raw_packet
  192. {
  193. raw_block_t blocks[BLOCKS_PER_PACKET];
  194. uint16_t revolution;
  195. uint8_t status[PACKET_STATUS_SIZE];
  196. } raw_packet_t;
  197. /** \brief Velodyne data conversion class */
  198. class RawData
  199. {
  200. public:
  201. /** configuration parameters */
  202. typedef struct
  203. {
  204. std::string model;
  205. std::string calibrationFile; ///< calibration file name
  206. double max_range; ///< maximum range to publish
  207. double min_range; ///< minimum range to publish
  208. int min_angle; ///< minimum angle to publish
  209. int max_angle; ///< maximum angle to publish
  210. double tmp_min_angle;
  211. double tmp_max_angle;
  212. } Config;
  213. RawData();
  214. ~RawData()
  215. {
  216. }
  217. /** \brief Set up for data processing.
  218. *
  219. * Perform initializations needed before data processing can
  220. * begin:
  221. *
  222. * - read device-specific angles calibration
  223. *
  224. * @param model model name, i.e. VLP16 32E 32C 128S
  225. * @param calib_file absolute path to the calibration file
  226. * @param max_range maximum range of point distance, in meter
  227. * @param min_range minimum range of point distance, in meter
  228. * @param min_angle minimum azimuth of point, in degree
  229. * @param max_angle maximum azimuth of point, in degree
  230. * @returns an optional calibration
  231. */
  232. bool setup(std::string model, std::string calib_file, double max_range, double min_range, int min_angle, int max_angle);
  233. void setupSinCosCache();
  234. void setupAzimuthCache();
  235. bool loadCalibration();
  236. /** \brief Set up for data processing offline.
  237. * Performs the same initialization as in setup, in the abscence of a ros::NodeHandle.
  238. * this method is useful if unpacking data directly from bag files, without passing
  239. * through a communication overhead.
  240. *
  241. * @param calibration_file path to the calibration file
  242. * @param max_range_ cutoff for maximum range
  243. * @param min_range_ cutoff for minimum range
  244. * @returns 0 if successful;
  245. * errno value for failure
  246. */
  247. int setupOffline(std::string calibration_file, double max_range_, double min_range_);
  248. // unpack velodyne lidar packets, convert to points and stored in data vector
  249. void unpack(const unsigned char *pkt, std::vector<Lidar_point> &data);
  250. void setParameters(double min_range, double max_range, double view_direction, double view_width);
  251. int scansPerPacket() const;
  252. void getCloud(std::vector<Lidar_point> &data);
  253. void getConfig(Config &conf){
  254. conf.model = config_.model;
  255. conf.calibrationFile = config_.calibrationFile;
  256. conf.max_range = config_.max_range;
  257. conf.min_range = config_.min_range;
  258. conf.min_angle = config_.min_angle;
  259. conf.max_angle = config_.max_angle;
  260. conf.tmp_min_angle = config_.tmp_min_angle;
  261. conf.tmp_max_angle = config_.tmp_max_angle;
  262. }
  263. void getCalib(velodyne_pointcloud::Calibration &calib)
  264. {
  265. calib.distance_resolution_m = calibration_.distance_resolution_m;
  266. calib.laser_corrections_map = calibration_.laser_corrections_map;
  267. calib.laser_corrections = calibration_.laser_corrections;
  268. calib.num_lasers = calibration_.num_lasers;
  269. calib.initialized = calibration_.initialized;
  270. }
  271. bool isInitialized() { return mb_initialized; }
  272. private:
  273. Config config_;
  274. bool mb_initialized;
  275. /**
  276. * Calibration file
  277. */
  278. velodyne_pointcloud::Calibration calibration_;
  279. float sin_rot_table_[ROTATION_MAX_UNITS];
  280. float cos_rot_table_[ROTATION_MAX_UNITS];
  281. // Caches the azimuth percent offset for the VLS-128 laser firings
  282. float vls_128_laser_azimuth_cache[16];
  283. // timing offset lookup table
  284. std::vector<std::vector<float>> timing_offsets;
  285. /** \brief setup per-point timing offsets
  286. *
  287. * Runs during initialization and determines the firing time for each point in the scan
  288. *
  289. * NOTE: Does not support all sensors yet (vlp16, vlp32, and hdl32 are currently supported)
  290. */
  291. bool buildTimings();
  292. /** add private function to handle the VLP16 **/
  293. // add range limit and utc timestamp by yct
  294. void unpack_vlp16(const unsigned char *pkt, std::vector<Lidar_point> &data);
  295. void unpack_vls128(const unsigned char *pkt, std::vector<Lidar_point> &data);
  296. /** in-line test whether a point is in range */
  297. inline bool pointInRange(float range)
  298. {
  299. return (range >= config_.min_range && range <= config_.max_range);
  300. }
  301. };
  302. } // namespace velodyne_rawdata
  303. #endif // VELODYNE_POINTCLOUD_RAWDATA_H