Apollo 10.0
自动驾驶开放平台
object.h
浏览该文件的文档.
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
28// #include "modules/common_msgs/prediction_msgs/feature.pb.h"
29
30namespace apollo {
31namespace perception {
32namespace base {
33
34struct 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 // @brief: attention on car-front-critical objects
82 bool is_front_critical = false;
83
84 // tracking information
85 // @brief track id, required
86 int track_id = -1;
87 // @brief velocity of the object, required
88 Eigen::Vector3f velocity = Eigen::Vector3f(0, 0, 0);
89 // @brief covariance matrix of the velocity uncertainty, required
90 Eigen::Matrix3f velocity_uncertainty;
91 // @brief if the velocity estimation is converged, true by default
92 bool velocity_converged = true;
93 // @brief velocity confidence, required
94 float velocity_confidence = 1.0f;
95 // @brief acceleration of the object, required
96 Eigen::Vector3f acceleration = Eigen::Vector3f(0, 0, 0);
97 // @brief covariance matrix of the acceleration uncertainty, required
98 Eigen::Matrix3f acceleration_uncertainty;
99
100 // @brief age of the tracked object, required
101 double tracking_time = 0.0;
102 // @brief timestamp of latest measurement, required
104
105 // @brief motion state of the tracked object, required
107 // Tailgating (trajectory of objects)
108 std::array<Eigen::Vector3d, 100> drops;
109 std::size_t drop_num = 0;
110 // CIPV
111 bool b_cipv = false;
112 // @brief brake light, left-turn light and right-turn light score, optional
114 // @brief sensor-specific object supplements, optional
120
121 // @debug feature to be used for semantic mapping
122// std::shared_ptr<apollo::prediction::Feature> feature;
123
124 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
125};
126
127using ObjectPtr = std::shared_ptr<Object>;
128using ObjectConstPtr = std::shared_ptr<const Object>;
129
130} // namespace base
131} // namespace perception
132} // namespace apollo
std::shared_ptr< const Object > ObjectConstPtr
Definition object.h:128
std::shared_ptr< Object > ObjectPtr
Definition object.h:127
class register implement
Definition arena_queue.h:37
Eigen::Matrix3f velocity_uncertainty
Definition object.h:90
std::vector< float > sub_type_probs
Definition object.h:76
CameraObjectSupplement camera_supplement
Definition object.h:118
Eigen::Vector3f acceleration
Definition object.h:96
Eigen::Vector3f direction
Definition object.h:47
std::vector< float > type_probs
Definition object.h:71
PointCloud< PointD > polygon
Definition object.h:43
Eigen::Vector3f size_variance
Definition object.h:64
FusionObjectSupplement fusion_supplement
Definition object.h:119
std::array< Eigen::Vector3d, 100 > drops
Definition object.h:108
Eigen::Matrix3f acceleration_uncertainty
Definition object.h:98
RadarObjectSupplement radar_supplement
Definition object.h:117
Radar4dObjectSupplement radar4d_supplement
Definition object.h:116
LidarObjectSupplement lidar_supplement
Definition object.h:115
Eigen::Matrix3f center_uncertainty
Definition object.h:58
Eigen::Vector3d anchor_point
Definition object.h:66
std::string ToString() const
Definition object.cc:77