Classes | Namespaces | Macros | Typedefs | Variables
lslidar_n301_decoder.h File Reference
#include <cmath>
#include <vector>
#include <string>
#include <boost/shared_ptr.hpp>
#include "time.h"
#include <ros/ros.h>
#include <sensor_msgs/PointCloud2.h>
#include <sensor_msgs/LaserScan.h>
#include <pcl_conversions/pcl_conversions.h>
#include <pcl_ros/point_cloud.h>
#include <pcl/point_types.h>
#include <lslidar_n301_msgs/LslidarN301Packet.h>
#include <lslidar_n301_msgs/LslidarN301Point.h>
#include <lslidar_n301_msgs/LslidarN301Scan.h>
#include <lslidar_n301_msgs/LslidarN301Sweep.h>
Include dependency graph for lslidar_n301_decoder.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  lslidar_n301_decoder::LslidarN301Decoder::Firing
 
class  lslidar_n301_decoder::LslidarN301Decoder
 
struct  lslidar_n301_decoder::point_struct
 
struct  lslidar_n301_decoder::PointXYZIT
 
struct  lslidar_n301_decoder::LslidarN301Decoder::RawBlock
 
struct  lslidar_n301_decoder::LslidarN301Decoder::RawPacket
 
union  lslidar_n301_decoder::LslidarN301Decoder::TwoBytes
 

Namespaces

 lslidar_n301_decoder
 

Macros

#define DEG_TO_RAD   0.017453292
 
#define RAD_TO_DEG   57.29577951
 

Typedefs

typedef LslidarN301Decoder::LslidarN301DecoderConstPtr lslidar_n301_decoder::LslidarN301DecoderConstPtr
 
typedef LslidarN301Decoder::LslidarN301DecoderPtr lslidar_n301_decoder::LslidarN301DecoderPtr
 
typedef PointXYZIT lslidar_n301_decoder::VPoint
 
typedef pcl::PointCloud< VPoint > lslidar_n301_decoder::VPointCloud
 

Variables

static const int lslidar_n301_decoder::BLOCK_DATA_SIZE
 
static const double lslidar_n301_decoder::BLOCK_TDURATION = 110.592
 
static const int lslidar_n301_decoder::BLOCKS_PER_PACKET = 12
 
static const double lslidar_n301_decoder::cos_scan_altitude [16]
 
static const double lslidar_n301_decoder::DISTANCE_MAX = 130.0
 
static const double lslidar_n301_decoder::DISTANCE_MAX_UNITS
 
static const double lslidar_n301_decoder::DISTANCE_RESOLUTION = 0.002
 
static const double lslidar_n301_decoder::DSR_TOFFSET = 2.304
 
struct lslidar_n301_decoder::PointXYZIT lslidar_n301_decoder::EIGEN_ALIGN16
 
static const double lslidar_n301_decoder::FIRING_TOFFSET = 55.296
 
static const int lslidar_n301_decoder::FIRINGS_PER_BLOCK = 2
 
static const int lslidar_n301_decoder::FIRINGS_PER_PACKET
 
static const uint16_t lslidar_n301_decoder::LOWER_BANK = 0xddff
 
static const int lslidar_n301_decoder::PACKET_SIZE = 1206
 
static const int lslidar_n301_decoder::PACKET_STATUS_SIZE = 4
 
static const int lslidar_n301_decoder::RAW_SCAN_SIZE = 3
 
static const double lslidar_n301_decoder::scan_altitude [16]
 
static const int lslidar_n301_decoder::SCANS_PER_BLOCK = 32
 
static const int lslidar_n301_decoder::SCANS_PER_FIRING = 16
 
static const int lslidar_n301_decoder::SCANS_PER_PACKET
 
static const double lslidar_n301_decoder::sin_scan_altitude [16]
 
static const int lslidar_n301_decoder::SIZE_BLOCK = 100
 
static const uint16_t lslidar_n301_decoder::UPPER_BANK = 0xeeff
 

Macro Definition Documentation

#define DEG_TO_RAD   0.017453292

Definition at line 21 of file lslidar_n301_decoder.h.

#define RAD_TO_DEG   57.29577951

Definition at line 22 of file lslidar_n301_decoder.h.



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