Go to the documentation of this file.
21 #ifndef VELODYNE_DRIVER__COMMON_HPP_
22 #define VELODYNE_DRIVER__COMMON_HPP_
25 #include <geometry_msgs/msg/point32.hpp>
39 namespace velodyne_driver
60 inline uint32_t
to_uint32(
const uint8_t first,
const uint8_t second)
64 const uint32_t ret =
static_cast<uint32_t
>(first) << 8U;
65 return ret +
static_cast<uint32_t
>(second);
73 #endif // VELODYNE_DRIVER__COMMON_HPP_
This file includes common type definition.
static constexpr uint32_t AZIMUTH_ROTATION_RESOLUTION
resolution of azimuth angle: number of points in a full rotation
Definition: common.hpp:48
bool bool8_t
Definition: types.hpp:39
static constexpr uint16_t NUM_BLOCKS_PER_PACKET
number of data blocks per data packet
Definition: common.hpp:55
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
static constexpr uint16_t NUM_POINTS_PER_BLOCK
number of points stored in a data block
Definition: common.hpp:57
static constexpr float32_t DEG2IDX
conversion from a degree (vlp) to idx
Definition: common.hpp:50
float float32_t
Definition: types.hpp:45
static constexpr uint32_t NUM_INTENSITY_VALUES
how intensity is quantized: 1 byte = 256 possible values
Definition: common.hpp:52
uint32_t to_uint32(const uint8_t first, const uint8_t second)
computes 2 byte representation of two bytes from out of order velodyne packet
Definition: common.hpp:60