Apollo  6.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  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
35 
36  // point cloud
37  std::shared_ptr<base::AttributePointCloud<base::PointF>> cloud;
38  // world point cloud
39  std::shared_ptr<base::AttributePointCloud<base::PointD>> world_cloud;
40  // timestamp
41  double timestamp = 0.0;
42  // lidar to world pose
43  Eigen::Affine3d lidar2world_pose = Eigen::Affine3d::Identity();
44  // lidar to world pose
45  Eigen::Affine3d novatel2world_pose = Eigen::Affine3d::Identity();
46  // hdmap struct
47  std::shared_ptr<base::HdmapStruct> hdmap_struct = nullptr;
48  // segmented objects
49  std::vector<std::shared_ptr<base::Object>> segmented_objects;
50  // tracked objects
51  std::vector<std::shared_ptr<base::Object>> tracked_objects;
52  // point cloud roi indices
54  // point cloud non ground indices
56  // secondary segmentor indices
58  // sensor info
60  // reserve string
61  std::string reserve;
62 
63  void Reset() {
64  if (cloud) {
65  cloud->clear();
66  }
67  if (world_cloud) {
68  world_cloud->clear();
69  }
70  timestamp = 0.0;
71  lidar2world_pose = Eigen::Affine3d::Identity();
72  novatel2world_pose = Eigen::Affine3d::Identity();
73  if (hdmap_struct) {
74  hdmap_struct->road_boundary.clear();
75  hdmap_struct->road_polygons.clear();
76  hdmap_struct->junction_polygons.clear();
77  hdmap_struct->hole_polygons.clear();
78  }
79  segmented_objects.clear();
80  tracked_objects.clear();
81  roi_indices.indices.clear();
82  non_ground_indices.indices.clear();
83  secondary_indices.indices.clear();
84  }
85 
87  const std::vector<uint32_t> &indices) {
88  if (cloud && filtered_cloud) {
89  filtered_cloud->CopyPointCloudExclude(*cloud, indices);
90  }
91  }
92 }; // struct LidarFrame
93 
94 } // namespace lidar
95 } // namespace perception
96 } // namespace apollo
EIGEN_MAKE_ALIGNED_OPERATOR_NEW std::shared_ptr< base::AttributePointCloud< base::PointF > > cloud
Definition: lidar_frame.h:37
base::PointIndices secondary_indices
Definition: lidar_frame.h:57
std::vector< int > indices
Definition: point.h:75
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
base::PointIndices non_ground_indices
Definition: lidar_frame.h:55
base::PointIndices roi_indices
Definition: lidar_frame.h:53
Eigen::Affine3d novatel2world_pose
Definition: lidar_frame.h:45
Definition: point_cloud.h:37
void CopyPointCloudExclude(const PointCloud< PointT > &rhs, const std::vector< IndexType > &indices)
Definition: point_cloud.h:153
std::vector< std::shared_ptr< base::Object > > segmented_objects
Definition: lidar_frame.h:49
std::string reserve
Definition: lidar_frame.h:61
std::shared_ptr< base::AttributePointCloud< base::PointD > > world_cloud
Definition: lidar_frame.h:39
base::SensorInfo sensor_info
Definition: lidar_frame.h:59
void FilterPointCloud(base::PointCloud< base::PointF > *filtered_cloud, const std::vector< uint32_t > &indices)
Definition: lidar_frame.h:86
Definition: sensor_meta.h:57
std::vector< std::shared_ptr< base::Object > > tracked_objects
Definition: lidar_frame.h:51
Definition: lidar_frame.h:33
std::shared_ptr< base::HdmapStruct > hdmap_struct
Definition: lidar_frame.h:47
Eigen::Affine3d lidar2world_pose
Definition: lidar_frame.h:43
void Reset()
Definition: lidar_frame.h:63
Eigen::Affine3d Affine3d
Definition: base_map_fwd.h:34
double timestamp
Definition: lidar_frame.h:41