Classes | Public Types | Public Member Functions | Private Member Functions | Private Attributes | List of all members
lslidar_c16_decoder::LslidarC16Decoder Class Reference

#include <lslidar_c16_decoder.h>

Classes

struct  Firing
 
struct  RawBlock
 
struct  RawPacket
 
union  TwoBytes
 

Public Types

typedef boost::shared_ptr< const LslidarC16DecoderLslidarC16DecoderConstPtr
 
typedef boost::shared_ptr< LslidarC16DecoderLslidarC16DecoderPtr
 

Public Member Functions

bool initialize ()
 
 LslidarC16Decoder (ros::NodeHandle &n, ros::NodeHandle &pn)
 
 LslidarC16Decoder (const LslidarC16Decoder &)=delete
 
LslidarC16Decoder operator= (const LslidarC16Decoder &)=delete
 
 ~LslidarC16Decoder ()
 

Private Member Functions

bool checkPacketValidity (const RawPacket *packet)
 
bool createRosIO ()
 
void decodePacket (const RawPacket *packet)
 
point_struct getMeans (std::vector< point_struct > clusters)
 
bool isPointInRange (const double &distance)
 
void layerCallback (const std_msgs::Int8Ptr &msg)
 
bool loadParameters ()
 
void packetCallback (const lslidar_c16_msgs::LslidarC16PacketConstPtr &msg)
 
void publishChannelScan ()
 
void publishPointCloud ()
 
void publishScan ()
 
double rawAzimuthToDouble (const uint16_t &raw_azimuth)
 

Private Attributes

double angle3_disable_max
 
double angle3_disable_min
 
double angle_base
 
double angle_disable_max
 
double angle_disable_min
 
bool apollo_interface
 
ros::Publisher channel_scan_pub
 
double cos_azimuth_table [6300]
 
Firing firings [FIRINGS_PER_PACKET]
 
std::string frame_id
 
double frequency
 
bool is_first_sweep
 
double last_azimuth
 
int layer_num
 
ros::Subscriber layer_sub
 
double max_range
 
double min_range
 
lslidar_c16_msgs::LslidarC16LayerPtr multi_scan
 
ros::NodeHandle nh
 
double packet_start_time
 
ros::Subscriber packet_sub
 
ros::NodeHandle pnh
 
sensor_msgs::PointCloud2 point_cloud_data
 
ros::Publisher point_cloud_pub
 
int point_num
 
bool publish_point_cloud
 
bool publish_scan
 
ros::Publisher scan_pub
 
double sin_azimuth_table [6300]
 
lslidar_c16_msgs::LslidarC16SweepPtr sweep_data
 
ros::Publisher sweep_pub
 
double sweep_start_time
 
bool use_gps_ts
 

Detailed Description

Definition at line 126 of file lslidar_c16_decoder.h.

Member Typedef Documentation

Definition at line 137 of file lslidar_c16_decoder.h.

Definition at line 136 of file lslidar_c16_decoder.h.

Constructor & Destructor Documentation

lslidar_c16_decoder::LslidarC16Decoder::LslidarC16Decoder ( ros::NodeHandle n,
ros::NodeHandle pn 
)

Definition at line 24 of file lslidar_c16_decoder.cpp.

lslidar_c16_decoder::LslidarC16Decoder::LslidarC16Decoder ( const LslidarC16Decoder )
delete
lslidar_c16_decoder::LslidarC16Decoder::~LslidarC16Decoder ( )
inline

Definition at line 132 of file lslidar_c16_decoder.h.

Member Function Documentation

bool lslidar_c16_decoder::LslidarC16Decoder::checkPacketValidity ( const RawPacket packet)
private

Definition at line 122 of file lslidar_c16_decoder.cpp.

bool lslidar_c16_decoder::LslidarC16Decoder::createRosIO ( )
private

Definition at line 79 of file lslidar_c16_decoder.cpp.

void lslidar_c16_decoder::LslidarC16Decoder::decodePacket ( const RawPacket packet)
private

Definition at line 362 of file lslidar_c16_decoder.cpp.

point_struct lslidar_c16_decoder::LslidarC16Decoder::getMeans ( std::vector< point_struct clusters)
private

Definition at line 336 of file lslidar_c16_decoder.cpp.

bool lslidar_c16_decoder::LslidarC16Decoder::initialize ( )

Definition at line 95 of file lslidar_c16_decoder.cpp.

bool lslidar_c16_decoder::LslidarC16Decoder::isPointInRange ( const double &  distance)
inlineprivate

Definition at line 183 of file lslidar_c16_decoder.h.

void lslidar_c16_decoder::LslidarC16Decoder::layerCallback ( const std_msgs::Int8Ptr &  msg)
private

Definition at line 438 of file lslidar_c16_decoder.cpp.

bool lslidar_c16_decoder::LslidarC16Decoder::loadParameters ( )
private

Definition at line 40 of file lslidar_c16_decoder.cpp.

LslidarC16Decoder lslidar_c16_decoder::LslidarC16Decoder::operator= ( const LslidarC16Decoder )
delete
void lslidar_c16_decoder::LslidarC16Decoder::packetCallback ( const lslidar_c16_msgs::LslidarC16PacketConstPtr &  msg)
private

Definition at line 455 of file lslidar_c16_decoder.cpp.

void lslidar_c16_decoder::LslidarC16Decoder::publishChannelScan ( )
private

Definition at line 216 of file lslidar_c16_decoder.cpp.

void lslidar_c16_decoder::LslidarC16Decoder::publishPointCloud ( )
private

Definition at line 134 of file lslidar_c16_decoder.cpp.

