Apollo 10.0
自动驾驶开放平台
tracked_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
27
28namespace apollo {
29namespace perception {
30namespace lidar {
31
33 TrackedObject() = default;
34 TrackedObject(base::ObjectPtr obj_ptr, const Eigen::Affine3d& pose);
35 TrackedObject(const TrackedObject& rhs) = default;
36 TrackedObject& operator=(const TrackedObject& rhs) = default;
41 void Reset();
50 void Reset(
51 base::ObjectPtr obj_ptr, const Eigen::Affine3d& pose,
52 const Eigen::Vector3d& global_to_local_offset = Eigen::Vector3d::Zero(),
53 const base::SensorInfo& sensor = base::SensorInfo(),
54 double timestamp = 0.0);
55
61 std::string ToString() const;
62
68
77 void AttachObject(
78 base::ObjectPtr obj_ptr, const Eigen::Affine3d& pose,
79 const Eigen::Vector3d& global_to_local_offset = Eigen::Vector3d::Zero(),
80 const base::SensorInfo& sensor = base::SensorInfo(),
81 double timestamp = 0.0);
82
88
95 void CopyFrom(std::shared_ptr<TrackedObject> rhs, bool is_deep);
96
102 void ToObject(base::ObjectPtr obj_ptr) const;
103
110 float GetVelThreshold(base::ObjectPtr obj) const;
111 // ***************************************************
112 // self information from match
113 // ***************************************************
114 std::vector<float> shape_features;
115 std::vector<float> shape_features_full;
117 // association distance
118 // range from 0 to max_match_distance
119 float association_score = 0.0f;
120
121 // ***************************************************
122 // self information from track
123 // ***************************************************
124 bool is_fake = false;
125 int track_id = -1;
126 double tracking_time = 0.0;
127
128 // ***************************************************
129 // information from main car
130 // ***************************************************
131 Eigen::Affine3d sensor_to_local_pose;
132
133 // ***************************************************
134 // measurement correlative information from object_ptr
135 // ***************************************************
137 // corners always store follow const order based on object direction
138 Eigen::Vector3d corners[4];
139 Eigen::Vector3d center;
140 Eigen::Vector3d barycenter;
141 Eigen::Vector3d anchor_point;
142 // center and corner points in object-detection original output
143 Eigen::Vector3d detection_center;
144 Eigen::Vector3d detection_corners[4];
145
146 // oriented
147 Eigen::Vector3d direction;
148 Eigen::Vector3d lane_direction;
149 Eigen::Vector3d size;
150
152 // @brief probability for each type, required
153 std::vector<float> type_probs;
154 bool is_background = false;
155
156 double timestamp = 0.0;
157
158 // ***************************************************
159 // measurement correlative information from measurement computer
160 // ***************************************************
163 Eigen::Vector3d measured_nearest_corner_velocity; // no projection
164 Eigen::Vector3d measured_corners_velocity[4];
171
172 // ***************************************************
173 // filter correlative information
174 // ***************************************************
175 // states
177 bool valid = false;
178 bool converged = true;
180 double update_quality = 0.0;
183 Eigen::Vector3d belief_anchor_point;
184 Eigen::Vector3d belief_velocity;
185 Eigen::Vector3d belief_acceleration;
186 Eigen::Vector3d belief_velocity_gain;
187
188 // filter covariances
189 Eigen::Matrix3d velocity_covariance;
191
192 // combine velocity and acceleration
193 Eigen::Vector4d state;
194 Eigen::Matrix4d measurement_covariance;
195 Eigen::Matrix4d state_covariance;
196
197 // motion score (calculated in kalman_filter)
198 // the three scores are
199 // (smaller score means high probability of motion state):
200 // 1. average value of (variance of velocity norm / average velocity norm)
201 // 2. average value of abs(theta diff)
202 // 3. variance of score1
203 Eigen::Vector3d motion_score;
204
205 // ***************************************************
206 // postprocess correlative information
207 // ***************************************************
208 Eigen::Vector3d output_velocity;
210 Eigen::Vector3d output_direction;
211 Eigen::Vector3d output_center;
212 Eigen::Vector3d output_size;
214
215 Eigen::Vector3d global_local_offset;
216
217 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
218} EIGEN_ALIGN16; // struct TrackedObject
219
220typedef std::shared_ptr<TrackedObject> TrackedObjectPtr;
221typedef std::shared_ptr<const TrackedObject> TrackedObjectConstPtr;
222
223} // namespace lidar
224} // namespace perception
225} // namespace apollo
std::shared_ptr< Object > ObjectPtr
Definition object.h:127
std::shared_ptr< const TrackedObject > TrackedObjectConstPtr
struct apollo::perception::lidar::PCLPointXYZIT EIGEN_ALIGN16
std::shared_ptr< TrackedObject > TrackedObjectPtr
class register implement
Definition arena_queue.h:37
void AttachObject(base::ObjectPtr obj_ptr, const Eigen::Affine3d &pose, const Eigen::Vector3d &global_to_local_offset=Eigen::Vector3d::Zero(), const base::SensorInfo &sensor=base::SensorInfo(), double timestamp=0.0)
Attach object
std::string ToString() const
Transform tracked data state to string
TrackedObject(const TrackedObject &rhs)=default
Eigen::Vector3d measured_detection_history_corners_velocity[4]
float GetVelThreshold(base::ObjectPtr obj) const
Get vehicle threshold
void ToObject(base::ObjectPtr obj_ptr) const
Convert tracked object to base object
void ComputeShapeFeatures()
Compute shape features
void TransformObjectCloudToWorld()
Transform object cloud to world
void CopyFrom(std::shared_ptr< TrackedObject > rhs, bool is_deep)
Copy from tracked object
TrackedObject & operator=(const TrackedObject &rhs)=default