44 const Eigen::VectorXf& track_predict,
46 const double time_diff) {
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;
56 float location_dist =
static_cast<float>(sqrt(
57 (measure_predict_diff.head(2).cwiseProduct(measure_predict_diff.head(2)))
63 Eigen::Vector2d ref_dir = last_object->output_velocity.head(2);
64 double speed = ref_dir.norm();
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));
83 const Eigen::VectorXf& track_predict,
85 const double time_diff) {
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;
95 Eigen::Vector3f track_motion_dir = track_predict.head(6).tail(3);
96 track_motion_dir[2] = 0.0;
98 double cos_theta = 0.994;
99 if (!track_motion_dir.head(2).isZero() &&
100 !anchor_point_shift_dir.head(2).isZero()) {
103 cos_theta = algorithm::CalculateCosTheta2DXY<float>(track_motion_dir,
104 anchor_point_shift_dir);
106 float direction_dist =
static_cast<float>(-cos_theta) + 1.0f;
108 return direction_dist;
112 const Eigen::VectorXf& track_predict,
114 const double time_diff) {
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>();
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);
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);
167 const Eigen::VectorXf& track_predict,
169 const double time_diff) {
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;
178 if (old_object_shape_features.size() != new_object_shape_features.size()) {
179 AINFO <<
"sizes of compared features not matched. TrackObjectDistance";
183 float histogram_dist = 0.0f;
184 for (
size_t i = 0; i < old_object_shape_features.size(); ++i) {
186 std::fabs(old_object_shape_features[i] - new_object_shape_features[i]);
189 return histogram_dist;
203 const Eigen::VectorXf& track_predict,
205 const double time_diff,
double match_threshold) {
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;
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;
228 (new_object->object_ptr->lidar_supplement).cloud_world;
229 if (change_cur_obj_bbox) {
232 cloud, new_dir, &new_size, &new_center, minimum_edge_length);
236 cloud, old_dir, &old_size, &old_center, minimum_edge_length);
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 *
247 Eigen::Vector2d new_center_transformed_2d =
248 static_cast<Eigen::Matrix<double, 2, 1, 0, 2, 1>
>(trans_mat *
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);
259 double dist = (1 - iou) * match_threshold;
260 return static_cast<float>(dist);
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