void lslidar_c16_decoder::LslidarC16Decoder::publishScan ( )
private

Definition at line 280 of file lslidar_c16_decoder.cpp.

double lslidar_c16_decoder::LslidarC16Decoder::rawAzimuthToDouble ( const uint16_t &  raw_azimuth)
inlineprivate

Definition at line 187 of file lslidar_c16_decoder.h.

Member Data Documentation

double lslidar_c16_decoder::LslidarC16Decoder::angle3_disable_max
private

Definition at line 206 of file lslidar_c16_decoder.h.

double lslidar_c16_decoder::LslidarC16Decoder::angle3_disable_min
private

Definition at line 205 of file lslidar_c16_decoder.h.

double lslidar_c16_decoder::LslidarC16Decoder::angle_base
private

Definition at line 198 of file lslidar_c16_decoder.h.

double lslidar_c16_decoder::LslidarC16Decoder::angle_disable_max
private

Definition at line 204 of file lslidar_c16_decoder.h.

double lslidar_c16_decoder::LslidarC16Decoder::angle_disable_min
private

Definition at line 203 of file lslidar_c16_decoder.h.

bool lslidar_c16_decoder::LslidarC16Decoder::apollo_interface
private

Definition at line 211 of file lslidar_c16_decoder.h.

ros::Publisher lslidar_c16_decoder::LslidarC16Decoder::channel_scan_pub
private

Definition at line 238 of file lslidar_c16_decoder.h.

double lslidar_c16_decoder::LslidarC16Decoder::cos_azimuth_table[6300]
private

Definition at line 212 of file lslidar_c16_decoder.h.

Firing lslidar_c16_decoder::LslidarC16Decoder::firings[FIRINGS_PER_PACKET]
private

Definition at line 220 of file lslidar_c16_decoder.h.

std::string lslidar_c16_decoder::LslidarC16Decoder::frame_id
private

Definition at line 227 of file lslidar_c16_decoder.h.

double lslidar_c16_decoder::LslidarC16Decoder::frequency
private

Definition at line 207 of file lslidar_c16_decoder.h.

bool lslidar_c16_decoder::LslidarC16Decoder::is_first_sweep
private

Definition at line 215 of file lslidar_c16_decoder.h.

double lslidar_c16_decoder::LslidarC16Decoder::last_azimuth
private

Definition at line 216 of file lslidar_c16_decoder.h.

int lslidar_c16_decoder::LslidarC16Decoder::layer_num
private

Definition at line 219 of file lslidar_c16_decoder.h.

ros::Subscriber lslidar_c16_decoder::LslidarC16Decoder::layer_sub
private

Definition at line 234 of file lslidar_c16_decoder.h.

double lslidar_c16_decoder::LslidarC16Decoder::max_range
private

Definition at line 202 of file lslidar_c16_decoder.h.

double lslidar_c16_decoder::LslidarC16Decoder::min_range
private

Definition at line 201 of file lslidar_c16_decoder.h.

lslidar_c16_msgs::LslidarC16LayerPtr lslidar_c16_decoder::LslidarC16Decoder::multi_scan
private

Definition at line 230 of file lslidar_c16_decoder.h.

ros::NodeHandle lslidar_c16_decoder::LslidarC16Decoder::nh
private

Definition at line 223 of file lslidar_c16_decoder.h.

double lslidar_c16_decoder::LslidarC16Decoder::packet_start_time
private

Definition at line 218 of file lslidar_c16_decoder.h.

ros::Subscriber lslidar_c16_decoder::LslidarC16Decoder::packet_sub
private

Definition at line 233 of file lslidar_c16_decoder.h.

ros::NodeHandle lslidar_c16_decoder::LslidarC16Decoder::pnh
private

Definition at line 224 of file lslidar_c16_decoder.h.

sensor_msgs::PointCloud2 lslidar_c16_decoder::LslidarC16Decoder::point_cloud_data
private

Definition at line 231 of file lslidar_c16_decoder.h.

ros::Publisher lslidar_c16_decoder::LslidarC16Decoder::point_cloud_pub
private

Definition at line 236 of file lslidar_c16_decoder.h.

int lslidar_c16_decoder::LslidarC16Decoder::point_num
private

Definition at line 197 of file lslidar_c16_decoder.h.

bool lslidar_c16_decoder::LslidarC16Decoder::publish_point_cloud
private

Definition at line 208 of file lslidar_c16_decoder.h.

bool lslidar_c16_decoder::LslidarC16Decoder::publish_scan
private

Definition at line 210 of file lslidar_c16_decoder.h.

ros::Publisher lslidar_c16_decoder::LslidarC16Decoder::scan_pub
private

Definition at line 237 of file lslidar_c16_decoder.h.

double lslidar_c16_decoder::LslidarC16Decoder::sin_azimuth_table[6300]
private

Definition at line 213 of file lslidar_c16_decoder.h.

lslidar_c16_msgs::LslidarC16SweepPtr lslidar_c16_decoder::LslidarC16Decoder::sweep_data
private

Definition at line 229 of file lslidar_c16_decoder.h.

ros::Publisher lslidar_c16_decoder::LslidarC16Decoder::sweep_pub
private

Definition at line 235 of file lslidar_c16_decoder.h.

double lslidar_c16_decoder::LslidarC16Decoder::sweep_start_time
private

Definition at line 217 of file lslidar_c16_decoder.h.

bool lslidar_c16_decoder::LslidarC16Decoder::use_gps_ts
private

Definition at line 209 of file lslidar_c16_decoder.h.


The documentation for this class was generated from the following files:


lslidar_c16_decoder
Author(s): Yutong
autogenerated on Thu Aug 22 2019 03:51:41