|
| 1 | +// Copyright 2021 Tier IV, Inc. |
| 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 | +#ifndef AUTOWARE__POINT_TYPES__TYPES_HPP_ |
| 16 | +#define AUTOWARE__POINT_TYPES__TYPES_HPP_ |
| 17 | + |
| 18 | +#include <point_cloud_msg_wrapper/point_cloud_msg_wrapper.hpp> |
| 19 | + |
| 20 | +#include <pcl/point_types.h> |
| 21 | + |
| 22 | +#include <cmath> |
| 23 | +#include <tuple> |
| 24 | + |
| 25 | +namespace autoware::point_types |
| 26 | +{ |
| 27 | +template <class T> |
| 28 | +bool float_eq(const T a, const T b, const T eps = 10e-6) |
| 29 | +{ |
| 30 | + return std::fabs(a - b) < eps; |
| 31 | +} |
| 32 | + |
| 33 | +struct PointXYZI |
| 34 | +{ |
| 35 | + float x{0.0F}; |
| 36 | + float y{0.0F}; |
| 37 | + float z{0.0F}; |
| 38 | + float intensity{0.0F}; |
| 39 | + friend bool operator==(const PointXYZI & p1, const PointXYZI & p2) noexcept |
| 40 | + { |
| 41 | + return float_eq<float>(p1.x, p2.x) && float_eq<float>(p1.y, p2.y) && |
| 42 | + float_eq<float>(p1.z, p2.z) && float_eq<float>(p1.intensity, p2.intensity); |
| 43 | + } |
| 44 | +}; |
| 45 | + |
| 46 | +enum ReturnType : uint8_t { |
| 47 | + INVALID = 0, |
| 48 | + SINGLE_STRONGEST, |
| 49 | + SINGLE_LAST, |
| 50 | + DUAL_STRONGEST_FIRST, |
| 51 | + DUAL_STRONGEST_LAST, |
| 52 | + DUAL_WEAK_FIRST, |
| 53 | + DUAL_WEAK_LAST, |
| 54 | + DUAL_ONLY, |
| 55 | +}; |
| 56 | + |
| 57 | +struct PointXYZIRC |
| 58 | +{ |
| 59 | + float x{0.0F}; |
| 60 | + float y{0.0F}; |
| 61 | + float z{0.0F}; |
| 62 | + std::uint8_t intensity{0U}; |
| 63 | + std::uint8_t return_type{0U}; |
| 64 | + std::uint16_t channel{0U}; |
| 65 | + |
| 66 | + friend bool operator==(const PointXYZIRC & p1, const PointXYZIRC & p2) noexcept |
| 67 | + { |
| 68 | + return float_eq<float>(p1.x, p2.x) && float_eq<float>(p1.y, p2.y) && |
| 69 | + float_eq<float>(p1.z, p2.z) && p1.intensity == p2.intensity && |
| 70 | + p1.return_type == p2.return_type && p1.channel == p2.channel; |
| 71 | + } |
| 72 | +}; |
| 73 | + |
| 74 | +struct PointXYZIRADRT |
| 75 | +{ |
| 76 | + float x{0.0F}; |
| 77 | + float y{0.0F}; |
| 78 | + float z{0.0F}; |
| 79 | + float intensity{0.0F}; |
| 80 | + uint16_t ring{0U}; |
| 81 | + float azimuth{0.0F}; |
| 82 | + float distance{0.0F}; |
| 83 | + uint8_t return_type{0U}; |
| 84 | + double time_stamp{0.0}; |
| 85 | + friend bool operator==(const PointXYZIRADRT & p1, const PointXYZIRADRT & p2) noexcept |
| 86 | + { |
| 87 | + return float_eq<float>(p1.x, p2.x) && float_eq<float>(p1.y, p2.y) && |
| 88 | + float_eq<float>(p1.z, p2.z) && float_eq<float>(p1.intensity, p2.intensity) && |
| 89 | + p1.ring == p2.ring && float_eq<float>(p1.azimuth, p2.azimuth) && |
| 90 | + float_eq<float>(p1.distance, p2.distance) && p1.return_type == p2.return_type && |
| 91 | + float_eq<float>(p1.time_stamp, p2.time_stamp); |
| 92 | + } |
| 93 | +}; |
| 94 | + |
| 95 | +struct PointXYZIRCAEDT |
| 96 | +{ |
| 97 | + float x{0.0F}; |
| 98 | + float y{0.0F}; |
| 99 | + float z{0.0F}; |
| 100 | + std::uint8_t intensity{0U}; |
| 101 | + std::uint8_t return_type{0U}; |
| 102 | + std::uint16_t channel{0U}; |
| 103 | + float azimuth{0.0F}; |
| 104 | + float elevation{0.0F}; |
| 105 | + float distance{0.0F}; |
| 106 | + std::uint32_t time_stamp{0U}; |
| 107 | + |
| 108 | + friend bool operator==(const PointXYZIRCAEDT & p1, const PointXYZIRCAEDT & p2) noexcept |
| 109 | + { |
| 110 | + return float_eq<float>(p1.x, p2.x) && float_eq<float>(p1.y, p2.y) && |
| 111 | + float_eq<float>(p1.z, p2.z) && p1.intensity == p2.intensity && |
| 112 | + p1.return_type == p2.return_type && p1.channel == p2.channel && |
| 113 | + float_eq<float>(p1.azimuth, p2.azimuth) && float_eq<float>(p1.distance, p2.distance) && |
| 114 | + p1.time_stamp == p2.time_stamp; |
| 115 | + } |
| 116 | +}; |
| 117 | + |
| 118 | +enum class PointXYZIIndex { X, Y, Z, Intensity }; |
| 119 | +enum class PointXYZIRCIndex { X, Y, Z, Intensity, ReturnType, Channel }; |
| 120 | +enum class PointXYZIRADRTIndex { |
| 121 | + X, |
| 122 | + Y, |
| 123 | + Z, |
| 124 | + Intensity, |
| 125 | + Ring, |
| 126 | + Azimuth, |
| 127 | + Distance, |
| 128 | + ReturnType, |
| 129 | + TimeStamp |
| 130 | +}; |
| 131 | +enum class PointXYZIRCAEDTIndex { |
| 132 | + X, |
| 133 | + Y, |
| 134 | + Z, |
| 135 | + Intensity, |
| 136 | + ReturnType, |
| 137 | + Channel, |
| 138 | + Azimuth, |
| 139 | + Elevation, |
| 140 | + Distance, |
| 141 | + TimeStamp |
| 142 | +}; |
| 143 | + |
| 144 | +LIDAR_UTILS__DEFINE_FIELD_GENERATOR_FOR_MEMBER(azimuth); |
| 145 | +LIDAR_UTILS__DEFINE_FIELD_GENERATOR_FOR_MEMBER(elevation); |
| 146 | +LIDAR_UTILS__DEFINE_FIELD_GENERATOR_FOR_MEMBER(distance); |
| 147 | +LIDAR_UTILS__DEFINE_FIELD_GENERATOR_FOR_MEMBER(return_type); |
| 148 | +LIDAR_UTILS__DEFINE_FIELD_GENERATOR_FOR_MEMBER(time_stamp); |
| 149 | + |
| 150 | +LIDAR_UTILS__DEFINE_FIELD_GENERATOR_FOR_MEMBER(channel); |
| 151 | + |
| 152 | +using PointXYZIRCGenerator = std::tuple< |
| 153 | + point_cloud_msg_wrapper::field_x_generator, point_cloud_msg_wrapper::field_y_generator, |
| 154 | + point_cloud_msg_wrapper::field_z_generator, point_cloud_msg_wrapper::field_intensity_generator, |
| 155 | + field_return_type_generator, field_channel_generator>; |
| 156 | + |
| 157 | +using PointXYZIRADRTGenerator = std::tuple< |
| 158 | + point_cloud_msg_wrapper::field_x_generator, point_cloud_msg_wrapper::field_y_generator, |
| 159 | + point_cloud_msg_wrapper::field_z_generator, point_cloud_msg_wrapper::field_intensity_generator, |
| 160 | + point_cloud_msg_wrapper::field_ring_generator, field_azimuth_generator, field_distance_generator, |
| 161 | + field_return_type_generator, field_time_stamp_generator>; |
| 162 | + |
| 163 | +using PointXYZIRCAEDTGenerator = std::tuple< |
| 164 | + point_cloud_msg_wrapper::field_x_generator, point_cloud_msg_wrapper::field_y_generator, |
| 165 | + point_cloud_msg_wrapper::field_z_generator, point_cloud_msg_wrapper::field_intensity_generator, |
| 166 | + field_return_type_generator, field_channel_generator, field_azimuth_generator, |
| 167 | + field_elevation_generator, field_distance_generator, field_time_stamp_generator>; |
| 168 | + |
| 169 | +} // namespace autoware::point_types |
| 170 | + |
| 171 | +POINT_CLOUD_REGISTER_POINT_STRUCT( |
| 172 | + autoware::point_types::PointXYZIRC, |
| 173 | + (float, x, x)(float, y, y)(float, z, z)(std::uint8_t, intensity, intensity)( |
| 174 | + std::uint8_t, return_type, return_type)(std::uint16_t, channel, channel)) |
| 175 | + |
| 176 | +POINT_CLOUD_REGISTER_POINT_STRUCT( |
| 177 | + autoware::point_types::PointXYZIRADRT, |
| 178 | + (float, x, x)(float, y, y)(float, z, z)(float, intensity, intensity)(std::uint16_t, ring, ring)( |
| 179 | + float, azimuth, azimuth)(float, distance, distance)(std::uint8_t, return_type, return_type)( |
| 180 | + double, time_stamp, time_stamp)) |
| 181 | + |
| 182 | +POINT_CLOUD_REGISTER_POINT_STRUCT( |
| 183 | + autoware::point_types::PointXYZIRCAEDT, |
| 184 | + (float, x, x)(float, y, y)(float, z, z)(std::uint8_t, intensity, intensity)( |
| 185 | + std::uint8_t, return_type, |
| 186 | + return_type)(std::uint16_t, channel, channel)(float, azimuth, azimuth)( |
| 187 | + float, elevation, elevation)(float, distance, distance)(std::uint32_t, time_stamp, time_stamp)) |
| 188 | +#endif // AUTOWARE__POINT_TYPES__TYPES_HPP_ |
0 commit comments