Class Vls128Decoder
Defined in File vls128_decoder.hpp
Inheritance Relationships
Base Type
public nebula::drivers::VelodyneScanDecoder(Class VelodyneScanDecoder)
Class Documentation
-
class Vls128Decoder : public nebula::drivers::VelodyneScanDecoder
Velodyne LiDAR decoder (VLS128)
Public Functions
Constructor.
- Parameters:
sensor_configuration – SensorConfiguration for this decoder
calibration_configuration – Calibration for this decoder
-
virtual void unpack(const std::vector<uint8_t> &packet, double packet_seconds) override
Parsing and shaping VelodynePacket.
- Parameters:
velodyne_packet –
-
virtual int points_per_packet() override
Calculation of points in each packet.
- Returns:
# of points
-
virtual std::tuple<drivers::NebulaPointCloudPtr, double> get_pointcloud() override
Get the constructed point cloud.
- Returns:
tuple of Point cloud and timestamp
-
virtual void reset_pointcloud(double time_stamp) override
Resetting point cloud buffer.
-
virtual void reset_overflow(double time_stamp) override
Resetting overflowed point cloud buffer.