Classes | Public Types | Public Member Functions | Private Member Functions | Private Attributes | List of all members
lslidar_n301_decoder::LslidarN301Decoder Class Reference

#include <lslidar_n301_decoder.h>

Classes

struct  Firing
 
struct  RawBlock
 
struct  RawPacket
 
union  TwoBytes
 

Public Types

typedef boost::shared_ptr< const LslidarN301DecoderLslidarN301DecoderConstPtr
 
typedef boost::shared_ptr< LslidarN301DecoderLslidarN301DecoderPtr
 

Public Member Functions

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

Private Member Functions

bool checkPacketValidity (const RawPacket *packet)
 
bool createRosIO ()
 
void decodePacket (const RawPacket *packet)
 
uint64_t get_gps_stamp (tm t)
 
point_struct getMeans (std::vector< point_struct > clusters)
 
bool isPointInRange (const double &distance)
 
bool loadParameters ()
 
void packetCallback (const lslidar_n301_msgs::LslidarN301PacketConstPtr &msg)
 
void publishPointCloud ()
 
void publishScan ()
 
double rawAzimuthToDouble (const uint16_t &raw_azimuth)
 

Private Attributes

double angle_base
 
double angle_disable_max
 
double angle_disable_min
 
std::string child_frame_id
 
double cos_azimuth_table [6300]
 
Firing firings [FIRINGS_PER_PACKET]
 
std::string fixed_frame_id
 
double frequency
 
bool is_first_sweep
 
double last_azimuth
 
double max_range
 
double min_range
 
ros::NodeHandle nh
 
double packet_start_time
 
ros::Subscriber packet_sub
 
uint64_t packet_timestamp
 
ros::NodeHandle pnh
 
sensor_msgs::PointCloud2 point_cloud_data
 
ros::Publisher point_cloud_pub
 
int point_num
 
tm pTime
 
bool publish_point_cloud
 
ros::Publisher scan_pub
 
double sin_azimuth_table [6300]
 
lslidar_n301_msgs::LslidarN301SweepPtr sweep_data
 
uint64_t sweep_end_time_gps
 
uint64_t sweep_end_time_hardware
 
ros::Publisher sweep_pub
 
double sweep_start_time
 
bool use_gps_ts
 

Detailed Description

Definition at line 125 of file lslidar_n301_decoder.h.

Member Typedef Documentation

Definition at line 136 of file lslidar_n301_decoder.h.

Definition at line 135 of file lslidar_n301_decoder.h.

Constructor & Destructor Documentation

lslidar_n301_decoder::LslidarN301Decoder::LslidarN301Decoder ( ros::NodeHandle n,
ros::NodeHandle pn 
)

Definition at line 23 of file lslidar_n301_decoder.cpp.

lslidar_n301_decoder::LslidarN301Decoder::LslidarN301Decoder ( const LslidarN301Decoder )
delete
lslidar_n301_decoder::LslidarN301Decoder::~LslidarN301Decoder ( )
inline

Definition at line 131 of file lslidar_n301_decoder.h.

Member Function Documentation

bool lslidar_n301_decoder::LslidarN301Decoder::checkPacketValidity ( const RawPacket packet)
private

Definition at line 95 of file lslidar_n301_decoder.cpp.

bool lslidar_n301_decoder::LslidarN301Decoder::createRosIO ( )
private

Definition at line 56 of file lslidar_n301_decoder.cpp.

void lslidar_n301_decoder::LslidarN301Decoder::decodePacket ( const RawPacket packet)
private

Definition at line 238 of file lslidar_n301_decoder.cpp.

uint64_t lslidar_n301_decoder::LslidarN301Decoder::get_gps_stamp ( tm  t)
private

Definition at line 229 of file lslidar_n301_decoder.cpp.

point_struct lslidar_n301_decoder::LslidarN301Decoder::getMeans ( std::vector< point_struct clusters)
private

Definition at line 203 of file lslidar_n301_decoder.cpp.

bool lslidar_n301_decoder::LslidarN301Decoder::initialize ( )

Definition at line 68 of file lslidar_n301_decoder.cpp.

bool lslidar_n301_decoder::LslidarN301Decoder::isPointInRange ( const double &  distance)
inlineprivate

Definition at line 186 of file lslidar_n301_decoder.h.

bool lslidar_n301_decoder::LslidarN301Decoder::loadParameters ( )
private

Definition at line 37 of file lslidar_n301_decoder.cpp.

LslidarN301Decoder lslidar_n301_decoder::LslidarN301Decoder::operator= ( const LslidarN301Decoder )
delete
void lslidar_n301_decoder::LslidarN301Decoder::packetCallback ( const lslidar_n301_msgs::LslidarN301PacketConstPtr &  msg)
private

Definition at line 328 of file lslidar_n301_decoder.cpp.

void lslidar_n301_decoder::LslidarN301Decoder::publishPointCloud ( )
private

Definition at line 106 of file lslidar_n301_decoder.cpp.

void lslidar_n301_decoder::LslidarN301Decoder::publishScan ( )
private

