Skip to content

Commit

Permalink
Merge branch 'main' into porting/autoware_qp_interface
Browse files Browse the repository at this point in the history
  • Loading branch information
youtalk authored Jan 8, 2025
2 parents 4ae5163 + 01bd0b1 commit 3f57193
Show file tree
Hide file tree
Showing 11 changed files with 391 additions and 7 deletions.
2 changes: 2 additions & 0 deletions .cppcheck_suppressions
Original file line number Diff line number Diff line change
@@ -1,4 +1,6 @@
*:*/test/*

missingInclude
missingIncludeSystem
unmatchedSuppression
unusedFunction
4 changes: 2 additions & 2 deletions .github/workflows/clang-tidy-pr-comments-manually.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ jobs:
runs-on: ubuntu-22.04
steps:
- name: Check out repository
uses: actions/checkout@v3
uses: actions/checkout@v4

- name: Download analysis results
run: |
Expand All @@ -40,7 +40,7 @@ jobs:
- name: Check out PR head
if: ${{ steps.check-fixes-yaml-existence.outputs.exists == 'true' }}
uses: actions/checkout@v3
uses: actions/checkout@v4
with:
repository: ${{ steps.set-variables.outputs.pr-head-repo }}
ref: ${{ steps.set-variables.outputs.pr-head-ref }}
Expand Down
4 changes: 2 additions & 2 deletions .github/workflows/clang-tidy-pr-comments.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ jobs:
runs-on: ubuntu-22.04
steps:
- name: Check out repository
uses: actions/checkout@v3
uses: actions/checkout@v4

- name: Download analysis results
run: |
Expand All @@ -41,7 +41,7 @@ jobs:
- name: Check out PR head
if: ${{ steps.check-fixes-yaml-existence.outputs.exists == 'true' }}
uses: actions/checkout@v3
uses: actions/checkout@v4
with:
repository: ${{ steps.set-variables.outputs.pr-head-repo }}
ref: ${{ steps.set-variables.outputs.pr-head-ref }}
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/cppcheck-weekly.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ jobs:

steps:
- name: Checkout code
uses: actions/checkout@v2
uses: actions/checkout@v4

# cppcheck from apt does not yet support --check-level args, and thus install from snap
- name: Install Cppcheck from snap
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/delete-closed-pr-docs.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ jobs:
runs-on: ubuntu-22.04
steps:
- name: Check out repository
uses: actions/checkout@v3
uses: actions/checkout@v4
with:
fetch-depth: 0

Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/deploy-docs.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ jobs:
runs-on: ubuntu-22.04
steps:
- name: Check out repository
uses: actions/checkout@v3
uses: actions/checkout@v4
with:
fetch-depth: 0
ref: ${{ github.event.pull_request.head.sha }}
Expand Down
25 changes: 25 additions & 0 deletions common/autoware_point_types/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
cmake_minimum_required(VERSION 3.14)
project(autoware_point_types)

find_package(autoware_cmake REQUIRED)
autoware_package()

include_directories(
include
SYSTEM
${PCL_INCLUDE_DIRS}
)

if(BUILD_TESTING)
ament_add_ros_isolated_gtest(test_autoware_point_types
test/test_point_types.cpp
)
target_include_directories(test_autoware_point_types
PRIVATE include
)
ament_target_dependencies(test_autoware_point_types
point_cloud_msg_wrapper
)
endif()

ament_auto_package()
68 changes: 68 additions & 0 deletions common/autoware_point_types/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,68 @@
# Autoware Point Types

## Overview

This package provides a variety of structures to represent different types of point cloud data, mainly used for point cloud processing and analysis.

## Design

### Point cloud data type definition

`autoware_point_types` defines multiple structures (such as PointXYZI, PointXYZIRC, PointXYZIRADRT, PointXYZIRCAEDT), each structure contains different attributes to adapt to different application scenarios.

- `autoware::point_types::PointXYZI`: Point type with intensity information.
- `autoware::point_types::PointXYZIRC`: Extended PointXYZI, adds return_type and channel information.
- `autoware::point_types::PointXYZIRADRT`: Extended PointXYZI, adds ring, azimuth, distance, return_type and time_stamp information.
- `autoware::point_types::PointXYZIRCAEDT`: Similar to PointXYZIRADRT, but adds elevation information and uses `std::uint32_t` as the data type for time_stamp.

### Operator overload

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.

### Field generators

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.

### Registration mechanism

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.

## Usage

- Create a point cloud object of PointXYZIRC type

```cpp
#include "autoware/point_types/types.hpp"

int main(){
pcl::PointCloud<autoware::point_types::PointXYZIRC>::Ptr cloud(new pcl::PointCloud<autoware::point_types::PointXYZIRC>());

for (int i = 0; i < 5; ++i) {
autoware::point_types::PointXYZIRC point;
point.x = static_cast<float>(i * 0.1);
point.y = static_cast<float>(i * 0.2);
point.z = static_cast<float>(i * 0.3);
point.intensity = static_cast<std::uint8_t>(i * 10);
point.return_type = autoware::point_types::ReturnType::SINGLE_STRONGEST;
point.channel = static_cast<std::uint16_t>(i);

cloud->points.push_back(point);
}
cloud->width = cloud->points.size();
cloud->height = 1;

return 0;
}
```

- Convert ROS message to point cloud of PointXYZIRC type

```cpp
ExampleNode::points_callback(const PointCloud2::ConstSharedPtr & points_msg_ptr)
{
pcl::PointCloud<autoware::point_types::PointXYZIRC>::Ptr points_ptr(
new pcl::PointCloud<autoware::point_types::PointXYZIRC>);

pcl::fromROSMsg(*points_msg_ptr, *points_ptr);
}
```
188 changes: 188 additions & 0 deletions common/autoware_point_types/include/autoware/point_types/types.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,188 @@
// Copyright 2021 Tier IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef AUTOWARE__POINT_TYPES__TYPES_HPP_
#define AUTOWARE__POINT_TYPES__TYPES_HPP_

#include <point_cloud_msg_wrapper/point_cloud_msg_wrapper.hpp>

#include <pcl/point_types.h>

#include <cmath>
#include <tuple>

namespace autoware::point_types
{
template <class T>
bool float_eq(const T a, const T b, const T eps = 10e-6)
{
return std::fabs(a - b) < eps;
}

struct PointXYZI
{
float x{0.0F};
float y{0.0F};
float z{0.0F};
float intensity{0.0F};
friend bool operator==(const PointXYZI & p1, const PointXYZI & p2) noexcept
{
return float_eq<float>(p1.x, p2.x) && float_eq<float>(p1.y, p2.y) &&
float_eq<float>(p1.z, p2.z) && float_eq<float>(p1.intensity, p2.intensity);
}
};

enum ReturnType : uint8_t {
INVALID = 0,
SINGLE_STRONGEST,
SINGLE_LAST,
DUAL_STRONGEST_FIRST,
DUAL_STRONGEST_LAST,
DUAL_WEAK_FIRST,
DUAL_WEAK_LAST,
DUAL_ONLY,
};

struct PointXYZIRC
{
float x{0.0F};
float y{0.0F};
float z{0.0F};
std::uint8_t intensity{0U};
std::uint8_t return_type{0U};
std::uint16_t channel{0U};

friend bool operator==(const PointXYZIRC & p1, const PointXYZIRC & p2) noexcept
{
return float_eq<float>(p1.x, p2.x) && float_eq<float>(p1.y, p2.y) &&
float_eq<float>(p1.z, p2.z) && p1.intensity == p2.intensity &&
p1.return_type == p2.return_type && p1.channel == p2.channel;
}
};

struct PointXYZIRADRT
{
float x{0.0F};
float y{0.0F};
float z{0.0F};
float intensity{0.0F};
uint16_t ring{0U};
float azimuth{0.0F};
float distance{0.0F};
uint8_t return_type{0U};
double time_stamp{0.0};
friend bool operator==(const PointXYZIRADRT & p1, const PointXYZIRADRT & p2) noexcept
{
return float_eq<float>(p1.x, p2.x) && float_eq<float>(p1.y, p2.y) &&
float_eq<float>(p1.z, p2.z) && float_eq<float>(p1.intensity, p2.intensity) &&
p1.ring == p2.ring && float_eq<float>(p1.azimuth, p2.azimuth) &&
float_eq<float>(p1.distance, p2.distance) && p1.return_type == p2.return_type &&
float_eq<float>(p1.time_stamp, p2.time_stamp);
}
};

struct PointXYZIRCAEDT
{
float x{0.0F};
float y{0.0F};
float z{0.0F};
std::uint8_t intensity{0U};
std::uint8_t return_type{0U};
std::uint16_t channel{0U};
float azimuth{0.0F};
float elevation{0.0F};
float distance{0.0F};
std::uint32_t time_stamp{0U};

friend bool operator==(const PointXYZIRCAEDT & p1, const PointXYZIRCAEDT & p2) noexcept
{
return float_eq<float>(p1.x, p2.x) && float_eq<float>(p1.y, p2.y) &&
float_eq<float>(p1.z, p2.z) && p1.intensity == p2.intensity &&
p1.return_type == p2.return_type && p1.channel == p2.channel &&
float_eq<float>(p1.azimuth, p2.azimuth) && float_eq<float>(p1.distance, p2.distance) &&
p1.time_stamp == p2.time_stamp;
}
};

enum class PointXYZIIndex { X, Y, Z, Intensity };
enum class PointXYZIRCIndex { X, Y, Z, Intensity, ReturnType, Channel };
enum class PointXYZIRADRTIndex {
X,
Y,
Z,
Intensity,
Ring,
Azimuth,
Distance,
ReturnType,
TimeStamp
};
enum class PointXYZIRCAEDTIndex {
X,
Y,
Z,
Intensity,
ReturnType,
Channel,
Azimuth,
Elevation,
Distance,
TimeStamp
};

LIDAR_UTILS__DEFINE_FIELD_GENERATOR_FOR_MEMBER(azimuth);
LIDAR_UTILS__DEFINE_FIELD_GENERATOR_FOR_MEMBER(elevation);
LIDAR_UTILS__DEFINE_FIELD_GENERATOR_FOR_MEMBER(distance);
LIDAR_UTILS__DEFINE_FIELD_GENERATOR_FOR_MEMBER(return_type);
LIDAR_UTILS__DEFINE_FIELD_GENERATOR_FOR_MEMBER(time_stamp);

LIDAR_UTILS__DEFINE_FIELD_GENERATOR_FOR_MEMBER(channel);

using PointXYZIRCGenerator = std::tuple<
point_cloud_msg_wrapper::field_x_generator, point_cloud_msg_wrapper::field_y_generator,
point_cloud_msg_wrapper::field_z_generator, point_cloud_msg_wrapper::field_intensity_generator,
field_return_type_generator, field_channel_generator>;

using PointXYZIRADRTGenerator = std::tuple<
point_cloud_msg_wrapper::field_x_generator, point_cloud_msg_wrapper::field_y_generator,
point_cloud_msg_wrapper::field_z_generator, point_cloud_msg_wrapper::field_intensity_generator,
point_cloud_msg_wrapper::field_ring_generator, field_azimuth_generator, field_distance_generator,
field_return_type_generator, field_time_stamp_generator>;

using PointXYZIRCAEDTGenerator = std::tuple<
point_cloud_msg_wrapper::field_x_generator, point_cloud_msg_wrapper::field_y_generator,
point_cloud_msg_wrapper::field_z_generator, point_cloud_msg_wrapper::field_intensity_generator,
field_return_type_generator, field_channel_generator, field_azimuth_generator,
field_elevation_generator, field_distance_generator, field_time_stamp_generator>;

} // namespace autoware::point_types

POINT_CLOUD_REGISTER_POINT_STRUCT(
autoware::point_types::PointXYZIRC,
(float, x, x)(float, y, y)(float, z, z)(std::uint8_t, intensity, intensity)(
std::uint8_t, return_type, return_type)(std::uint16_t, channel, channel))

POINT_CLOUD_REGISTER_POINT_STRUCT(
autoware::point_types::PointXYZIRADRT,
(float, x, x)(float, y, y)(float, z, z)(float, intensity, intensity)(std::uint16_t, ring, ring)(
float, azimuth, azimuth)(float, distance, distance)(std::uint8_t, return_type, return_type)(
double, time_stamp, time_stamp))

POINT_CLOUD_REGISTER_POINT_STRUCT(
autoware::point_types::PointXYZIRCAEDT,
(float, x, x)(float, y, y)(float, z, z)(std::uint8_t, intensity, intensity)(
std::uint8_t, return_type,
return_type)(std::uint16_t, channel, channel)(float, azimuth, azimuth)(
float, elevation, elevation)(float, distance, distance)(std::uint32_t, time_stamp, time_stamp))
#endif // AUTOWARE__POINT_TYPES__TYPES_HPP_
35 changes: 35 additions & 0 deletions common/autoware_point_types/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,35 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>autoware_point_types</name>
<version>0.0.0</version>
<description>The point types definition to use point_cloud_msg_wrapper</description>
<maintainer email="[email protected]">David Wong</maintainer>
<maintainer email="[email protected]">Max Schmeller</maintainer>
<maintainer email="[email protected]">Cynthia Liu</maintainer>
<license>Apache License 2.0</license>

<buildtool_depend>ament_cmake_core</buildtool_depend>
<buildtool_depend>ament_cmake_export_dependencies</buildtool_depend>
<buildtool_depend>ament_cmake_test</buildtool_depend>
<buildtool_depend>autoware_cmake</buildtool_depend>

<buildtool_export_depend>ament_cmake_core</buildtool_export_depend>
<buildtool_export_depend>ament_cmake_test</buildtool_export_depend>

<depend>ament_cmake_copyright</depend>
<depend>ament_cmake_cppcheck</depend>
<depend>ament_cmake_lint_cmake</depend>
<depend>ament_cmake_xmllint</depend>
<depend>pcl_ros</depend>
<depend>point_cloud_msg_wrapper</depend>

<test_depend>ament_cmake_ros</test_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>autoware_lint_common</test_depend>
<test_depend>point_cloud_msg_wrapper</test_depend>

<export>
<build_type>ament_cmake</build_type>
</export>
</package>
Loading

0 comments on commit 3f57193

Please sign in to comment.