Skip to content

Commit 97e5cf2

Browse files
authored
Merge branch 'main' into port-autoware_kalman_filter
2 parents a25fae3 + 871106e commit 97e5cf2

File tree

10 files changed

+389
-7
lines changed

10 files changed

+389
-7
lines changed

.github/workflows/clang-tidy-pr-comments-manually.yaml

+2-2
Original file line numberDiff line numberDiff line change
@@ -15,7 +15,7 @@ jobs:
1515
runs-on: ubuntu-22.04
1616
steps:
1717
- name: Check out repository
18-
uses: actions/checkout@v3
18+
uses: actions/checkout@v4
1919

2020
- name: Download analysis results
2121
run: |
@@ -40,7 +40,7 @@ jobs:
4040
4141
- name: Check out PR head
4242
if: ${{ steps.check-fixes-yaml-existence.outputs.exists == 'true' }}
43-
uses: actions/checkout@v3
43+
uses: actions/checkout@v4
4444
with:
4545
repository: ${{ steps.set-variables.outputs.pr-head-repo }}
4646
ref: ${{ steps.set-variables.outputs.pr-head-ref }}

.github/workflows/clang-tidy-pr-comments.yaml

+2-2
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,7 @@ jobs:
1717
runs-on: ubuntu-22.04
1818
steps:
1919
- name: Check out repository
20-
uses: actions/checkout@v3
20+
uses: actions/checkout@v4
2121

2222
- name: Download analysis results
2323
run: |
@@ -41,7 +41,7 @@ jobs:
4141
4242
- name: Check out PR head
4343
if: ${{ steps.check-fixes-yaml-existence.outputs.exists == 'true' }}
44-
uses: actions/checkout@v3
44+
uses: actions/checkout@v4
4545
with:
4646
repository: ${{ steps.set-variables.outputs.pr-head-repo }}
4747
ref: ${{ steps.set-variables.outputs.pr-head-ref }}

.github/workflows/cppcheck-weekly.yaml

+1-1
Original file line numberDiff line numberDiff line change
@@ -11,7 +11,7 @@ jobs:
1111

1212
steps:
1313
- name: Checkout code
14-
uses: actions/checkout@v2
14+
uses: actions/checkout@v4
1515

1616
# cppcheck from apt does not yet support --check-level args, and thus install from snap
1717
- name: Install Cppcheck from snap

.github/workflows/delete-closed-pr-docs.yaml

+1-1
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,7 @@ jobs:
1414
runs-on: ubuntu-22.04
1515
steps:
1616
- name: Check out repository
17-
uses: actions/checkout@v3
17+
uses: actions/checkout@v4
1818
with:
1919
fetch-depth: 0
2020

.github/workflows/deploy-docs.yaml

+1-1
Original file line numberDiff line numberDiff line change
@@ -34,7 +34,7 @@ jobs:
3434
runs-on: ubuntu-22.04
3535
steps:
3636
- name: Check out repository
37-
uses: actions/checkout@v3
37+
uses: actions/checkout@v4
3838
with:
3939
fetch-depth: 0
4040
ref: ${{ github.event.pull_request.head.sha }}
+25
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,25 @@
1+
cmake_minimum_required(VERSION 3.14)
2+
project(autoware_point_types)
3+
4+
find_package(autoware_cmake REQUIRED)
5+
autoware_package()
6+
7+
include_directories(
8+
include
9+
SYSTEM
10+
${PCL_INCLUDE_DIRS}
11+
)
12+
13+
if(BUILD_TESTING)
14+
ament_add_ros_isolated_gtest(test_autoware_point_types
15+
test/test_point_types.cpp
16+
)
17+
target_include_directories(test_autoware_point_types
18+
PRIVATE include
19+
)
20+
ament_target_dependencies(test_autoware_point_types
21+
point_cloud_msg_wrapper
22+
)
23+
endif()
24+
25+
ament_auto_package()

common/autoware_point_types/README.md

