Skip to content

Class nebula::drivers::VelodyneScanDecoder

ClassList > nebula > drivers > VelodyneScanDecoder

Base class for Velodyne LiDAR decoder.

  • #include <velodyne_scan_decoder.hpp>

Inherited by the following classes: nebula::drivers::vlp16::Vlp16Decoder, nebula::drivers::vlp32::Vlp32Decoder, nebula::drivers::vls128::Vls128Decoder

Public Functions

Type Name
VelodyneScanDecoder (VelodyneScanDecoder && c) = delete
VelodyneScanDecoder (const VelodyneScanDecoder & c) = delete
VelodyneScanDecoder () = default
virtual std::tuple< drivers::NebulaPointCloudPtr, double > get_pointcloud () = 0
Virtual function for getting the constructed point cloud.
bool hasScanned ()
Virtual function for getting the flag indicating whether one cycle is ready.
VelodyneScanDecoder & operator= (VelodyneScanDecoder && c) = delete
VelodyneScanDecoder & operator= (const VelodyneScanDecoder & c) = delete
virtual bool parsePacket (const velodyne_msgs::msg::VelodynePacket & velodyne_packet) = 0
Virtual function for parsing VelodynePacket based on packet structure.
virtual int pointsPerPacket () = 0
Calculation of points in each packet.
virtual void reset_overflow (double time_stamp) = 0
Resetting overflowed point cloud buffer.
virtual void reset_pointcloud (double time_stamp) = 0
Resetting point cloud buffer.
virtual void unpack (const std::vector< uint8_t > & packet, int32_t packet_seconds) = 0
Virtual function for parsing and shaping VelodynePacket.
virtual ~VelodyneScanDecoder () = default

Protected Attributes

Type Name
std::shared_ptr< const drivers::VelodyneCalibrationConfiguration > calibration_configuration_
Calibration for this decoder.
double dual_return_distance_threshold_ = {}
drivers::NebulaPointCloudPtr overflow_pc_
Point cloud overflowing from one cycle.
drivers::NebulaPointCloudPtr scan_pc_
Decoded point cloud.
double scan_timestamp_ = {}
std::shared_ptr< const drivers::VelodyneSensorConfiguration > sensor_configuration_
SensorConfiguration for this decoder.

Protected Functions

Type Name
void checkAndHandleScanComplete (const std::vector< uint8_t > & packet, int32_t packet_seconds, const uint32_t phase)
Checks if the current packet completes the ongoing scan. TODO: this has been moved from velodyne_hw_interface.cpp and is a temporary solution until the Velodyne decoder uses the same structure as Hesai/Robosense.

Public Functions Documentation

function VelodyneScanDecoder [1/3]

nebula::drivers::VelodyneScanDecoder::VelodyneScanDecoder (
    VelodyneScanDecoder && c
) = delete

function VelodyneScanDecoder [2/3]

nebula::drivers::VelodyneScanDecoder::VelodyneScanDecoder (
    const VelodyneScanDecoder & c
) = delete

function VelodyneScanDecoder [3/3]

nebula::drivers::VelodyneScanDecoder::VelodyneScanDecoder () = default

function get_pointcloud

Virtual function for getting the constructed point cloud.

virtual std::tuple< drivers::NebulaPointCloudPtr, double > nebula::drivers::VelodyneScanDecoder::get_pointcloud () = 0

Returns:

tuple of Point cloud and timestamp


function hasScanned

Virtual function for getting the flag indicating whether one cycle is ready.

inline bool nebula::drivers::VelodyneScanDecoder::hasScanned () 

Returns:

Readied


function operator=

VelodyneScanDecoder & nebula::drivers::VelodyneScanDecoder::operator= (
    VelodyneScanDecoder && c
) = delete

function operator=

VelodyneScanDecoder & nebula::drivers::VelodyneScanDecoder::operator= (
    const VelodyneScanDecoder & c
) = delete

function parsePacket

Virtual function for parsing VelodynePacket based on packet structure.

virtual bool nebula::drivers::VelodyneScanDecoder::parsePacket (
    const velodyne_msgs::msg::VelodynePacket & velodyne_packet
) = 0

Parameters:

  • pandar_packet

Returns:

Resulting flag


function pointsPerPacket

Calculation of points in each packet.

virtual int nebula::drivers::VelodyneScanDecoder::pointsPerPacket () = 0

Returns:

of points


function reset_overflow

virtual void nebula::drivers::VelodyneScanDecoder::reset_overflow (
    double time_stamp
) = 0

function reset_pointcloud

virtual void nebula::drivers::VelodyneScanDecoder::reset_pointcloud (
    double time_stamp
) = 0

function unpack

Virtual function for parsing and shaping VelodynePacket.

virtual void nebula::drivers::VelodyneScanDecoder::unpack (
    const std::vector< uint8_t > & packet,
    int32_t packet_seconds
) = 0

Parameters:

  • pandar_packet

function ~VelodyneScanDecoder

virtual nebula::drivers::VelodyneScanDecoder::~VelodyneScanDecoder () = default

Protected Attributes Documentation

variable calibration_configuration_

std::shared_ptr<const drivers::VelodyneCalibrationConfiguration> nebula::drivers::VelodyneScanDecoder::calibration_configuration_;

variable dual_return_distance_threshold_

double nebula::drivers::VelodyneScanDecoder::dual_return_distance_threshold_;

variable overflow_pc_

drivers::NebulaPointCloudPtr nebula::drivers::VelodyneScanDecoder::overflow_pc_;

variable scan_pc_

drivers::NebulaPointCloudPtr nebula::drivers::VelodyneScanDecoder::scan_pc_;

variable scan_timestamp_

double nebula::drivers::VelodyneScanDecoder::scan_timestamp_;

variable sensor_configuration_

std::shared_ptr<const drivers::VelodyneSensorConfiguration> nebula::drivers::VelodyneScanDecoder::sensor_configuration_;

Protected Functions Documentation

function checkAndHandleScanComplete

Checks if the current packet completes the ongoing scan. TODO: this has been moved from velodyne_hw_interface.cpp and is a temporary solution until the Velodyne decoder uses the same structure as Hesai/Robosense.

inline void nebula::drivers::VelodyneScanDecoder::checkAndHandleScanComplete (
    const std::vector< uint8_t > & packet,
    int32_t packet_seconds,
    const uint32_t phase
) 

Parameters:

  • packet The packet buffer to extract azimuths from
  • packet_seconds The seconds-since-epoch part of the packet's timestamp
  • phase The sensor's scan phase used for scan cutting


The documentation for this class was generated from the following file nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_scan_decoder.hpp