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