Apollo  6.0
Open source self driving car software
object.h
Go to the documentation of this file.
1 /******************************************************************************
2  * Copyright 2019 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/Core"
23 
26 
27 namespace apollo {
28 namespace perception {
29 namespace benchmark {
30 
31 enum ObjectType {
32  UNKNOWN = 0,
36  BICYCLE = 4,
37  VEHICLE = 5,
39 };
40 
41 ObjectType translate_string_to_type(const std::string& str);
42 
43 unsigned int translate_type_to_index(const ObjectType& type);
44 
45 std::string translate_type_index_to_string(unsigned int index);
46 
47 std::string translate_type_to_string(ObjectType type);
48 
57 };
58 
59 enum SensorType {
62  RADAR = 2,
63  CAMERA = 3,
65 };
66 
67 SensorType translate_string_to_sensor_type(const std::string& str);
68 
69 std::string translate_sensor_type_to_string(const SensorType& type);
70 
71 struct alignas(16) Object {
72  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
73 
74  Object();
75  // shallow copy for copy constructor and assignment
76  Object(const Object& rhs);
77  Object& operator=(const Object& rhs);
78  // deep copy
79  void clone(const Object& rhs);
80  std::string to_string() const;
81 
82  // object id per frame
83  int id = 0;
84  // point cloud of the object
86  // point cloud indices of the object
88  // polygon of the object
90  // confidence of the object
91  float confidence = 1.f;
92 
93  // oriented boundingbox information
94  // main direction
96  // the yaw angle, direction with x-axis (1, 0, 0)
97  double yaw = 0.0;
98  // the roll angle, direction with
99  double roll = 0.0;
100  // the pitch angle, direction with
101  double pitch = 0.0;
102  // ground center of the object (cx, cy, z_min)
104  // size of the oriented bbox, length is the size in the main direction
105  double length = 0.0;
106  double width = 0.0;
107  double height = 0.0;
108  // truncated
109  double truncated = 0.0;
110  double occluded = 0.0;
111 
112  // Object classification type.
114  // Probability of each type, used for track type.
115  std::vector<float> type_probs;
116 
117  // Internal object classification type.
119  // Internal probability of each type, used for track type.
120  std::vector<float> internal_type_probs;
121 
122  // fg/bg flag
123  bool is_background = false;
124 
125  // tracking information
126  int track_id = 0;
127 
129  // age of the tracked object
130  double tracking_time = 0.0;
131  double latest_tracked_time = 0.0;
132 
133  // roi flag
134  bool is_in_roi = false;
135 
136  // lane flag
137  bool is_in_main_lanes = false;
138 
139  // visible related
140  float visible_ratio = 1.f;
141  bool visible = true;
142 
143  // sensor type
145 
146  // reserve
147  std::string reserve;
148 
149  // sensor particular suplplements, default nullptr
153 
154  // jaccard index with ground truth when benchmark evaluation
155  double ji = 0.0;
156 };
157 
158 typedef std::shared_ptr<Object> ObjectPtr;
159 typedef std::shared_ptr<const Object> ObjectConstPtr;
160 
161 using SeqId = uint32_t;
162 
163 // Sensor single frame objects.
165  SensorObjects() { sensor2world_pose = Eigen::Matrix4d::Zero(); }
166 
167  std::string to_string() const;
168 
170  std::string name;
171  double timestamp = 0.0;
172  SeqId seq_num = 0;
173  std::vector<ObjectPtr> objects;
174  std::vector<std::vector<Eigen::Vector3d>> objects_box_vertices;
175  std::vector<ObjectPtr> gt_objects;
176  std::vector<std::vector<Eigen::Vector3d>> gt_objects_box_vertices;
178 };
179 
180 } // namespace benchmark
181 } // namespace perception
182 } // namespace apollo
double height
Definition: object.h:107
int track_id
Definition: object.h:126
InternalObjectType internal_type
Definition: object.h:118
std::string translate_sensor_type_to_string(const SensorType &type)
SensorType
Definition: object.h:59
double truncated
Definition: object.h:109
std::shared_ptr< RadarSupplement > RadarSupplementPtr
Definition: object_supplement.h:52
float visible_ratio
Definition: object.h:140
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
PointCloud polygon
Definition: object.h:89
ObjectType type
Definition: object.h:113
double width
Definition: object.h:106
InternalObjectType
Definition: object.h:49
Object & operator=(const Object &rhs)
double pitch
Definition: object.h:101
std::shared_ptr< CameraSupplement > CameraSupplementPtr
Definition: object_supplement.h:68
Definition: pointcloud.h:26
double length
Definition: object.h:105
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Object()
Eigen::Vector3d velocity
Definition: object.h:128
ObjectType
Definition: object.h:31
std::vector< std::vector< Eigen::Vector3d > > objects_box_vertices
Definition: object.h:174
Eigen::Vector3d Vector3d
Definition: frame_transform.h:27
Eigen::Matrix4d Matrix4d
Definition: base_map_fwd.h:32
SensorType translate_string_to_sensor_type(const std::string &str)
pcl::PointCloud< Point >::Ptr PointCloudPtr
Definition: types.h:65
std::vector< ObjectPtr > objects
Definition: object.h:173
CameraSupplementPtr camera_supplement
Definition: object.h:152
std::shared_ptr< Object > ObjectPtr
Definition: object.h:158
float confidence
Definition: object.h:91
ObjectType translate_string_to_type(const std::string &str)
std::string reserve
Definition: object.h:147
PointCloudPtr cloud
Definition: object.h:85
Eigen::Vector3d direction
Definition: object.h:95
std::string translate_type_to_string(ObjectType type)
unsigned int translate_type_to_index(const ObjectType &type)
std::string translate_type_index_to_string(unsigned int index)
::pcl::PointIndices::Ptr PointIndicesPtr
Definition: types.h:30
bool is_background
Definition: object.h:123
double tracking_time
Definition: object.h:130
LidarSupplementPtr lidar_supplement
Definition: object.h:150
uint32_t SeqId
Definition: object.h:161
PointIndicesPtr indices
Definition: object.h:87
bool visible
Definition: object.h:141
SensorType sensor_type
Definition: object.h:144
std::vector< float > internal_type_probs
Definition: object.h:120
double yaw
Definition: object.h:97
std::shared_ptr< LidarSupplement > LidarSupplementPtr
Definition: object_supplement.h:34
std::vector< std::vector< Eigen::Vector3d > > gt_objects_box_vertices
Definition: object.h:176
double latest_tracked_time
Definition: object.h:131
std::string name
Definition: object.h:170
bool is_in_roi
Definition: object.h:134
std::vector< ObjectPtr > gt_objects
Definition: object.h:175
std::shared_ptr< const Object > ObjectConstPtr
Definition: object.h:159
Eigen::Matrix4d sensor2world_pose
Definition: object.h:177
double occluded
Definition: object.h:110
RadarSupplementPtr radar_supplement
Definition: object.h:151
double ji
Definition: object.h:155
std::vector< float > type_probs
Definition: object.h:115
bool is_in_main_lanes
Definition: object.h:137
double roll
Definition: object.h:99
Eigen::Vector3d center
Definition: object.h:103