Autoware.Auto
common.hpp
Go to the documentation of this file.
1 // Copyright 2018-2020 the Autoware Foundation
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 //    http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 //
15 // Co-developed by Tier IV, Inc. and Apex.AI, Inc.
16 
20 
21 #ifndef VELODYNE_DRIVER__COMMON_HPP_
22 #define VELODYNE_DRIVER__COMMON_HPP_
23 
25 #include <geometry_msgs/msg/point32.hpp>
26 #include <common/types.hpp>
27 
28 namespace autoware
29 {
32 namespace drivers
33 {
39 namespace velodyne_driver
40 {
43 
44 // These constants seem to be shared among velodyne drivers. If a model with different specs is
45 // to be supported, they should be refactored.
46 
48 static constexpr uint32_t AZIMUTH_ROTATION_RESOLUTION = 36000U;
50 static constexpr float32_t DEG2IDX = static_cast<float32_t>(AZIMUTH_ROTATION_RESOLUTION) / 360.0F;
52 static constexpr uint32_t NUM_INTENSITY_VALUES = 256U;
53 
55 static constexpr uint16_t NUM_BLOCKS_PER_PACKET = 12U;
57 static constexpr uint16_t NUM_POINTS_PER_BLOCK = 32U;
58 
60 inline uint32_t to_uint32(const uint8_t first, const uint8_t second)
61 {
62  // probably ok since uint8_t<<8 =>uint32_t, this is to get around
63  // warning due to implicit promotion to int
64  const uint32_t ret = static_cast<uint32_t>(first) << 8U;
65  return ret + static_cast<uint32_t>(second);
66 }
67 
69 } // namespace velodyne_driver
70 } // namespace drivers
71 } // namespace autoware
72 
73 #endif // VELODYNE_DRIVER__COMMON_HPP_
types.hpp
This file includes common type definition.
autoware::drivers::velodyne_driver::AZIMUTH_ROTATION_RESOLUTION
static constexpr uint32_t AZIMUTH_ROTATION_RESOLUTION
resolution of azimuth angle: number of points in a full rotation
Definition: common.hpp:48
autoware::common::types::PointXYZIF
Definition: types.hpp:48
autoware::common::types::bool8_t
bool bool8_t
Definition: types.hpp:33
visibility_control.hpp
autoware::drivers::velodyne_driver::NUM_BLOCKS_PER_PACKET
static constexpr uint16_t NUM_BLOCKS_PER_PACKET
number of data blocks per data packet
Definition: common.hpp:55
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
autoware::drivers::velodyne_driver::NUM_POINTS_PER_BLOCK
static constexpr uint16_t NUM_POINTS_PER_BLOCK
number of points stored in a data block
Definition: common.hpp:57
autoware::drivers::velodyne_driver::DEG2IDX
static constexpr float32_t DEG2IDX
conversion from a degree (vlp) to idx
Definition: common.hpp:50
autoware::common::types::float32_t
float float32_t
Definition: types.hpp:36
autoware::drivers::velodyne_driver::NUM_INTENSITY_VALUES
static constexpr uint32_t NUM_INTENSITY_VALUES
how intensity is quantized: 1 byte = 256 possible values
Definition: common.hpp:52
autoware::drivers::velodyne_driver::to_uint32
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