Namespace nebula::drivers
Namespace List > nebula > drivers
Namespaces
Type | Name |
---|---|
namespace | continental_ars548 |
namespace | continental_srr520 |
namespace | hesai_packet |
namespace | robosense_packet |
namespace | vlp16 |
namespace | vlp32 |
namespace | vls128 |
Classes
Type | Name |
---|---|
class | AngleCorrector <typename CorrectionDataT> Handles angle correction for given azimuth/channel combinations, as well as trigonometry lookup tables. |
class | AngleCorrectorCalibrationBased <ChannelN, AngleUnit> |
class | AngleCorrectorCorrectionBased <ChannelN, AngleUnit> |
class | BpearlV3 |
class | BpearlV4 |
class | ContinentalPacketsDecoder Base class for Continental Radar decoder. |
struct | CorrectedAngleData |
class | Helios |
class | HesaiDecoder <typename SensorT> |
class | HesaiDriver Hesai driver. |
class | HesaiScanDecoder Base class for Hesai LiDAR decoder. |
class | HesaiSensor <typename PacketT, AngleCorrection> Base class for all sensor definitions. |
class | NebulaDriverBase Base class for each sensor driver. |
class | Pandar128E3X |
class | Pandar128E4X |
class | Pandar40 |
class | Pandar64 |
class | PandarAT128 |
class | PandarQT128 |
class | PandarQT64 |
class | PandarXT32 |
class | PandarXT32M |
class | RobosenseDecoder <typename SensorT> |
class | RobosenseDriver Robosense driver. |
class | RobosenseInfoDecoder <typename SensorT> |
class | RobosenseInfoDecoderBase |
class | RobosenseInfoDriver Robosense driver. |
class | RobosenseScanDecoder Base class for Robosense LiDAR decoder. |
class | RobosenseSensor <typename PacketT, typename InfoPacketT> Base class for all sensor definitions. |
class | VelodyneDriver Velodyne driver. |
class | VelodyneScanDecoder Base class for Velodyne LiDAR decoder. |
struct | raw_block Raw Velodyne data block. |
struct | raw_packet Raw Velodyne packet. |
Public Types
Type | Name |
---|---|
enum | AngleCorrectionType |
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 = = |
2.665f |
|
const float | g_vls128_seq_duration = = |
53.3f |
Public Functions
Type | Name |
---|---|
bool | angle_is_between (T start_angle, T end_angle, T angle, bool start_inclusive=true, bool end_inclusive=true) Tests if angle is in the region of the circle defined bystart_angle andend_angle . Notably,end_angle can be smaller thanstart_angle , in which case the region passes over the 360/0 deg bound. This function is unit-independent (but all angles have to have the same unit), so degrees, radians, and arbitrary scale factors can be used. |
T | normalize_angle (T angle, T max_angle) Normalizes an angle to the interval [0; max_angle]. This function is unit-independent. max_angle is 360 for degrees, 2 * M_PI for radians, and the corresponding scaled value for scaled units such as centi-degrees (36000). |
Public Types Documentation
enum AngleCorrectionType
enum nebula::drivers::AngleCorrectionType {
CALIBRATION,
CORRECTION
};
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 angle_is_between
Tests if angle
is in the region of the circle defined bystart_angle
andend_angle
. Notably,end_angle
can be smaller thanstart_angle
, in which case the region passes over the 360/0 deg bound. This function is unit-independent (but all angles have to have the same unit), so degrees, radians, and arbitrary scale factors can be used.
template<typename T>
bool nebula::drivers::angle_is_between (
T start_angle,
T end_angle,
T angle,
bool start_inclusive=true,
bool end_inclusive=true
)
function normalize_angle
Normalizes an angle to the interval [0; max_angle]. This function is unit-independent. max_angle
is 360 for degrees, 2 * M_PI for radians, and the corresponding scaled value for scaled units such as centi-degrees (36000).
template<typename T>
T nebula::drivers::normalize_angle (
T angle,
T max_angle
)
The documentation for this class was generated from the following file nebula_decoders/include/nebula_decoders/nebula_decoders_common/angles.hpp