Apollo 10.0
自动驾驶开放平台
mrf_track_object_distance.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 *****************************************************************************/
16
18
19#include "cyber/common/file.h"
21#include "modules/perception/radar4d_detection/lib/tracker/multi_radar_fusion/proto/mrf_config.pb.h"
22
23namespace apollo {
24namespace perception {
25namespace radar4d {
26
27// location dist weight, irection dist weight, bbox size dist weight,
28// point num dist weight, histogram dist weight, centroid shift dist weight
29// bbox iou dist weight, semantic map dist weight
30const std::vector<float> MrfTrackObjectDistance::kForegroundDefaultWeight = {
31 1.f, 0.f, 0.f, 0.f, 0.f, 0.f, 0.f, 0.f};
32// location dist weight, irection dist weight, bbox size dist weight,
33// point num dist weight, histogram dist weight, centroid shift dist weight
34// bbox iou dist weight
35const std::vector<float> MrfTrackObjectDistance::kBackgroundDefaultWeight = {
36 0.f, 0.f, 0.f, 0.f, 0.f, 0.2f, 0.8f};
37
39 const MrfTrackObjectDistanceInitOptions& options) {
40 std::string config_file = "mrf_track_object_distance.pb.txt";
41 if (!options.config_file.empty()) {
42 config_file = options.config_file;
43 }
44 config_file = GetConfigFile(options.config_path, config_file);
45 MrfDistanceConfig config;
46 ACHECK(cyber::common::GetProtoFromFile(config_file, &config));
47
50 for (int i = 0; i < config.foreground_weights_size(); ++i) {
51 const auto& fgws = config.foreground_weights(i);
52 const std::string& name = fgws.sensor_name_pair();
53 std::vector<float> weights(7, 0.f);
54 weights[0] = fgws.location_dist_weight();
55 weights[1] = fgws.direction_dist_weight();
56 weights[2] = fgws.bbox_size_dist_weight();
57 weights[3] = fgws.point_num_dist_weight();
58 weights[4] = fgws.histogram_dist_weight();
59 weights[5] = fgws.centroid_shift_dist_weight();
60 weights[6] = fgws.bbox_iou_dist_weight();
61 weights[7] = fgws.semantic_map_dist_weight();
62 foreground_weight_table_.emplace(name, weights);
63 }
64 for (int i = 0; i < config.background_weights_size(); ++i) {
65 const auto& bgws = config.background_weights(i);
66 const std::string& name = bgws.sensor_name_pair();
67 std::vector<float> weights(7, 0.f);
68 weights[0] = bgws.location_dist_weight();
69 weights[1] = bgws.direction_dist_weight();
70 weights[2] = bgws.bbox_size_dist_weight();
71 weights[3] = bgws.point_num_dist_weight();
72 weights[4] = bgws.histogram_dist_weight();
73 weights[5] = bgws.centroid_shift_dist_weight();
74 weights[6] = bgws.bbox_iou_dist_weight();
75 background_weight_table_.emplace(name, weights);
76 }
77
78 return true;
79}
80
82 const TrackedObjectConstPtr& object,
83 const MrfTrackDataConstPtr& track) const {
84 bool is_background = object->is_background;
85 const TrackedObjectConstPtr latest_object = track->GetLatestObject().second;
86 std::string key = latest_object->sensor_info.name + object->sensor_info.name;
87 const std::vector<float>* weights = nullptr;
88 if (is_background) {
89 auto iter = background_weight_table_.find(key);
90 if (iter == background_weight_table_.end()) {
91 weights = &kBackgroundDefaultWeight;
92 } else {
93 weights = &iter->second;
94 }
95 } else {
96 auto iter = foreground_weight_table_.find(key);
97 if (iter == foreground_weight_table_.end()) {
98 weights = &kForegroundDefaultWeight;
99 } else {
100 weights = &iter->second;
101 }
102 }
103 if (weights == nullptr || weights->size() < 7) {
104 AERROR << "Invalid weights";
105 return 1e+10f;
106 }
107 float distance = 0.f;
108 float delta = 1e-10f;
109
110 double current_time = object->object_ptr->latest_tracked_time;
111 track->PredictState(current_time);
112
113 double time_diff =
114 track->age_ ? current_time - track->latest_visible_time_ : 0;
115 if (weights->at(0) > delta) {
116 distance +=
117 weights->at(0) * LocationDistance(latest_object, track->predict_.state,
118 object, time_diff);
119 }
120 if (weights->at(1) > delta) {
121 distance +=
122 weights->at(1) * DirectionDistance(latest_object, track->predict_.state,
123 object, time_diff);
124 }
125 if (weights->at(2) > delta) {
126 distance +=
127 weights->at(2) * BboxSizeDistance(latest_object, track->predict_.state,
128 object, time_diff);
129 }
130 if (weights->at(3) > delta) {
131 distance +=
132 weights->at(3) * PointNumDistance(latest_object, track->predict_.state,
133 object, time_diff);
134 }
135 if (weights->at(4) > delta) {
136 distance +=
137 weights->at(4) * HistogramDistance(latest_object, track->predict_.state,
138 object, time_diff);
139 }
140 if (weights->at(5) > delta) {
141 distance += weights->at(5) * CentroidShiftDistance(latest_object,
142 track->predict_.state,
143 object, time_diff);
144 }
145 if (weights->at(6) > delta) {
146 distance += weights->at(6) *
147 BboxIouDistance(latest_object, track->predict_.state, object,
149 }
150 // for foreground, calculate semantic map based distance
151// if (!is_background) {
152// distance += weights->at(7) * SemanticMapDistance(*track, object);
153// }
154
155 return distance;
156}
157
158} // namespace radar4d
159} // namespace perception
160} // namespace apollo
std::map< std::string, std::vector< float > > foreground_weight_table_
bool Init(const MrfTrackObjectDistanceInitOptions &options=MrfTrackObjectDistanceInitOptions())
Init mrf track object distance
std::map< std::string, std::vector< float > > background_weight_table_
float ComputeDistance(const TrackedObjectConstPtr &object, const MrfTrackDataConstPtr &track) const
Compute object track distance
#define ACHECK(cond)
Definition log.h:80
#define AERROR
Definition log.h:44
bool GetProtoFromFile(const std::string &file_name, google::protobuf::Message *message)
Parses the content of the file specified by the file_name as a representation of protobufs,...
Definition file.cc:132
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 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
std::shared_ptr< const TrackedObject > TrackedObjectConstPtr
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 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 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 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
std::shared_ptr< const MrfTrackData > MrfTrackDataConstPtr
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
std::string GetConfigFile(const std::string &config_path, const std::string &config_file)
Definition util.cc:80
class register implement
Definition arena_queue.h:37