Apollo 11.0
自动驾驶开放平台
tracked_object.cc
浏览该文件的文档.
1/******************************************************************************
2 * Copyright 2023 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 *****************************************************************************/
17
18#include "cyber/common/log.h"
24
25namespace apollo {
26namespace perception {
27namespace radar4d {
28
29using RadarPointFCloud =
31
33 const Eigen::Affine3d& pose) {
34 AttachObject(obj_ptr, pose);
35}
36
38 const Eigen::Affine3d& pose,
39 const Eigen::Vector3d& global_to_local_offset,
40 const base::SensorInfo& sensor) {
41 if (obj_ptr) {
42 // all state of input obj_ptr will not change except cloud world
43 object_ptr = obj_ptr;
44
46 global_local_offset = global_to_local_offset;
47 // object info to tracked object
48 center = pose * object_ptr->center;
49 const RadarPointFCloud& cloud = (object_ptr->radar4d_supplement).cloud;
50 barycenter = (algorithm::CalculateRadarCentroid(cloud)).cast<double>();
51 barycenter = pose * barycenter;
53
54 Eigen::Matrix3d rotation = pose.rotation();
55 direction = rotation * object_ptr->direction.cast<double>();
57 size = object_ptr->size.cast<double>();
58 type = object_ptr->type;
59 is_background = object_ptr->radar4d_supplement.is_background;
60
61 base::RadarPointDCloud& cloud_world =
62 (object_ptr->radar4d_supplement).cloud_world;
63 cloud_world.clear();
64 cloud_world.resize(cloud.size());
65 for (size_t i = 0; i < cloud.size(); ++i) {
66 Eigen::Vector3d pt(cloud[i].x, cloud[i].y, cloud[i].z);
67 Eigen::Vector3d pt_world = pose * pt;
68 cloud_world[i].x = pt_world(0);
69 cloud_world[i].y = pt_world(1);
70 cloud_world[i].z = pt_world(2);
71 cloud_world[i].rcs = cloud[i].rcs;
72 cloud_world[i].velocity = cloud[i].velocity;
73 cloud_world[i].comp_vel = cloud[i].comp_vel;
74 }
75 // other belief information keep as Reset()
76 selected_measured_velocity = Eigen::Vector3d::Zero();
77 selected_measured_acceleration = Eigen::Vector3d::Zero();
79 belief_velocity = Eigen::Vector3d::Zero();
80 belief_acceleration = Eigen::Vector3d::Zero();
81
82 output_velocity = Eigen::Vector3d::Zero();
83 output_velocity_uncertainty = Eigen::Matrix3d::Zero();
87
88 sensor_info = sensor;
89 }
90}
91
93 const base::RadarPointFCloud& cloud =
94 (object_ptr->radar4d_supplement).cloud;
95 base::RadarPointDCloud& cloud_world =
96 (object_ptr->radar4d_supplement).cloud_world;
97 cloud_world.clear();
98 cloud_world.resize(cloud.size());
99 for (size_t i = 0; i < cloud.size(); ++i) {
100 Eigen::Vector3d pt(cloud[i].x, cloud[i].y, cloud[i].z);
101 Eigen::Vector3d pt_world = sensor_to_local_pose * pt;
102 cloud_world[i].x = pt_world(0);
103 cloud_world[i].y = pt_world(1);
104 cloud_world[i].z = pt_world(2);
105 cloud_world[i].rcs = cloud[i].rcs;
106 cloud_world[i].velocity = cloud[i].velocity;
107 cloud_world[i].comp_vel = cloud[i].comp_vel;
108 }
109}
110
112 object_ptr.reset();
113 sensor_to_local_pose = Eigen::Affine3d::Identity();
114
115 // measurement reset
116 for (int i = 0; i < 4; ++i) {
117 corners[i] = Eigen::Vector3d::Zero();
118 measured_corners_velocity[i] = Eigen::Vector3d::Zero();
119 }
120 center = Eigen::Vector3d::Zero();
121 barycenter = Eigen::Vector3d::Zero();
122 anchor_point = Eigen::Vector3d::Zero();
123 measured_barycenter_velocity = Eigen::Vector3d::Zero();
124 measured_center_velocity = Eigen::Vector3d::Zero();
125 measured_nearest_corner_velocity = Eigen::Vector3d::Zero();
126 direction = Eigen::Vector3d::Zero();
127 lane_direction = Eigen::Vector3d::Zero();
128 size = Eigen::Vector3d::Zero();
130 is_background = false;
131 shape_features.clear();
132 shape_features_full.clear();
134 association_score = 0.0;
135 is_fake = false;
136 track_id = -1;
137 tracking_time = 0.0;
138
139 // filter reset
141 valid = false;
142 converged = true;
144 update_quality = 0.0;
146 selected_measured_acceleration = Eigen::Vector3d::Zero();
150 belief_velocity_gain = Eigen::Vector3d::Zero();
151 velocity_covariance = Eigen::Matrix3d::Zero();
152 belief_velocity_online_covariance = Eigen::Matrix3d::Zero();
153
154 state = Eigen::Vector4d::Zero();
155 measurement_covariance = Eigen::Matrix4d::Zero();
156 state_covariance = Eigen::Matrix4d::Zero();
157
158 motion_score = Eigen::Vector3d(1, 1, 1);
159
160 // output reset
166
167 // sensor info reset
169}
170
171void TrackedObject::Reset(base::ObjectPtr obj_ptr, const Eigen::Affine3d& pose,
172 const Eigen::Vector3d& global_to_local_offset,
173 const base::SensorInfo& sensor) {
174 Reset();
175 AttachObject(obj_ptr, pose, global_to_local_offset, sensor);
176}
177
178void TrackedObject::CopyFrom(TrackedObjectPtr rhs, bool is_deep) {
179 *this = *rhs;
180 if (is_deep) {
181 object_ptr = base::ObjectPool::Instance().Get();
182 *object_ptr = *(rhs->object_ptr);
183 } else {
184 object_ptr = rhs->object_ptr;
185 }
186}
187
189 if (obj->type == base::ObjectType::VEHICLE) {
190 return 0.99f;
191 }
192 return 0.0f;
193}
194
196 *obj = *object_ptr;
197 // obj id keep default
198 // obj polygon calculate outside, because
199 /* 1. if ConvexHull2D as member variable:
200 constructor time consume a little large
201 2. if ConvexHull2D as static or global variable:
202 need mutex time consume in multi threads
203 what a pity!
204 */
205 obj->direction = output_direction.cast<float>();
206 // obj theta_variance not calculate in tracker, keep default
207 obj->center = output_center;
208 // obj center_uncertainty not calculate in tracker, keep default
209 obj->size = output_size.cast<float>();
210 // obj size_varuance not calculate in tracker, keep default
211 obj->anchor_point = belief_anchor_point;
212 obj->type = type;
213 // obj type_probs not calculate in tracker, keep default
214 // obj confidence not calculate in tracker, keep default
215 obj->track_id = track_id;
216 obj->velocity = output_velocity.cast<float>();
217 obj->velocity_uncertainty = output_velocity_uncertainty.cast<float>();
218 obj->velocity_converged = converged;
219 obj->tracking_time = tracking_time;
220 if (obj->velocity.norm() > GetVelThreshold(obj)) {
221 obj->theta = std::atan2(obj->velocity[1], obj->velocity[0]);
222 } else {
223 obj->theta = std::atan2(obj->direction[1], obj->direction[0]);
224 }
225 // obj latest_tracked_time not calculate in tracker, keep default
226 // obj car_light not calculate in tracker, keep default
227 // obj radar4d_supplement cloud_world has passed in *obj = *object_ptr
228 // obj radar4d_supplement other elements not calculate in tracker,
229 // keep default
230 // obj radar_supplement not calculate in tracker, keep default
231 // obj camera_supplement not calculate in tracker, keep default
232}
233
234std::string TrackedObject::ToString() const {
235 // std::string txt;
236 // return txt;
237 std::ostringstream oos;
238 oos << "obj id: " << object_ptr->id << ", track_id: " << object_ptr->track_id
239 << ", bary_center: (" << barycenter[0] << "," << barycenter[1] << ","
240 << barycenter[2] << ")"
241 << ", lane_direction: (" << lane_direction[0] << "," << lane_direction[1]
242 << "," << lane_direction[2] << ")";
243 return oos.str();
244}
245
247 // Compute object's shape feature
248 // 1. check whether shape feature is ready
249 // 2. compute object's shape feature
251 FeatureDescriptor fd(&(object_ptr->radar4d_supplement.cloud));
252 fd.ComputeHistogram(static_cast<int>(histogram_bin_size),
253 shape_features_full.data());
254
255 size_t feature_len = histogram_bin_size * 3;
256 shape_features.clear();
257 shape_features.resize(feature_len);
258 for (size_t i = 0; i < feature_len; ++i) {
260 }
261}
262} // namespace radar4d
263} // namespace perception
264} // namespace apollo
void ComputeHistogram(int bin_size, float *feature)
Eigen::Matrix< T, 3, 1 > CalculateRadarCentroid(const base::AttributeRadarPointCloud< base::RadarPoint< T > > &cloud)
Definition common.h:152
AttributeRadarPointCloud< RadarPointF > RadarPointFCloud
AttributeRadarPointCloud< RadarPointD > RadarPointDCloud
std::shared_ptr< Object > ObjectPtr
Definition object.h:127
apollo::perception::base::RadarPointCloud< RadarPointF > RadarPointFCloud
std::shared_ptr< TrackedObject > TrackedObjectPtr
class register implement
Definition arena_queue.h:37
float GetVelThreshold(base::ObjectPtr obj) const
Get vehicle threshold
void ToObject(base::ObjectPtr obj_ptr) const
Convert tracked object to base object
void TransformObjectCloudToWorld()
Transform object cloud to world
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())
Attach object
void CopyFrom(std::shared_ptr< TrackedObject > rhs, bool is_deep)
Copy from tracked object
void ComputeShapeFeatures()
Compute shape features
std::string ToString() const
Transform tracked data state to string