Namespace nebula::drivers
Namespace List > nebula > drivers
Namespaces
| Type | Name |
|---|---|
| namespace | vlp16 |
| namespace | vlp32 |
| namespace | vls128 |
Classes
| Type | Name |
|---|---|
| class | VelodyneCalibration Calibration information for the entire device. |
| struct | VelodyneCalibrationConfiguration struct for Velodyne calibration configuration |
| class | VelodyneDriver Velodyne driver. |
| class | VelodyneHwInterface Hardware interface of velodyne driver. |
| struct | VelodyneLaserCorrection |
| class | VelodyneScanDecoder Base class for Velodyne LiDAR decoder. |
| struct | VelodyneSensorConfiguration struct for Velodyne sensor configuration |
| struct | raw_block Raw Velodyne data block. |
| struct | raw_packet Raw Velodyne packet. |
Public Types
| Type | Name |
|---|---|
| enum | RETURN_TYPE Velodyne echo types. |
| union | two_bytes |
| typedef struct nebula::drivers::raw_block | raw_block_t Raw Velodyne data block. |
| typedef struct nebula::drivers::raw_packet | raw_packet_t Raw Velodyne packet. |
Public Static Attributes
| Type | Name |
|---|---|
| const int | g_block_data_size = (g\_scans\_per\_block \* g\_raw\_scan\_size) |
| const int | g_blocks_per_packet = 12 |
| const uint32_t | g_degree_subdivisions = 100 |
| const uint16_t | g_lower_bank = 0xddff |
| const size_t | g_offset_first_azimuth = 2 |
| const size_t | g_offset_last_azimuth = 1102 |
| const int | g_packet_size = 1206 |
| const int | g_packet_status_size = 4 |
| const int | g_raw_scan_size = 3 |
| const uint16_t | g_return_mode_dual = 57 |
| const size_t | g_return_mode_index = 1204 |
| const uint16_t | g_return_mode_last = 56 |
| const uint16_t | g_return_mode_strongest = 55 |
| const uint16_t | g_rotation_max_units = 36000u |
| const double | g_rotation_resolution = 0.01 |
| const int | g_scans_per_block = 32 |
| const int | g_scans_per_packet = (g\_scans\_per\_block \* g\_blocks\_per\_packet) |
| const int | g_size_block = 100 |
| const uint16_t | g_upper_bank = 0xeeff |
| const float | g_vlp128_distance_resolution = 0.004f |
| const float | g_vlp16_block_duration = 110.592f |
| const float | g_vlp16_dsr_toffset = 2.304f |
| const float | g_vlp16_firing_toffset = 55.296f |
| const int | g_vlp16_firings_per_block = 2 |
| const int | g_vlp16_scans_per_firing = 16 |
| const float | g_vlp32_channel_duration = 2.304f |
| const float | g_vlp32_seq_duration = 55.296f |
| const uint16_t | g_vls128_bank_1 = 0xeeff |
| const uint16_t | g_vls128_bank_2 = 0xddff |
| const uint16_t | g_vls128_bank_3 = 0xccff |
| const uint16_t | g_vls128_bank_4 = 0xbbff |
| const float | g_vls128_channel_duration = /* multi line expression */ |
| const float | g_vls128_seq_duration = /* multi line expression */ |
Public Functions
| Type | Name |
|---|---|
| std::ostream & | operator<< (std::ostream & os, VelodyneSensorConfiguration const & arg) Convert VelodyneSensorConfiguration to string (Overloading the << operator) |
| ReturnMode | return_mode_from_string_velodyne (const std::string & return_mode) Convert return mode name to ReturnMode enum (Velodyne-specific return_mode_from_string) |
Public Types Documentation
enum RETURN_TYPE
Velodyne echo types.
enum nebula::drivers::RETURN_TYPE {
INVALID = 0,
SINGLE_STRONGEST = 1,
SINGLE_LAST = 2,
DUAL_STRONGEST_FIRST = 3,
DUAL_STRONGEST_LAST = 4,
DUAL_WEAK_FIRST = 5,
DUAL_WEAK_LAST = 6,
DUAL_ONLY = 7
};
union two_bytes
used for unpacking the first two data bytes in a block
They are packed into the actual data stream misaligned. I doubt this works on big endian machines.
typedef raw_block_t
Raw Velodyne data block.
typedef struct nebula::drivers::raw_block nebula::drivers::raw_block_t;
Each block contains data from either the upper or lower laser bank. The device returns three times as many upper bank blocks.
use stdint.h types, so things work with both 64 and 32-bit machines
typedef raw_packet_t
Raw Velodyne packet.
typedef struct nebula::drivers::raw_packet nebula::drivers::raw_packet_t;
revolution is described in the device manual as incrementing (mod 65536) for each physical turn of the device. Our device seems to alternate between two different values every third packet. One value increases, the other decreases.
Todo
figure out if revolution is only present for one of the two types of status fields
status has either a temperature encoding or the microcode level
Public Static Attributes Documentation
variable g_block_data_size
const int nebula::drivers::g_block_data_size;
variable g_blocks_per_packet
const int nebula::drivers::g_blocks_per_packet;
variable g_degree_subdivisions
const uint32_t nebula::drivers::g_degree_subdivisions;
variable g_lower_bank
const uint16_t nebula::drivers::g_lower_bank;
variable g_offset_first_azimuth
const size_t nebula::drivers::g_offset_first_azimuth;
variable g_offset_last_azimuth
const size_t nebula::drivers::g_offset_last_azimuth;
variable g_packet_size
const int nebula::drivers::g_packet_size;
variable g_packet_status_size
const int nebula::drivers::g_packet_status_size;
variable g_raw_scan_size
const int nebula::drivers::g_raw_scan_size;
variable g_return_mode_dual
const uint16_t nebula::drivers::g_return_mode_dual;
variable g_return_mode_index
const size_t nebula::drivers::g_return_mode_index;
variable g_return_mode_last
const uint16_t nebula::drivers::g_return_mode_last;
variable g_return_mode_strongest
const uint16_t nebula::drivers::g_return_mode_strongest;
Return Modes
variable g_rotation_max_units
const uint16_t nebula::drivers::g_rotation_max_units;
variable g_rotation_resolution
const double nebula::drivers::g_rotation_resolution;
variable g_scans_per_block
const int nebula::drivers::g_scans_per_block;
variable g_scans_per_packet
const int nebula::drivers::g_scans_per_packet;
variable g_size_block
const int nebula::drivers::g_size_block;
Raw Velodyne packet constants and structures.
variable g_upper_bank
const uint16_t nebula::drivers::g_upper_bank;
Todo
make this work for both big and little-endian machines
variable g_vlp128_distance_resolution
const float nebula::drivers::g_vlp128_distance_resolution;
Special Definitions for VLS128 support
variable g_vlp16_block_duration
const float nebula::drivers::g_vlp16_block_duration;
variable g_vlp16_dsr_toffset
const float nebula::drivers::g_vlp16_dsr_toffset;
variable g_vlp16_firing_toffset
const float nebula::drivers::g_vlp16_firing_toffset;
variable g_vlp16_firings_per_block
const int nebula::drivers::g_vlp16_firings_per_block;
Special Defines for VLP16 support
variable g_vlp16_scans_per_firing
const int nebula::drivers::g_vlp16_scans_per_firing;
variable g_vlp32_channel_duration
const float nebula::drivers::g_vlp32_channel_duration;
Special Defines for VLP32 support
variable g_vlp32_seq_duration
const float nebula::drivers::g_vlp32_seq_duration;
variable g_vls128_bank_1
const uint16_t nebula::drivers::g_vls128_bank_1;
Special Definitions for VLS128 support
variable g_vls128_bank_2
const uint16_t nebula::drivers::g_vls128_bank_2;
variable g_vls128_bank_3
const uint16_t nebula::drivers::g_vls128_bank_3;
variable g_vls128_bank_4
const uint16_t nebula::drivers::g_vls128_bank_4;
variable g_vls128_channel_duration
const float nebula::drivers::g_vls128_channel_duration;
variable g_vls128_seq_duration
const float nebula::drivers::g_vls128_seq_duration;
Public Functions Documentation
function operator<<
Convert VelodyneSensorConfiguration to string (Overloading the << operator)
inline std::ostream & nebula::drivers::operator<< (
std::ostream & os,
VelodyneSensorConfiguration const & arg
)
Parameters:
osarg
Returns:
stream
function return_mode_from_string_velodyne
Convert return mode name to ReturnMode enum (Velodyne-specific return_mode_from_string)
inline ReturnMode nebula::drivers::return_mode_from_string_velodyne (
const std::string & return_mode
)
Parameters:
return_modeReturn mode name (Upper and lower case letters must match)
Returns:
Corresponding ReturnMode
The documentation for this class was generated from the following file src/nebula_velodyne/nebula_velodyne_common/include/nebula_velodyne_common/velodyne_calibration_decoder.hpp