Apollo 10.0
自动驾驶开放平台
mrf_track_object_matcher.h
浏览该文件的文档.
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#pragma once
17
18#include <memory>
19#include <string>
20#include <utility>
21#include <vector>
22
23#include "cyber/common/macros.h"
28
29namespace apollo {
30namespace perception {
31namespace radar4d {
32
34
36
38
40 public:
43
51 bool Init(const MrfTrackObjectMatcherInitOptions &options =
53
64 void Match(const MrfTrackObjectMatcherOptions &options,
65 const std::vector<TrackedObjectPtr> &objects,
66 const std::vector<MrfTrackDataPtr> &tracks,
67 std::vector<std::pair<size_t, size_t>> *assignments,
68 std::vector<size_t> *unassigned_tracks,
69 std::vector<size_t> *unassigned_objects);
70
76 std::string Name() const { return "MrfTrackObjectMatcher"; }
77
78 protected:
86 void ComputeAssociateMatrix(const std::vector<MrfTrackDataPtr> &tracks,
87 const std::vector<TrackedObjectPtr> &new_objects,
88 algorithm::SecureMat<float> *association_mat);
89
90 protected:
91 std::unique_ptr<MrfTrackObjectDistance> track_object_distance_;
94
95 float bound_value_ = 100.f;
96 float max_match_distance_ = 4.0f;
97 bool use_semantic_map = false;
98
99 private:
101}; // class MrfTrackObjectMatcher
102
103} // namespace radar4d
104} // namespace perception
105} // namespace apollo
void Match(const MrfTrackObjectMatcherOptions &options, const std::vector< TrackedObjectPtr > &objects, const std::vector< MrfTrackDataPtr > &tracks, std::vector< std::pair< size_t, size_t > > *assignments, std::vector< size_t > *unassigned_tracks, std::vector< size_t > *unassigned_objects)
Match detected objects to tracks
std::unique_ptr< MrfTrackObjectDistance > track_object_distance_
bool Init(const MrfTrackObjectMatcherInitOptions &options=MrfTrackObjectMatcherInitOptions())
Initalize mrf track object matcher
void ComputeAssociateMatrix(const std::vector< MrfTrackDataPtr > &tracks, const std::vector< TrackedObjectPtr > &new_objects, algorithm::SecureMat< float > *association_mat)
Compute association matrix
#define DISALLOW_COPY_AND_ASSIGN(classname)
Definition macros.h:48
class register implement
Definition arena_queue.h:37