Autoware.Auto
point_cloud_fusion.hpp
Go to the documentation of this file.
1 // Copyright 2019-2021 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 
17 #ifndef POINT_CLOUD_FUSION__POINT_CLOUD_FUSION_HPP_
18 #define POINT_CLOUD_FUSION__POINT_CLOUD_FUSION_HPP_
19 
21 
22 #include <common/types.hpp>
24 #include <point_cloud_msg_wrapper/point_cloud_msg_wrapper.hpp>
25 #include <vector>
26 
27 namespace autoware
28 {
29 namespace perception
30 {
31 namespace filters
32 {
33 namespace point_cloud_fusion
34 {
37 
38 class POINT_CLOUD_FUSION_PUBLIC PointCloudFusion
39 {
40 public:
41  enum class Error : uint8_t
42  {
43  NONE = 0U,
44  TOO_LARGE,
45  INSERT_FAILED
46  }; // enum class Error
48 
52  explicit PointCloudFusion(
53  uint32_t cloud_capacity,
54  size_t input_topics_size);
55 
63  uint32_t fuse_pc_msgs(
64  const std::array<PointCloudMsgT::ConstSharedPtr, 8> & msgs,
65  PointCloudMsgT & cloud_concatenated);
66 
67 private:
68  void concatenate_pointcloud(
69  const PointCloudMsgT & pc_in,
70  uint32_t & concat_idx,
71  CloudModifier & modifier) const;
72 
73  uint32_t m_cloud_capacity;
74  size_t m_input_topics_size;
75 };
76 
77 } // namespace point_cloud_fusion
78 } // namespace filters
79 } // namespace perception
80 } // namespace autoware
81 
82 #endif // POINT_CLOUD_FUSION__POINT_CLOUD_FUSION_HPP_
autoware::perception::filters::point_cloud_fusion::PointCloudFusion::PointCloudMsgT
sensor_msgs::msg::PointCloud2 PointCloudMsgT
Definition: point_cloud_fusion.hpp:47
autoware::perception::filters::point_cloud_fusion::PointCloudFusion
Definition: point_cloud_fusion.hpp:38
types.hpp
This file includes common type definition.
autoware::perception::filters::point_cloud_fusion::PointCloudFusion::Error
Error
Definition: point_cloud_fusion.hpp:41
point_cloud_utils.hpp
This class defines common functions and classes to work with pointclouds.
autoware::common::types::PointXYZIF
Definition: types.hpp:56
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
autoware::common::lidar_utils::CloudModifier
point_cloud_msg_wrapper::PointCloud2Modifier< autoware::common::types::PointXYZI > CloudModifier
Definition: point_cloud_utils.hpp:53
visibility_control.hpp
autoware::perception::filters::filter_node_base::PointCloud2
sensor_msgs::msg::PointCloud2 PointCloud2
Definition: filter_node_base.cpp:32