18 #ifndef LSLIDAR_N301_DECODER_H 19 #define LSLIDAR_N301_DECODER_H 21 #define DEG_TO_RAD 0.017453292 22 #define RAD_TO_DEG 57.29577951 27 #include <boost/shared_ptr.hpp> 31 #include <sensor_msgs/PointCloud2.h> 32 #include <sensor_msgs/LaserScan.h> 36 #include <pcl/point_types.h> 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> 58 (DISTANCE_MAX / DISTANCE_RESOLUTION + 1.0);
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
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]),
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]),
122 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
154 uint8_t time_stamp_yt[4];
170 bool loadParameters();
175 bool checkPacketValidity(
const RawPacket* packet);
176 void decodePacket(
const RawPacket* packet);
177 void packetCallback(
const lslidar_n301_msgs::LslidarN301PacketConstPtr& msg);
180 void publishPointCloud();
187 return (distance >= min_range && distance <= max_range);
193 return static_cast<double>(raw_azimuth) / 100.0 *
DEG_TO_RAD;
197 point_struct getMeans(std::vector<point_struct> clusters);
222 double cos_azimuth_table[6300];
223 double sin_azimuth_table[6300];
256 (
float, x, x)(
float, y, y)(
float, z, z)(
static const double scan_altitude[16]
static const int SCANS_PER_BLOCK
boost::shared_ptr< LslidarN301Decoder > LslidarN301DecoderPtr
uint64_t packet_timestamp
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
uint16_t header
UPPER_BANK or LOWER_BANK.
pcl::PointCloud< VPoint > VPointCloud
static const int BLOCKS_PER_PACKET
uint64_t sweep_end_time_gps
ros::Publisher point_cloud_pub
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
std::string child_frame_id
static const uint16_t LOWER_BANK
static const double DSR_TOFFSET
static const int FIRINGS_PER_PACKET
static const int RAW_SCAN_SIZE
static const double DISTANCE_MAX_UNITS
static const uint16_t UPPER_BANK
sensor_msgs::PointCloud2 point_cloud_data
static const int FIRINGS_PER_BLOCK
std::string fixed_frame_id
static const double DISTANCE_RESOLUTION
struct lslidar_n301_decoder::PointXYZIT EIGEN_ALIGN16
ros::Subscriber packet_sub
uint64_t sweep_end_time_hardware
static const int PACKET_SIZE