+68
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,68 @@
1+
# Autoware Point Types
2+
3+
## Overview
4+
5+
This package provides a variety of structures to represent different types of point cloud data, mainly used for point cloud processing and analysis.
6+
7+
## Design
8+
9+
### Point cloud data type definition
10+
11+
`autoware_point_types` defines multiple structures (such as PointXYZI, PointXYZIRC, PointXYZIRADRT, PointXYZIRCAEDT), each structure contains different attributes to adapt to different application scenarios.
12+
13+
- `autoware::point_types::PointXYZI`: Point type with intensity information.
14+
- `autoware::point_types::PointXYZIRC`: Extended PointXYZI, adds return_type and channel information.
15+
- `autoware::point_types::PointXYZIRADRT`: Extended PointXYZI, adds ring, azimuth, distance, return_type and time_stamp information.
16+
- `autoware::point_types::PointXYZIRCAEDT`: Similar to PointXYZIRADRT, but adds elevation information and uses `std::uint32_t` as the data type for time_stamp.
17+
18+
### Operator overload
19+
20+
Each structure overloads the `==` operator, allowing users to easily compare whether two points are equal, which is very useful for deduplication and matching of point cloud data.
21+
22+
### Field generators
23+
24+
The field generator is implemented using macro definitions and std::tuple, which simplifies the serialization and deserialization process of point cloud messages and improves the reusability and readability of the code.
25+
26+
### Registration mechanism
27+
28+
Register custom point cloud structures into the PCL library through the macro `POINT_CLOUD_REGISTER_POINT_STRUCT`, so that these structures can be directly integrated with other functions of the PCL library.
29+
30+
## Usage
31+
32+
- Create a point cloud object of PointXYZIRC type
33+
34+
```cpp
35+
#include "autoware/point_types/types.hpp"
36+
37+
int main(){
38+
pcl::PointCloud<autoware::point_types::PointXYZIRC>::Ptr cloud(new pcl::PointCloud<autoware::point_types::PointXYZIRC>());
39+
40+
for (int i = 0; i < 5; ++i) {
41+
autoware::point_types::PointXYZIRC point;
42+
point.x = static_cast<float>(i * 0.1);
43+
point.y = static_cast<float>(i * 0.2);
44+
point.z = static_cast<float>(i * 0.3);
45+
point.intensity = static_cast<std::uint8_t>(i * 10);
46+
point.return_type = autoware::point_types::ReturnType::SINGLE_STRONGEST;
47+
point.channel = static_cast<std::uint16_t>(i);
48+
49+
cloud->points.push_back(point);
50+
}
51+
cloud->width = cloud->points.size();
52+
cloud->height = 1;
53+
54+
return 0;
55+
}
56+
```
57+
58+
- Convert ROS message to point cloud of PointXYZIRC type
59+
60+
```cpp
61+
ExampleNode::points_callback(const PointCloud2::ConstSharedPtr & points_msg_ptr)
62+
{
63+
pcl::PointCloud<autoware::point_types::PointXYZIRC>::Ptr points_ptr(
64+
new pcl::PointCloud<autoware::point_types::PointXYZIRC>);
65+
66+
pcl::fromROSMsg(*points_msg_ptr, *points_ptr);
67+
}
68+
```
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,188 @@
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_
+35
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,35 @@
1+
<?xml version="1.0"?>
2+
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
3+
<package format="3">
4+
<name>autoware_point_types</name>
5+
<version>0.0.0</version>
6+
<description>The point types definition to use point_cloud_msg_wrapper</description>
7+
<maintainer email="david.wong@tier4.jp">David Wong</maintainer>
8+
<maintainer email="max.schmeller@tier4.jp">Max Schmeller</maintainer>
9+
<maintainer email="cynthia.liu@autocore.ai">Cynthia Liu</maintainer>
10+
<license>Apache License 2.0</license>
11+
12+
<buildtool_depend>ament_cmake_core</buildtool_depend>
13+
<buildtool_depend>ament_cmake_export_dependencies</buildtool_depend>
14+
<buildtool_depend>ament_cmake_test</buildtool_depend>
15+
<buildtool_depend>autoware_cmake</buildtool_depend>
16+
17+
<buildtool_export_depend>ament_cmake_core</buildtool_export_depend>
18+
<buildtool_export_depend>ament_cmake_test</buildtool_export_depend>
19+
20+
<depend>ament_cmake_copyright</depend>
21+
<depend>ament_cmake_cppcheck</depend>
22+
<depend>ament_cmake_lint_cmake</depend>
23+
<depend>ament_cmake_xmllint</depend>
24+
<depend>pcl_ros</depend>
25+
<depend>point_cloud_msg_wrapper</depend>
26+
27+
<test_depend>ament_cmake_ros</test_depend>
28+
<test_depend>ament_lint_auto</test_depend>
29+
<test_depend>autoware_lint_common</test_depend>
30+
<test_depend>point_cloud_msg_wrapper</test_depend>
31+
32+
<export>
33+
<build_type>ament_cmake</build_type>
34+
</export>
35+
</package>

0 commit comments

Comments
 (0)