Apollo  6.0
Open source self driving car software
mlf_track_object_matcher.h
Go to the documentation of this file.
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  *****************************************************************************/
16 #pragma once
17 
18 #include <memory>
19 #include <string>
20 #include <utility>
21 #include <vector>
22 
23 #include "cyber/common/macros.h"
27 
28 namespace apollo {
29 namespace perception {
30 namespace lidar {
31 
33 
35 
37  public:
38  MlfTrackObjectMatcher() = default;
39  ~MlfTrackObjectMatcher() = default;
40 
41  bool Init(const MlfTrackObjectMatcherInitOptions &options =
43 
44  // @brief: match detected objects to tracks
45  // @params [in]: new detected objects for matching
46  // @params [in]: maintaining tracks for matching
47  // @params [out]: assignment pair of object & track
48  // @params [out]: tracks without matched object
49  // @params [out]: objects without matched track
50  void Match(const MlfTrackObjectMatcherOptions &options,
51  const std::vector<TrackedObjectPtr> &objects,
52  const std::vector<MlfTrackDataPtr> &tracks,
53  std::vector<std::pair<size_t, size_t>> *assignments,
54  std::vector<size_t> *unassigned_tracks,
55  std::vector<size_t> *unassigned_objects);
56 
57  std::string Name() const { return "MlfTrackObjectMatcher"; }
58 
59  protected:
60  // @brief: compute association matrix
61  // @params [in]: maintained tracks for matching
62  // @params [in]: new detected objects for matching
63  // @params [out]: matrix of association distance
64  void ComputeAssociateMatrix(const std::vector<MlfTrackDataPtr> &tracks,
65  const std::vector<TrackedObjectPtr> &new_objects,
66  common::SecureMat<float> *association_mat);
67 
68  protected:
69  std::unique_ptr<MlfTrackObjectDistance> track_object_distance_;
72 
73  float bound_value_ = 100.f;
74  float max_match_distance_ = 4.0f;
75  bool use_semantic_map = false;
76 
77  private:
79 }; // class MlfTrackObjectMatcher
80 
81 } // namespace lidar
82 } // namespace perception
83 } // namespace apollo
std::string Name() const
Definition: mlf_track_object_matcher.h:57
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
Definition: mlf_track_object_matcher.h:36
#define DISALLOW_COPY_AND_ASSIGN(classname)
Definition: macros.h:48
BaseBipartiteGraphMatcher * foreground_matcher_
Definition: mlf_track_object_matcher.h:70
Definition: mlf_track_object_matcher.h:34
Definition: mlf_track_object_matcher.h:32
std::unique_ptr< MlfTrackObjectDistance > track_object_distance_
Definition: mlf_track_object_matcher.h:69
bool Init(const char *binary_name)
Definition: base_bipartite_graph_matcher.h:39
BaseBipartiteGraphMatcher * background_matcher_
Definition: mlf_track_object_matcher.h:71