Apollo  6.0
Open source self driving car software
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
apollo::drivers::velodyne::VelodyneParser Class Referenceabstract

Velodyne data conversion class. More...

#include <velodyne_parser.h>

Inheritance diagram for apollo::drivers::velodyne::VelodyneParser:
Inheritance graph
Collaboration diagram for apollo::drivers::velodyne::VelodyneParser:
Collaboration graph

Public Member Functions

 VelodyneParser ()
 
 VelodyneParser (const Config &config)
 
virtual ~VelodyneParser ()
 
virtual void GeneratePointcloud (const std::shared_ptr< VelodyneScan > &scan_msg, std::shared_ptr< PointCloud > out_msg)=0
 Set up for data processing. More...
 
virtual void setup ()
 
virtual void Order (std::shared_ptr< PointCloud > cloud)=0
 
const Calibrationget_calibration ()
 
const double get_last_timestamp ()
 

Protected Member Functions

PointXYZIT get_nan_point (uint64_t timestamp)
 
void init_angle_params (double view_direction, double view_width)
 
void ComputeCoords (const float &raw_distance, const LaserCorrection &corrections, const uint16_t rotation, PointXYZIT *point)
 Compute coords with the data in block. More...
 
bool is_scan_valid (int rotation, float distance)
 
virtual void Unpack (const VelodynePacket &pkt, std::shared_ptr< PointCloud > pc)=0
 Unpack velodyne packet. More...
 
uint64_t GetGpsStamp (double current_stamp, double *previous_stamp, uint64_t *gps_base_usec)
 
virtual uint64_t GetTimestamp (double base_time, float time_offset, uint16_t laser_block_id)=0
 

Protected Attributes

const float(* inner_time_ )[12][32]
 
Calibration calibration_
 
float sin_rot_table_ [ROTATION_MAX_UNITS]
 
float cos_rot_table_ [ROTATION_MAX_UNITS]
 
double last_time_stamp_
 
Config config_
 
bool need_two_pt_correction_
 
Mode mode_
 

Detailed Description

Velodyne data conversion class.

Constructor & Destructor Documentation

◆ VelodyneParser() [1/2]

apollo::drivers::velodyne::VelodyneParser::VelodyneParser ( )
inline

◆ VelodyneParser() [2/2]

apollo::drivers::velodyne::VelodyneParser::VelodyneParser ( const Config &  config)
explicit

◆ ~VelodyneParser()

virtual apollo::drivers::velodyne::VelodyneParser::~VelodyneParser ( )
inlinevirtual

Member Function Documentation

◆ ComputeCoords()

void apollo::drivers::velodyne::VelodyneParser::ComputeCoords ( const float &  raw_distance,
const LaserCorrection corrections,
const uint16_t  rotation,
PointXYZIT *  point 
)
protected

Compute coords with the data in block.

Parameters
tmpA two bytes union store the value of laser distance information
indexThe index of block

◆ GeneratePointcloud()

virtual void apollo::drivers::velodyne::VelodyneParser::GeneratePointcloud ( const std::shared_ptr< VelodyneScan > &  scan_msg,
std::shared_ptr< PointCloud out_msg 
)
pure virtual

Set up for data processing.

Perform initializations needed before data processing can begin:

  • read device-specific angles calibration
Parameters
private_nhprivate node handle for ROS parameters
Returns
0 if successful; errno value for failure

Implemented in apollo::drivers::velodyne::Velodyne128Parser, apollo::drivers::velodyne::Velodyne16Parser, apollo::drivers::velodyne::Velodyne32Parser, and apollo::drivers::velodyne::Velodyne64Parser.

◆ get_calibration()

const Calibration& apollo::drivers::velodyne::VelodyneParser::get_calibration ( )
inline

◆ get_last_timestamp()

const double apollo::drivers::velodyne::VelodyneParser::get_last_timestamp ( )
inline

◆ get_nan_point()

PointXYZIT apollo::drivers::velodyne::VelodyneParser::get_nan_point ( uint64_t  timestamp)
protected

◆ GetGpsStamp()

uint64_t apollo::drivers::velodyne::VelodyneParser::GetGpsStamp ( double  current_stamp,
double *  previous_stamp,
uint64_t *  gps_base_usec 
)
protected

◆ GetTimestamp()

virtual uint64_t apollo::drivers::velodyne::VelodyneParser::GetTimestamp ( double  base_time,
float  time_offset,
uint16_t  laser_block_id 
)
protectedpure virtual

◆ init_angle_params()

void apollo::drivers::velodyne::VelodyneParser::init_angle_params ( double  view_direction,
double  view_width 
)
protected

◆ is_scan_valid()

bool apollo::drivers::velodyne::VelodyneParser::is_scan_valid ( int  rotation,
float  distance 
)
protected

◆ Order()

virtual void apollo::drivers::velodyne::VelodyneParser::Order ( std::shared_ptr< PointCloud cloud)
pure virtual

◆ setup()

virtual void apollo::drivers::velodyne::VelodyneParser::setup ( )
virtual

◆ Unpack()

virtual void apollo::drivers::velodyne::VelodyneParser::Unpack ( const VelodynePacket &  pkt,
std::shared_ptr< PointCloud pc 
)
protectedpure virtual

Unpack velodyne packet.

Member Data Documentation

◆ calibration_

Calibration apollo::drivers::velodyne::VelodyneParser::calibration_
protected

◆ config_

Config apollo::drivers::velodyne::VelodyneParser::config_
protected

◆ cos_rot_table_

float apollo::drivers::velodyne::VelodyneParser::cos_rot_table_[ROTATION_MAX_UNITS]
protected

◆ inner_time_

const float(* apollo::drivers::velodyne::VelodyneParser::inner_time_)[12][32]
protected

◆ last_time_stamp_

double apollo::drivers::velodyne::VelodyneParser::last_time_stamp_
protected

◆ mode_

Mode apollo::drivers::velodyne::VelodyneParser::mode_
protected

◆ need_two_pt_correction_

bool apollo::drivers::velodyne::VelodyneParser::need_two_pt_correction_
protected

◆ sin_rot_table_

float apollo::drivers::velodyne::VelodyneParser::sin_rot_table_[ROTATION_MAX_UNITS]
protected

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