Class nebula::drivers::VelodyneDriver
ClassList > nebula > drivers > VelodyneDriver
Velodyne driver.
#include <velodyne_driver.hpp>
Inherits the following classes: nebula::drivers::NebulaDriverBase
Public Functions
Type | Name |
---|---|
VelodyneDriver () = delete |
|
VelodyneDriver (const std::shared_ptr< const drivers::VelodyneSensorConfiguration > & sensor_configuration, const std::shared_ptr< const drivers::VelodyneCalibrationConfiguration > & calibration_configuration) Constructor. |
|
Status | get_status () Get current status of this driver. |
std::tuple< drivers::NebulaPointCloudPtr, double > | parse_cloud_packet (const std::vector< uint8_t > & packet, double packet_seconds) Convert VelodyneScan message to point cloud. |
virtual Status | set_calibration_configuration (const CalibrationConfigurationBase & calibration_configuration) override Setting CalibrationConfiguration (not used) |
Public Functions inherited from nebula::drivers::NebulaDriverBase
See nebula::drivers::NebulaDriverBase
Type | Name |
---|---|
NebulaDriverBase (NebulaDriverBase && c) = delete |
|
NebulaDriverBase (const NebulaDriverBase & c) = delete |
|
NebulaDriverBase () = default |
|
NebulaDriverBase & | operator= (NebulaDriverBase && c) = delete |
NebulaDriverBase & | operator= (const NebulaDriverBase & c) = delete |
virtual Status | set_calibration_configuration (const CalibrationConfigurationBase & calibration_configuration) = 0 Virtual function for setting calibration configuration. |
Public Functions Documentation
function VelodyneDriver [1/2]
nebula::drivers::VelodyneDriver::VelodyneDriver () = delete
function VelodyneDriver [2/2]
Constructor.
nebula::drivers::VelodyneDriver::VelodyneDriver (
const std::shared_ptr< const drivers::VelodyneSensorConfiguration > & sensor_configuration,
const std::shared_ptr< const drivers::VelodyneCalibrationConfiguration > & calibration_configuration
)
Parameters:
sensor_configuration
SensorConfiguration for this drivercalibration_configuration
CalibrationConfiguration for this driver
function get_status
Get current status of this driver.
Status nebula::drivers::VelodyneDriver::get_status ()
Returns:
Current status
function parse_cloud_packet
Convert VelodyneScan message to point cloud.
std::tuple< drivers::NebulaPointCloudPtr, double > nebula::drivers::VelodyneDriver::parse_cloud_packet (
const std::vector< uint8_t > & packet,
double packet_seconds
)
Parameters:
velodyne_scan
Message
Returns:
tuple of Point cloud and timestamp
function set_calibration_configuration
Setting CalibrationConfiguration (not used)
virtual Status nebula::drivers::VelodyneDriver::set_calibration_configuration (
const CalibrationConfigurationBase & calibration_configuration
) override
Parameters:
calibration_configuration
Returns:
Resulting status
Implements nebula::drivers::NebulaDriverBase::set_calibration_configuration
The documentation for this class was generated from the following file nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/velodyne_driver.hpp