Apollo  v5.5.0
Open source self driving car software
lidar_frame.h
Go to the documentation of this file.
1 /******************************************************************************
2  * Copyright 2018 The Apollo Authors. All Rights Reserved.
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *****************************************************************************/
16 #pragma once
17 
18 #include <memory>
19 #include <string>
20 #include <vector>
21 
22 #include "Eigen/Dense"
23 
28 
29 namespace apollo {
30 namespace perception {
31 namespace lidar {
32 
33 struct LidarFrame {
34  // point cloud
35  std::shared_ptr<base::AttributePointCloud<base::PointF>> cloud;
36  // world point cloud
37  std::shared_ptr<base::AttributePointCloud<base::PointD>> world_cloud;
38  // timestamp
39  double timestamp = 0.0;
40  // lidar to world pose
41  Eigen::Affine3d lidar2world_pose = Eigen::Affine3d::Identity();
42  // hdmap struct
43  std::shared_ptr<base::HdmapStruct> hdmap_struct = nullptr;
44  // segmented objects
45  std::vector<std::shared_ptr<base::Object>> segmented_objects;
46  // tracked objects
47  std::vector<std::shared_ptr<base::Object>> tracked_objects;
48  // point cloud roi indices
50  // point cloud non ground indices
52  // secondary segmentor indices
54  // sensor info
56  // reserve string
57  std::string reserve;
58 
59  void Reset() {
60  if (cloud) {
61  cloud->clear();
62  }
63  if (world_cloud) {
64  world_cloud->clear();
65  }
66  timestamp = 0.0;
67  lidar2world_pose = Eigen::Affine3d::Identity();
68  if (hdmap_struct) {
69  hdmap_struct->road_boundary.clear();
70  hdmap_struct->road_polygons.clear();
71  hdmap_struct->junction_polygons.clear();
72  hdmap_struct->hole_polygons.clear();
73  }
74  segmented_objects.clear();
75  tracked_objects.clear();
76  roi_indices.indices.clear();
77  non_ground_indices.indices.clear();
78  secondary_indices.indices.clear();
79  }
80 
82  const std::vector<uint32_t> &indices) {
83  if (cloud && filtered_cloud) {
84  filtered_cloud->CopyPointCloudExclude(*cloud, indices);
85  }
86  }
87 }; // struct LidarFrame
88 
89 } // namespace lidar
90 } // namespace perception
91 } // namespace apollo
std::shared_ptr< base::AttributePointCloud< base::PointF > > cloud
Definition: lidar_frame.h:35
base::PointIndices secondary_indices
Definition: lidar_frame.h:53
std::vector< int > indices
Definition: point.h:76
Definition: blob.h:72
base::PointIndices non_ground_indices
Definition: lidar_frame.h:51
base::PointIndices roi_indices
Definition: lidar_frame.h:49
Definition: point_cloud.h:33
void CopyPointCloudExclude(const PointCloud< PointT > &rhs, const std::vector< IndexType > &indices)
Definition: point_cloud.h:146
std::vector< std::shared_ptr< base::Object > > segmented_objects
Definition: lidar_frame.h:45
std::string reserve
Definition: lidar_frame.h:57
std::shared_ptr< base::AttributePointCloud< base::PointD > > world_cloud
Definition: lidar_frame.h:37
base::SensorInfo sensor_info
Definition: lidar_frame.h:55
void FilterPointCloud(base::PointCloud< base::PointF > *filtered_cloud, const std::vector< uint32_t > &indices)
Definition: lidar_frame.h:81
Definition: sensor_meta.h:57
std::vector< std::shared_ptr< base::Object > > tracked_objects
Definition: lidar_frame.h:47
Definition: lidar_frame.h:33
std::shared_ptr< base::HdmapStruct > hdmap_struct
Definition: lidar_frame.h:43
Eigen::Affine3d lidar2world_pose
Definition: lidar_frame.h:41
void Reset()
Definition: lidar_frame.h:59
double timestamp
Definition: lidar_frame.h:39