Classes | Namespaces | Typedefs | Variables
rawdata.h File Reference

Interfaces for interpreting raw packets from the Robosense 3D LIDAR. More...

#include <ros/ros.h>
#include <ros/package.h>
#include <rslidar_msgs/rslidarPacket.h>
#include <rslidar_msgs/rslidarScan.h>
#include "std_msgs/String.h"
#include <pcl/point_types.h>
#include <pcl_ros/point_cloud.h>
#include <pcl_ros/impl/transforms.hpp>
#include <pcl_conversions/pcl_conversions.h>
#include <stdio.h>
Include dependency graph for rawdata.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  rslidar_rawdata::raw_block
 Raw rslidar data block. More...
 
struct  rslidar_rawdata::raw_packet
 Raw Rsldar packet. More...
 
class  rslidar_rawdata::RawData
 RSLIDAR data conversion class. More...
 
union  rslidar_rawdata::two_bytes
 

Namespaces

 rslidar_rawdata
 

Typedefs

typedef struct rslidar_rawdata::raw_block rslidar_rawdata::raw_block_t
 Raw rslidar data block. More...
 
typedef struct rslidar_rawdata::raw_packet rslidar_rawdata::raw_packet_t
 Raw Rsldar packet. More...
 

Variables

float rslidar_rawdata::aIntensityCal [7][32]
 
float rslidar_rawdata::aIntensityCal_old [1600][32]
 
static const int rslidar_rawdata::BLOCK_DATA_SIZE = (SCANS_PER_BLOCK * RAW_SCAN_SIZE)
 
static const int rslidar_rawdata::BLOCKS_PER_PACKET = 12
 
bool rslidar_rawdata::Curvesis_new = true
 
float rslidar_rawdata::CurvesRate [32]
 
static const float rslidar_rawdata::DISTANCE_MAX = 200.0f
 
static const float rslidar_rawdata::DISTANCE_MAX_UNITS = (DISTANCE_MAX / DISTANCE_RESOLUTION + 1.0f)
 
static const float rslidar_rawdata::DISTANCE_MIN = 0.2f
 
static const float rslidar_rawdata::DISTANCE_RESOLUTION = 0.01f
 
static const float rslidar_rawdata::DISTANCE_RESOLUTION_NEW = 0.005f
 
int rslidar_rawdata::g_ChannelNum [32][51]
 
float rslidar_rawdata::HORI_ANGLE [32]
 
static const uint16_t rslidar_rawdata::LOWER_BANK = 0xddff
 
int rslidar_rawdata::numOfLasers = 16
 
static const int rslidar_rawdata::PACKET_SIZE = 1248
 
static const int rslidar_rawdata::PACKET_STATUS_SIZE = 4
 
static const int rslidar_rawdata::RAW_SCAN_SIZE = 3
 
static const float rslidar_rawdata::RL32_FIRING_TOFFSET = 50.0f
 
static const uint16_t rslidar_rawdata::ROTATION_MAX_UNITS = 36000
 
static const float rslidar_rawdata::ROTATION_RESOLUTION = 0.01f
 
static const float rslidar_rawdata::RS16_BLOCK_TDURATION = 100.0f
 
static const float rslidar_rawdata::RS16_DSR_TOFFSET = 3.0f
 
static const float rslidar_rawdata::RS16_FIRING_TOFFSET = 50.0f
 
static const int rslidar_rawdata::RS16_FIRINGS_PER_BLOCK = 2
 
static const int rslidar_rawdata::RS16_SCANS_PER_FIRING = 16
 
static const float rslidar_rawdata::RS32_BLOCK_TDURATION = 50.0f
 
static const float rslidar_rawdata::RS32_DSR_TOFFSET = 3.0f
 
static const int rslidar_rawdata::RS32_FIRINGS_PER_BLOCK = 1
 
static const int rslidar_rawdata::RS32_SCANS_PER_FIRING = 32
 
static const int rslidar_rawdata::SCANS_PER_BLOCK = 32
 
static const int rslidar_rawdata::SCANS_PER_PACKET = (SCANS_PER_BLOCK * BLOCKS_PER_PACKET)
 
static const int rslidar_rawdata::SIZE_BLOCK = 100
 
float rslidar_rawdata::temper = 31.0
 
static const int rslidar_rawdata::TEMPERATURE_MIN = 31
 
int rslidar_rawdata::TEMPERATURE_RANGE = 40
 
int rslidar_rawdata::tempPacketNum = 0
 
static const uint16_t rslidar_rawdata::UPPER_BANK = 0xeeff
 
float rslidar_rawdata::VERT_ANGLE [32]
 

Detailed Description

Interfaces for interpreting raw packets from the Robosense 3D LIDAR.

Author
Yaxin Liu
Patrick Beeson
Jack O'Quin
Tony Zhang

Definition in file rawdata.h.



rslidar_pointcloud
Author(s): Tony Zhang , Tony Zhang, George Wang, Piyush Khandelwal, Jesse Vera
autogenerated on Mon Jun 10 2019 14:41:10