lslidar_n301_decoder.h
Go to the documentation of this file.
1 /*
2  * This file is part of lslidar_n301 driver.
3  *
4  * The driver is free software: you can redistribute it and/or modify
5  * it under the terms of the GNU General Public License as published by
6  * the Free Software Foundation, either version 3 of the License, or
7  * (at your option) any later version.
8  *
9  * The driver is distributed in the hope that it will be useful,
10  * but WITHOUT ANY WARRANTY; without even the implied warranty of
11  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12  * GNU General Public License for more details.
13  *
14  * You should have received a copy of the GNU General Public License
15  * along with the driver. If not, see <http://www.gnu.org/licenses/>.
16  */
17 
18 #ifndef LSLIDAR_N301_DECODER_H
19 #define LSLIDAR_N301_DECODER_H
20 
21 #define DEG_TO_RAD 0.017453292
22 #define RAD_TO_DEG 57.29577951
23 
24 #include <cmath>
25 #include <vector>
26 #include <string>
27 #include <boost/shared_ptr.hpp>
28 #include "time.h"
29 
30 #include <ros/ros.h>
31 #include <sensor_msgs/PointCloud2.h>
32 #include <sensor_msgs/LaserScan.h>
33 
35 #include <pcl_ros/point_cloud.h>
36 #include <pcl/point_types.h>
37 
38 #include <lslidar_n301_msgs/LslidarN301Packet.h>
39 #include <lslidar_n301_msgs/LslidarN301Point.h>
40 #include <lslidar_n301_msgs/LslidarN301Scan.h>
41 #include <lslidar_n301_msgs/LslidarN301Sweep.h>
42 
43 
45 
46 // Raw lslidar packet constants and structures.
47 static const int SIZE_BLOCK = 100;
48 static const int RAW_SCAN_SIZE = 3;
49 static const int SCANS_PER_BLOCK = 32;
50 static const int BLOCK_DATA_SIZE =
51  (SCANS_PER_BLOCK * RAW_SCAN_SIZE);
52 
53 // According to Bruce Hall DISTANCE_MAX is 65.0, but we noticed
54 // valid packets with readings up to 130.0.
55 static const double DISTANCE_MAX = 130.0;
56 static const double DISTANCE_RESOLUTION = 0.002;
57 static const double DISTANCE_MAX_UNITS =
58  (DISTANCE_MAX / DISTANCE_RESOLUTION + 1.0);
59 
61 static const uint16_t UPPER_BANK = 0xeeff;
62 static const uint16_t LOWER_BANK = 0xddff;
63 
65 static const int FIRINGS_PER_BLOCK = 2;
66 static const int SCANS_PER_FIRING = 16;
67 static const double BLOCK_TDURATION = 110.592; // [µs]
68 static const double DSR_TOFFSET = 2.304; // [µs]
69 static const double FIRING_TOFFSET = 55.296; // [µs]
70 
71 static const int PACKET_SIZE = 1206;
72 static const int BLOCKS_PER_PACKET = 12;
73 static const int PACKET_STATUS_SIZE = 4;
74 static const int SCANS_PER_PACKET =
75  (SCANS_PER_BLOCK * BLOCKS_PER_PACKET);
76 static const int FIRINGS_PER_PACKET =
77  FIRINGS_PER_BLOCK * BLOCKS_PER_PACKET;
78 
79 // Pre-compute the sine and cosine for the altitude angles.
80 static const double scan_altitude[16] = {
81  -0.2617993877991494, 0.017453292519943295,
82  -0.22689280275926285, 0.05235987755982989,
83  -0.19198621771937624, 0.08726646259971647,
84  -0.15707963267948966, 0.12217304763960307,
85  -0.12217304763960307, 0.15707963267948966,
86  -0.08726646259971647, 0.19198621771937624,
87  -0.05235987755982989, 0.22689280275926285,
88  -0.017453292519943295, 0.2617993877991494
89 };
90 
91 static const double cos_scan_altitude[16] = {
92  std::cos(scan_altitude[ 0]), std::cos(scan_altitude[ 1]),
93  std::cos(scan_altitude[ 2]), std::cos(scan_altitude[ 3]),
94  std::cos(scan_altitude[ 4]), std::cos(scan_altitude[ 5]),
95  std::cos(scan_altitude[ 6]), std::cos(scan_altitude[ 7]),
96  std::cos(scan_altitude[ 8]), std::cos(scan_altitude[ 9]),
97  std::cos(scan_altitude[10]), std::cos(scan_altitude[11]),
98  std::cos(scan_altitude[12]), std::cos(scan_altitude[13]),
99  std::cos(scan_altitude[14]), std::cos(scan_altitude[15]),
100 };
101 
102 static const double sin_scan_altitude[16] = {
103  std::sin(scan_altitude[ 0]), std::sin(scan_altitude[ 1]),
104  std::sin(scan_altitude[ 2]), std::sin(scan_altitude[ 3]),
105  std::sin(scan_altitude[ 4]), std::sin(scan_altitude[ 5]),
106  std::sin(scan_altitude[ 6]), std::sin(scan_altitude[ 7]),
107  std::sin(scan_altitude[ 8]), std::sin(scan_altitude[ 9]),
108  std::sin(scan_altitude[10]), std::sin(scan_altitude[11]),
109  std::sin(scan_altitude[12]), std::sin(scan_altitude[13]),
110  std::sin(scan_altitude[14]), std::sin(scan_altitude[15]),
111 };
112 
113 typedef struct{
114  double distance;
115  double intensity;
116 }point_struct;
117 
118 struct PointXYZIT {
120  uint8_t intensity;
121  double timestamp;
122  EIGEN_MAKE_ALIGNED_OPERATOR_NEW // make sure our new allocators are aligned
123 } EIGEN_ALIGN16;
124 
126 public:
127 
129  LslidarN301Decoder(const LslidarN301Decoder&) = delete;
130  LslidarN301Decoder operator=(const LslidarN301Decoder&) = delete;
132 
133  bool initialize();
134 
137 
138 private:
139 
140  union TwoBytes {
141  uint16_t distance;
142  uint8_t bytes[2];
143  };
144 
145  struct RawBlock {
146  uint16_t header;
147  uint16_t rotation;
148  uint8_t data[BLOCK_DATA_SIZE];
149  };
150 
151  struct RawPacket {
153  // uint32_t time_stamp;
154  uint8_t time_stamp_yt[4];
155  uint8_t factory[2];
156  //uint16_t revolution;
157  //uint8_t status[PACKET_STATUS_SIZE];
158  };
159 
160 
161  struct Firing {
162  // Azimuth associated with the first shot within this firing.
164  double azimuth[SCANS_PER_FIRING];
167  };
168 
169  // Intialization sequence
170  bool loadParameters();
171  bool createRosIO();
172 
173 
174  // Callback function for a single lslidar packet.
175  bool checkPacketValidity(const RawPacket* packet);
176  void decodePacket(const RawPacket* packet);
177  void packetCallback(const lslidar_n301_msgs::LslidarN301PacketConstPtr& msg);
178 
179  // Publish data
180  void publishPointCloud();
181 
182  // Publish scan Data
183  void publishScan();
184 
185  // Check if a point is in the required range.
186  bool isPointInRange(const double& distance) {
187  return (distance >= min_range && distance <= max_range);
188  }
189 
190  double rawAzimuthToDouble(const uint16_t& raw_azimuth) {
191  // According to the user manual,
192  // azimuth = raw_azimuth / 100.0;
193  return static_cast<double>(raw_azimuth) / 100.0 * DEG_TO_RAD;
194  }
195 
196  // calc the means_point
197  point_struct getMeans(std::vector<point_struct> clusters);
198 
199  //get gps_base time
200  uint64_t get_gps_stamp(tm t);
201  tm pTime;
202 
204 
205  // time relavated variables
208 
209  // configuration degree base
211  double angle_base;
212 
213  // Configuration parameters
214  double min_range;
215  double max_range;
218  double frequency;
221 
222  double cos_azimuth_table[6300];
223  double sin_azimuth_table[6300];
224 
226  double last_azimuth;
230 
231  // ROS related parameters
234 
235  std::string fixed_frame_id;
236  std::string child_frame_id;
237 
238  lslidar_n301_msgs::LslidarN301SweepPtr sweep_data;
239  sensor_msgs::PointCloud2 point_cloud_data;
240 
245 
246 };
247 
251 typedef pcl::PointCloud<VPoint> VPointCloud;
252 
253 } // end namespace lslidar_n301_decoder
254 
255 POINT_CLOUD_REGISTER_POINT_STRUCT(lslidar_n301_decoder::PointXYZIT,
256  (float, x, x)(float, y, y)(float, z, z)(
257  uint8_t, intensity,
258  intensity)(double, timestamp, timestamp))
259 
260 #endif
static const double scan_altitude[16]
static const int SCANS_PER_BLOCK
boost::shared_ptr< LslidarN301Decoder > LslidarN301DecoderPtr
static const double BLOCK_TDURATION
static const int SCANS_PER_PACKET
ROSCONSOLE_DECL void initialize()
static const int BLOCK_DATA_SIZE
boost::shared_ptr< const LslidarN301Decoder > LslidarN301DecoderConstPtr
lslidar_n301_msgs::LslidarN301SweepPtr sweep_data
static const int SIZE_BLOCK
TFSIMD_FORCE_INLINE tfScalar distance(const Vector3 &v) const
static const int SCANS_PER_FIRING
pcl::PointCloud< VPoint > VPointCloud
static const int BLOCKS_PER_PACKET
static const double FIRING_TOFFSET
static const int PACKET_STATUS_SIZE
static const double DISTANCE_MAX
static const double cos_scan_altitude[16]
static const double sin_scan_altitude[16]
double rawAzimuthToDouble(const uint16_t &raw_azimuth)
uint16_t rotation
0-35999, divide by 100 to get degrees
LslidarN301Decoder::LslidarN301DecoderPtr LslidarN301DecoderPtr
bool isPointInRange(const double &distance)
LslidarN301Decoder::LslidarN301DecoderConstPtr LslidarN301DecoderConstPtr
static const uint16_t LOWER_BANK
static const double DSR_TOFFSET
static const int FIRINGS_PER_PACKET
static const int RAW_SCAN_SIZE
unsigned long uint64_t
Definition: check.cpp:6
#define DEG_TO_RAD
static const double DISTANCE_MAX_UNITS
static const uint16_t UPPER_BANK
static const int FIRINGS_PER_BLOCK
static const double DISTANCE_RESOLUTION
struct lslidar_n301_decoder::PointXYZIT EIGEN_ALIGN16
static const int PACKET_SIZE


lslidar_n301_decoder
Author(s): Nick Shu
autogenerated on Thu Sep 26 2019 03:58:31