Apollo
6.0
Open source self driving car software
|
Raw Velodyne data block. More...
#include <velodyne_parser.h>
Public Attributes | |
uint16_t | laser_block_id |
UPPER_BANK or LOWER_BANK. More... | |
uint16_t | rotation |
0-35999, divide by 100 to get degrees More... | |
uint8_t | data [BLOCK_DATA_SIZE] |
Raw Velodyne data block.
Each block contains data from either the upper or lower laser bank. The device returns three times as many upper bank blocks.
use cstdint types, so things work with both 64 and 32-bit machines
uint8_t apollo::drivers::velodyne::RawBlock::data[BLOCK_DATA_SIZE] |
uint16_t apollo::drivers::velodyne::RawBlock::laser_block_id |
UPPER_BANK or LOWER_BANK.
uint16_t apollo::drivers::velodyne::RawBlock::rotation |
0-35999, divide by 100 to get degrees