Apollo  v5.5.0
Open source self driving car software
object.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/Core"
23 #include "boost/circular_buffer.hpp"
24 
29 
30 namespace apollo {
31 namespace perception {
32 namespace base {
33 
34 struct alignas(16) Object {
35  Object();
36  std::string ToString() const;
37  void Reset();
38 
39  // @brief object id per frame, required
40  int id = -1;
41 
42  // @brief convex hull of the object, required
44 
45  // oriented boundingbox information
46  // @brief main direction of the object, required
47  Eigen::Vector3f direction = Eigen::Vector3f(1, 0, 0);
48  /*@brief the yaw angle, theta = 0.0 <=> direction(1, 0, 0),
49  currently roll and pitch are not considered,
50  make sure direction and theta are consistent, required
51  */
52  float theta = 0.0f;
53  // @brief theta variance, required
54  float theta_variance = 0.0f;
55  // @brief center of the boundingbox (cx, cy, cz), required
56  Eigen::Vector3d center = Eigen::Vector3d(0, 0, 0);
57  // @brief covariance matrix of the center uncertainty, required
58  Eigen::Matrix3f center_uncertainty;
59  /* @brief size = [length, width, height] of boundingbox
60  length is the size of the main direction, required
61  */
62  Eigen::Vector3f size = Eigen::Vector3f(0, 0, 0);
63  // @brief size variance, required
64  Eigen::Vector3f size_variance = Eigen::Vector3f(0, 0, 0);
65  // @brief anchor point, required
66  Eigen::Vector3d anchor_point = Eigen::Vector3d(0, 0, 0);
67 
68  // @brief object type, required
70  // @brief probability for each type, required
71  std::vector<float> type_probs;
72 
73  // @brief object sub-type, optional
75  // @brief probability for each sub-type, optional
76  std::vector<float> sub_type_probs;
77 
78  // @brief existence confidence, required
79  float confidence = 1.0f;
80 
81  // tracking information
82  // @brief track id, required
83  int track_id = -1;
84  // @brief velocity of the object, required
85  Eigen::Vector3f velocity = Eigen::Vector3f(0, 0, 0);
86  // @brief covariance matrix of the velocity uncertainty, required
87  Eigen::Matrix3f velocity_uncertainty;
88  // @brief if the velocity estimation is converged, true by default
89  bool velocity_converged = true;
90  // @brief velocity confidence, required
91  float velocity_confidence = 1.0f;
92  // @brief acceleration of the object, required
93  Eigen::Vector3f acceleration = Eigen::Vector3f(0, 0, 0);
94  // @brief covariance matrix of the acceleration uncertainty, required
95  Eigen::Matrix3f acceleration_uncertainty;
96 
97  // @brief age of the tracked object, required
98  double tracking_time = 0.0;
99  // @brief timestamp of latest measurement, required
100  double latest_tracked_time = 0.0;
101 
102  // @brief motion state of the tracked object, required
104  // // Tailgating (trajectory of objects)
105  std::array<Eigen::Vector3d, 100> drops;
106  std::size_t drop_num = 0;
107  // // CIPV
108  bool b_cipv = false;
109  // @brief brake light, left-turn light and right-turn light score, optional
111  // @brief sensor-specific object supplements, optional
116 };
117 
118 using ObjectPtr = std::shared_ptr<Object>;
119 using ObjectConstPtr = std::shared_ptr<const Object>;
120 
121 } // namespace base
122 } // namespace perception
123 } // namespace apollo
std::array< Eigen::Vector3d, 100 > drops
Definition: object.h:105
RadarObjectSupplement radar_supplement
Definition: object.h:113
std::size_t drop_num
Definition: object.h:106
MotionState
Definition: object_types.h:80
LidarObjectSupplement lidar_supplement
Definition: object.h:112
FusionObjectSupplement fusion_supplement
Definition: object.h:115
std::string ToString() const
Definition: blob.h:72
std::vector< float > sub_type_probs
Definition: object.h:76
Definition: object_supplement.h:245
Eigen::Matrix3f acceleration_uncertainty
Definition: object.h:95
bool b_cipv
Definition: object.h:108
Eigen::Vector3f size_variance
Definition: object.h:64
double tracking_time
Definition: object.h:98
ObjectSubType sub_type
Definition: object.h:74
Eigen::Matrix3f velocity_uncertainty
Definition: object.h:87
float theta
Definition: object.h:52
std::vector< float > type_probs
Definition: object.h:71
double latest_tracked_time
Definition: object.h:100
PointCloud< PointD > polygon
Definition: object.h:43
Definition: object_supplement.h:32
int track_id
Definition: object.h:83
Definition: point_cloud.h:33
Eigen::Vector3f velocity
Definition: object.h:85
Definition: vehicle_struct.h:22
float velocity_confidence
Definition: object.h:91
CarLight car_light
Definition: object.h:110
Definition: object.h:34
Eigen::Vector3f size
Definition: object.h:62
ObjectType type
Definition: object.h:69
Eigen::Matrix3f center_uncertainty
Definition: object.h:58
Eigen::Vector3d center
Definition: object.h:56
Definition: object_supplement.h:76
CameraObjectSupplement camera_supplement
Definition: object.h:114
MotionState motion_state
Definition: object.h:103
std::shared_ptr< const Object > ObjectConstPtr
Definition: object.h:119
Eigen::Vector3f acceleration
Definition: object.h:93
Definition: object_supplement.h:102
Eigen::Vector3d anchor_point
Definition: object.h:66
float confidence
Definition: object.h:79
ObjectType
Definition: object_types.h:26
float theta_variance
Definition: object.h:54
Eigen::Vector3f direction
Definition: object.h:47
ObjectSubType
Definition: object_types.h:63
bool velocity_converged
Definition: object.h:89
std::shared_ptr< Object > ObjectPtr
Definition: object.h:118