Class VelodyneScanDecoder
Defined in File velodyne_scan_decoder.hpp
Inheritance Relationships
Derived Types
public nebula::drivers::vlp16::Vlp16Decoder(Class Vlp16Decoder)public nebula::drivers::vlp32::Vlp32Decoder(Class Vlp32Decoder)public nebula::drivers::vls128::Vls128Decoder(Class Vls128Decoder)
Class Documentation
-
class VelodyneScanDecoder
Base class for Velodyne LiDAR decoder.
Subclassed by nebula::drivers::vlp16::Vlp16Decoder, nebula::drivers::vlp32::Vlp32Decoder, nebula::drivers::vls128::Vls128Decoder
Public Functions
-
VelodyneScanDecoder(VelodyneScanDecoder &&c) = delete
-
VelodyneScanDecoder &operator=(VelodyneScanDecoder &&c) = delete
-
VelodyneScanDecoder(const VelodyneScanDecoder &c) = delete
-
VelodyneScanDecoder &operator=(const VelodyneScanDecoder &c) = delete
-
virtual ~VelodyneScanDecoder() = default
-
VelodyneScanDecoder() = default
-
virtual void unpack(const std::vector<uint8_t> &packet, double packet_seconds) = 0
Virtual function for parsing and shaping VelodynePacket.
- Parameters:
pandar_packet –
-
virtual bool parse_packet(const velodyne_msgs::msg::VelodynePacket &velodyne_packet) = 0
Virtual function for parsing VelodynePacket based on packet structure.
- Parameters:
pandar_packet –
- Returns:
Resulting flag
-
inline bool has_scanned()
Virtual function for getting the flag indicating whether one cycle is ready.
- Returns:
Readied
-
virtual int points_per_packet() = 0
Calculation of points in each packet.
- Returns:
# of points
-
virtual std::tuple<drivers::NebulaPointCloudPtr, double> get_pointcloud() = 0
Virtual function for getting the constructed point cloud.
- Returns:
tuple of Point cloud and timestamp
-
virtual void reset_pointcloud(double time_stamp) = 0
Resetting point cloud buffer.
-
virtual void reset_overflow(double time_stamp) = 0
Resetting overflowed point cloud buffer.
Protected Functions
-
inline void check_and_handle_scan_complete(const std::vector<uint8_t> &packet, double 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.
- Parameters:
packet – The packet buffer to extract azimuths from
packet_seconds – The packet’s timestamp in seconds, including the sub-second part
phase – The sensor’s scan phase used for scan cutting
Protected Attributes
-
drivers::NebulaPointCloudPtr scan_pc_
Decoded point cloud.
-
drivers::NebulaPointCloudPtr overflow_pc_
Point cloud overflowing from one cycle.
-
double dual_return_distance_threshold_ = {}
-
double scan_timestamp_ = {}
-
std::shared_ptr<const drivers::VelodyneSensorConfiguration> sensor_configuration_
SensorConfiguration for this decoder.
-
std::shared_ptr<const drivers::VelodyneCalibrationConfiguration> calibration_configuration_
Calibration for this decoder.
-
VelodyneScanDecoder(VelodyneScanDecoder &&c) = delete