Autoware.Auto
autoware::drivers::velodyne_driver::VelodyneTranslator< SensorData > Class Template Reference

This class handles converting packets from a velodyne lidar into cartesian points. More...

#include <velodyne_translator.hpp>

Classes

class  Config
 
struct  DataBlock
 corresponds to a velodyne data block. More...
 
struct  DataChannel
 corresponds to an individual laser's firing and return First two bytes are distance, last byte is intensity More...
 
struct  Packet
 stores a Velodyne data packet More...
 

Public Member Functions

 VelodyneTranslator (const Config &config)
 default constructor More...
 
void convert (const Packet &pkt, std::vector< autoware::common::types::PointXYZIF > &output)
 Convert a packet into a block of cartesian points. More...
 

Static Public Attributes

static constexpr uint16_t POINT_BLOCK_CAPACITY = 512U
 Stores basic configuration information, does some simple validity checking. More...
 

Detailed Description

template<typename SensorData>
class autoware::drivers::velodyne_driver::VelodyneTranslator< SensorData >

This class handles converting packets from a velodyne lidar into cartesian points.

Template Parameters
SensorDataData class representing a specific sensor model.

Constructor & Destructor Documentation

◆ VelodyneTranslator()

template<typename SensorData >
autoware::drivers::velodyne_driver::VelodyneTranslator< SensorData >::VelodyneTranslator ( const Config config)
inlineexplicit

default constructor

Parameters
[in]configconfig struct with rpm, transform, radial and angle pruning params
Exceptions
std::runtime_errorif pruning parameters are inconsistent

Member Function Documentation

◆ convert()

template<typename SensorData >
void autoware::drivers::velodyne_driver::VelodyneTranslator< SensorData >::convert ( const Packet pkt,
std::vector< autoware::common::types::PointXYZIF > &  output 
)
inline

Convert a packet into a block of cartesian points.

Parameters
[in]pktA packet from a VLP16 HiRes sensor for conversion
[out]outputGets filled with cartesian points and any additional flags

Member Data Documentation

◆ POINT_BLOCK_CAPACITY

template<typename SensorData >
constexpr uint16_t autoware::drivers::velodyne_driver::VelodyneTranslator< SensorData >::POINT_BLOCK_CAPACITY = 512U
static

Stores basic configuration information, does some simple validity checking.


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