Definition at line 148 of file lslidar_n301_decoder.cpp.

double lslidar_n301_decoder::LslidarN301Decoder::rawAzimuthToDouble ( const uint16_t &  raw_azimuth)
inlineprivate

Definition at line 190 of file lslidar_n301_decoder.h.

Member Data Documentation

double lslidar_n301_decoder::LslidarN301Decoder::angle_base
private

Definition at line 211 of file lslidar_n301_decoder.h.

double lslidar_n301_decoder::LslidarN301Decoder::angle_disable_max
private

Definition at line 217 of file lslidar_n301_decoder.h.

double lslidar_n301_decoder::LslidarN301Decoder::angle_disable_min
private

Definition at line 216 of file lslidar_n301_decoder.h.

std::string lslidar_n301_decoder::LslidarN301Decoder::child_frame_id
private

Definition at line 236 of file lslidar_n301_decoder.h.

double lslidar_n301_decoder::LslidarN301Decoder::cos_azimuth_table[6300]
private

Definition at line 222 of file lslidar_n301_decoder.h.

Firing lslidar_n301_decoder::LslidarN301Decoder::firings[FIRINGS_PER_PACKET]
private

Definition at line 229 of file lslidar_n301_decoder.h.

std::string lslidar_n301_decoder::LslidarN301Decoder::fixed_frame_id
private

Definition at line 235 of file lslidar_n301_decoder.h.

double lslidar_n301_decoder::LslidarN301Decoder::frequency
private

Definition at line 218 of file lslidar_n301_decoder.h.

bool lslidar_n301_decoder::LslidarN301Decoder::is_first_sweep
private

Definition at line 225 of file lslidar_n301_decoder.h.

double lslidar_n301_decoder::LslidarN301Decoder::last_azimuth
private

Definition at line 226 of file lslidar_n301_decoder.h.

double lslidar_n301_decoder::LslidarN301Decoder::max_range
private

Definition at line 215 of file lslidar_n301_decoder.h.

double lslidar_n301_decoder::LslidarN301Decoder::min_range
private

Definition at line 214 of file lslidar_n301_decoder.h.

ros::NodeHandle lslidar_n301_decoder::LslidarN301Decoder::nh
private

Definition at line 232 of file lslidar_n301_decoder.h.

double lslidar_n301_decoder::LslidarN301Decoder::packet_start_time
private

Definition at line 228 of file lslidar_n301_decoder.h.

ros::Subscriber lslidar_n301_decoder::LslidarN301Decoder::packet_sub
private

Definition at line 241 of file lslidar_n301_decoder.h.

uint64_t lslidar_n301_decoder::LslidarN301Decoder::packet_timestamp
private

Definition at line 203 of file lslidar_n301_decoder.h.

ros::NodeHandle lslidar_n301_decoder::LslidarN301Decoder::pnh
private

Definition at line 233 of file lslidar_n301_decoder.h.

sensor_msgs::PointCloud2 lslidar_n301_decoder::LslidarN301Decoder::point_cloud_data
private

Definition at line 239 of file lslidar_n301_decoder.h.

ros::Publisher lslidar_n301_decoder::LslidarN301Decoder::point_cloud_pub
private

Definition at line 243 of file lslidar_n301_decoder.h.

int lslidar_n301_decoder::LslidarN301Decoder::point_num
private

Definition at line 210 of file lslidar_n301_decoder.h.

tm lslidar_n301_decoder::LslidarN301Decoder::pTime
private

Definition at line 201 of file lslidar_n301_decoder.h.

bool lslidar_n301_decoder::LslidarN301Decoder::publish_point_cloud
private

Definition at line 219 of file lslidar_n301_decoder.h.

ros::Publisher lslidar_n301_decoder::LslidarN301Decoder::scan_pub
private

Definition at line 244 of file lslidar_n301_decoder.h.

double lslidar_n301_decoder::LslidarN301Decoder::sin_azimuth_table[6300]
private

Definition at line 223 of file lslidar_n301_decoder.h.

lslidar_n301_msgs::LslidarN301SweepPtr lslidar_n301_decoder::LslidarN301Decoder::sweep_data
private

Definition at line 238 of file lslidar_n301_decoder.h.

uint64_t lslidar_n301_decoder::LslidarN301Decoder::sweep_end_time_gps
private

Definition at line 206 of file lslidar_n301_decoder.h.

uint64_t lslidar_n301_decoder::LslidarN301Decoder::sweep_end_time_hardware
private

Definition at line 207 of file lslidar_n301_decoder.h.

ros::Publisher lslidar_n301_decoder::LslidarN301Decoder::sweep_pub
private

Definition at line 242 of file lslidar_n301_decoder.h.

double lslidar_n301_decoder::LslidarN301Decoder::sweep_start_time
private

Definition at line 227 of file lslidar_n301_decoder.h.

bool lslidar_n301_decoder::LslidarN301Decoder::use_gps_ts
private

Definition at line 220 of file lslidar_n301_decoder.h.


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


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