Apollo 10.0
自动驾驶开放平台
distance_collection.cc
浏览该文件的文档.
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 *****************************************************************************/
17
18#include <algorithm>
19#include <vector>
20
21#include "cyber/common/log.h"
26
27namespace apollo {
28namespace perception {
29namespace lidar {
30
32 const Eigen::VectorXf& track_predict,
33 const TrackedObjectConstPtr& new_object,
34 const double time_diff) {
35 Eigen::Vector3f measured_anchor = (new_object->barycenter).cast<float>();
36 Eigen::Vector3f predicted_anchor = track_predict.head(3);
37 Eigen::Vector3f measured_diff = measured_anchor - predicted_anchor;
38
39 float location_dist = measured_diff.head(2).norm();
40 return location_dist;
41}
42
43float LocationDistance(const TrackedObjectConstPtr& last_object,
44 const Eigen::VectorXf& track_predict,
45 const TrackedObjectConstPtr& new_object,
46 const double time_diff) {
47 // Compute locatin distance for last object and new object
48 // range from 0 to positive infinity
49
50 Eigen::Vector3f measured_anchor_point =
51 (new_object->anchor_point).cast<float>();
52 Eigen::Vector3f predicted_anchor_point = track_predict.head(3);
53 Eigen::Vector3f measure_predict_diff =
54 measured_anchor_point - predicted_anchor_point;
55
56 float location_dist = static_cast<float>(sqrt(
57 (measure_predict_diff.head(2).cwiseProduct(measure_predict_diff.head(2)))
58 .sum()));
59
60 /* NEED TO NOTICE: All the states would be collected mainly based on
61 * states of tracked objects. Thus, update tracked object when you
62 * update the state of track !!!!! */
63 Eigen::Vector2d ref_dir = last_object->output_velocity.head(2);
64 double speed = ref_dir.norm();
65 ref_dir /= speed;
66
67 /* Let location distance generated from a normal distribution with
68 * symmetric variance. Modify its variance when speed greater than
69 * a threshold. Penalize variance other than motion direction. */
70 if (speed > 2) {
71 Eigen::Vector2d ref_o_dir = Eigen::Vector2d(ref_dir[1], -ref_dir[0]);
72 double dx = ref_dir(0) * measure_predict_diff(0) +
73 ref_dir(1) * measure_predict_diff(1);
74 double dy = ref_o_dir(0) * measure_predict_diff(0) +
75 ref_o_dir(1) * measure_predict_diff(1);
76 location_dist = static_cast<float>(sqrt(dx * dx * 0.5 + dy * dy * 2));
77 }
78
79 return location_dist;
80}
81
83 const Eigen::VectorXf& track_predict,
84 const TrackedObjectConstPtr& new_object,
85 const double time_diff) {
86 // Compute direction distance for last object and new object
87 // range from 0 to 2
88
89 Eigen::Vector3f old_anchor_point =
90 (last_object->belief_anchor_point).cast<float>();
91 Eigen::Vector3f new_anchor_point = (new_object->anchor_point).cast<float>();
92 Eigen::Vector3f anchor_point_shift_dir = new_anchor_point - old_anchor_point;
93 anchor_point_shift_dir[2] = 0.0;
94
95 Eigen::Vector3f track_motion_dir = track_predict.head(6).tail(3);
96 track_motion_dir[2] = 0.0;
97
98 double cos_theta = 0.994; // average cos
99 if (!track_motion_dir.head(2).isZero() &&
100 !anchor_point_shift_dir.head(2).isZero()) {
101 // cos_theta = vector_cos_theta_2d_xy(track_motion_dir,
102 // anchor_point_shift_dir);
103 cos_theta = algorithm::CalculateCosTheta2DXY<float>(track_motion_dir,
104 anchor_point_shift_dir);
105 }
106 float direction_dist = static_cast<float>(-cos_theta) + 1.0f;
107
108 return direction_dist;
109}
110
112 const Eigen::VectorXf& track_predict,
113 const TrackedObjectConstPtr& new_object,
114 const double time_diff) {
115 // Compute bbox size distance for last object and new object
116 // range from 0 to 1
117
118 Eigen::Vector3f old_bbox_dir = last_object->output_direction.cast<float>();
119 Eigen::Vector3f new_bbox_dir = new_object->direction.cast<float>();
120 Eigen::Vector3f old_bbox_size = last_object->output_size.cast<float>();
121 Eigen::Vector3f new_bbox_size = new_object->size.cast<float>();
122
123 float size_dist = 0.0f;
124 double dot_val_00 = fabs(old_bbox_dir(0) * new_bbox_dir(0) +
125 old_bbox_dir(1) * new_bbox_dir(1));
126 double dot_val_01 = fabs(old_bbox_dir(0) * new_bbox_dir(1) -
127 old_bbox_dir(1) * new_bbox_dir(0));
128 float temp_val_0 = 0.0f;
129 float temp_val_1 = 0.0f;
130 if (dot_val_00 > dot_val_01) {
131 temp_val_0 = static_cast<float>(fabs(old_bbox_size(0) - new_bbox_size(0))) /
132 std::max(old_bbox_size(0), new_bbox_size(0));
133 temp_val_1 = static_cast<float>(fabs(old_bbox_size(1) - new_bbox_size(1))) /
134 std::max(old_bbox_size(1), new_bbox_size(1));
135 size_dist = std::min(temp_val_0, temp_val_1);
136 } else {
137 temp_val_0 = static_cast<float>(fabs(old_bbox_size(0) - new_bbox_size(1))) /
138 std::max(old_bbox_size(0), new_bbox_size(1));
139 temp_val_1 = static_cast<float>(fabs(old_bbox_size(1) - new_bbox_size(0))) /
140 std::max(old_bbox_size(1), new_bbox_size(0));
141 size_dist = std::min(temp_val_0, temp_val_1);
142 }
143
144 return size_dist;
145}
146
148 const Eigen::VectorXf& track_predict,
149 const TrackedObjectConstPtr& new_object,
150 const double time_diff) {
151 // Compute point num distance for last object and new object
152 // range from 0 and 1
153
154 int old_point_number = static_cast<int>(
155 (last_object->object_ptr->lidar_supplement).cloud_world.size());
156 int new_point_number = static_cast<int>(
157 (new_object->object_ptr->lidar_supplement).cloud_world.size());
158
159 float point_num_dist =
160 static_cast<float>(fabs(old_point_number - new_point_number)) * 1.0f /
161 static_cast<float>(std::max(old_point_number, new_point_number));
162
163 return point_num_dist;
164}
165
167 const Eigen::VectorXf& track_predict,
168 const TrackedObjectConstPtr& new_object,
169 const double time_diff) {
170 // Compute histogram distance for last object and new object
171 // range from 0 to 3
172
173 const std::vector<float>& old_object_shape_features =
174 last_object->shape_features;
175 const std::vector<float>& new_object_shape_features =
176 new_object->shape_features;
177
178 if (old_object_shape_features.size() != new_object_shape_features.size()) {
179 AINFO << "sizes of compared features not matched. TrackObjectDistance";
180 return 100;
181 }
182
183 float histogram_dist = 0.0f;
184 for (size_t i = 0; i < old_object_shape_features.size(); ++i) {
185 histogram_dist +=
186 std::fabs(old_object_shape_features[i] - new_object_shape_features[i]);
187 }
188
189 return histogram_dist;
190}
191
193 const Eigen::VectorXf& track_predict,
194 const TrackedObjectConstPtr& new_object,
195 const double time_diff) {
196 float dist = static_cast<float>(
197 (last_object->barycenter.head(2) - new_object->barycenter.head(2))
198 .norm());
199 return dist;
200}
201
202float BboxIouDistance(const TrackedObjectConstPtr& last_object,
203 const Eigen::VectorXf& track_predict,
204 const TrackedObjectConstPtr& new_object,
205 const double time_diff, double match_threshold) {
206 // Step 1: unify bbox direction, change the one with less pts,
207 // for efficiency.
208 Eigen::Vector3f old_dir = last_object->output_direction.cast<float>();
209 Eigen::Vector3f old_size = last_object->output_size.cast<float>();
210 Eigen::Vector3d old_center = last_object->output_center;
211 Eigen::Vector3f new_dir = new_object->direction.cast<float>();
212 Eigen::Vector3f new_size = new_object->size.cast<float>();
213 Eigen::Vector3d new_center = new_object->center;
214 old_dir.normalize();
215 new_dir.normalize();
216 // handle randomness
217 old_size(0) = old_size(0) > 0.3f ? old_size(0) : 0.3f;
218 old_size(1) = old_size(1) > 0.3f ? old_size(1) : 0.3f;
219 new_size(0) = new_size(0) > 0.3f ? new_size(0) : 0.3f;
220 new_size(1) = new_size(1) > 0.3f ? new_size(1) : 0.3f;
221 int last_object_num_pts = static_cast<int>(
222 (last_object->object_ptr->lidar_supplement).cloud_world.size());
223 int cur_obj_num_pts = static_cast<int>(
224 (new_object->object_ptr->lidar_supplement).cloud_world.size());
225 bool change_cur_obj_bbox = last_object_num_pts > cur_obj_num_pts;
226 float minimum_edge_length = 0.01f;
227 base::PointDCloud& cloud =
228 (new_object->object_ptr->lidar_supplement).cloud_world;
229 if (change_cur_obj_bbox) {
230 new_dir = old_dir;
232 cloud, new_dir, &new_size, &new_center, minimum_edge_length);
233 } else {
234 old_dir = new_dir;
236 cloud, old_dir, &old_size, &old_center, minimum_edge_length);
237 }
238 // Step 2: compute 2d iou bbox to bbox
239 Eigen::Matrix2d trans_mat;
240 trans_mat(0, 0) = (old_dir.cast<double>())(0);
241 trans_mat(0, 1) = (old_dir.cast<double>())(1);
242 trans_mat(1, 0) = -(old_dir.cast<double>())(1);
243 trans_mat(1, 1) = (old_dir.cast<double>())(0);
244 Eigen::Vector2d old_center_transformed_2d =
245 static_cast<Eigen::Matrix<double, 2, 1, 0, 2, 1>>(trans_mat *
246 old_center.head(2));
247 Eigen::Vector2d new_center_transformed_2d =
248 static_cast<Eigen::Matrix<double, 2, 1, 0, 2, 1>>(trans_mat *
249 new_center.head(2));
250 old_center(0) = old_center_transformed_2d(0);
251 old_center(1) = old_center_transformed_2d(1);
252 new_center(0) = new_center_transformed_2d(0);
253 new_center(1) = new_center_transformed_2d(1);
254 Eigen::Vector3d old_size_tmp = old_size.cast<double>();
255 Eigen::Vector3d new_size_tmp = new_size.cast<double>();
256 double iou = algorithm::CalculateIou2DXY<double>(old_center, old_size_tmp,
257 new_center, new_size_tmp);
258 // Step 4: compute dist
259 double dist = (1 - iou) * match_threshold;
260 return static_cast<float>(dist);
261}
262
263} // namespace lidar
264} // namespace perception
265} // namespace apollo
Define the LineSegment2d class.
#define AINFO
Definition log.h:42
void CalculateBBoxSizeCenter2DXY(const PointCloudT &cloud, const Eigen::Vector3f &dir, Eigen::Vector3f *size, Eigen::Vector3d *center, float minimum_edge_length=std::numeric_limits< float >::epsilon())
Definition common.h:112
std::shared_ptr< const TrackedObject > TrackedObjectConstPtr
float CentroidShiftDistance(const TrackedObjectConstPtr &last_object, const Eigen::VectorXf &track_predict, const TrackedObjectConstPtr &new_object, const double time_diff)
Compute centroid shift distance for object and background match
float HistogramDistance(const TrackedObjectConstPtr &last_object, const Eigen::VectorXf &track_predict, const TrackedObjectConstPtr &new_object, const double time_diff)
Compute histogram distance for given track & object
float BboxIouDistance(const TrackedObjectConstPtr &last_object, const Eigen::VectorXf &track_predict, const TrackedObjectConstPtr &new_object, const double time_diff, double match_threshold)
Compute bbox iou distance for object and background match
float LocationDistance(const TrackedObjectConstPtr &last_object, const Eigen::VectorXf &track_predict, const TrackedObjectConstPtr &new_object, const double time_diff)
Compute location distance for given track & object
float BboxSizeDistance(const TrackedObjectConstPtr &last_object, const Eigen::VectorXf &track_predict, const TrackedObjectConstPtr &new_object, const double time_diff)
Compute bbox size distance for given track & object
float EuclideanDistance(const TrackedObjectConstPtr &last_object, const Eigen::VectorXf &track_predict, const TrackedObjectConstPtr &new_object, const double time_diff)
: compute euclidean distance for given track & object
float PointNumDistance(const TrackedObjectConstPtr &last_object, const Eigen::VectorXf &track_predict, const TrackedObjectConstPtr &new_object, const double time_diff)
Compute point num distance for given track & object
float DirectionDistance(const TrackedObjectConstPtr &last_object, const Eigen::VectorXf &track_predict, const TrackedObjectConstPtr &new_object, const double time_diff)
Compute direction distance for given track & object
class register implement
Definition arena_queue.h:37
Defines the Vec2d class.