Apollo  6.0
Open source self driving car software
mlf_tracker.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 <limits>
19 #include <string>
20 #include <vector>
21 
25 
26 namespace apollo {
27 namespace perception {
28 namespace lidar {
29 
31 
32 struct MlfTrackOptions {};
33 
34 class MlfTracker {
35  public:
36  MlfTracker() = default;
38  for (auto& filter : filters_) {
39  delete filter;
40  }
41  }
42 
43  bool Init(const MlfTrackerInitOptions options = MlfTrackerInitOptions());
44 
45  // @brief: initialize new track data and push new object to cache
46  // @params [in/out]: new track data
47  // @params [in/out]: new object
48  void InitializeTrack(MlfTrackDataPtr new_track_data,
49  TrackedObjectPtr new_object);
50 
51  // @brief: update track data with object
52  // @params [in/out]: history track data
53  // @params [in/out]: new object
54  void UpdateTrackDataWithObject(MlfTrackDataPtr track_data,
55  TrackedObjectPtr new_object);
56 
57  // @brief: update track data without object
58  // @params [in]: timestamp
59  // @params [in/out]: history track data
60  void UpdateTrackDataWithoutObject(double timestamp,
61  MlfTrackDataPtr track_data);
62 
63  std::string Name() const { return "MlfTracker"; }
64 
65  protected:
66  // @brief: get next track id
67  // @return: track id
69  if (global_track_id_counter_ == std::numeric_limits<int>::max()) {
70  global_track_id_counter_ = 0;
71  }
72  return global_track_id_counter_++;
73  }
74 
75  protected:
76  // a single whole state filter or separate state filters
77  std::vector<MlfBaseFilter*> filters_;
78  // global track id
79  int global_track_id_counter_ = 0;
80  // filter option
82 }; // class MlfTracker
83 
84 } // namespace lidar
85 } // namespace perception
86 } // namespace apollo
Definition: mlf_base_filter.h:31
std::string Name() const
Definition: mlf_tracker.h:63
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
MlfFilterOptions filter_options_
Definition: mlf_tracker.h:81
~MlfTracker()
Definition: mlf_tracker.h:37
int GetNextTrackId()
Definition: mlf_tracker.h:68
Definition: mlf_tracker.h:32
Definition: mlf_tracker.h:34
std::shared_ptr< MlfTrackData > MlfTrackDataPtr
Definition: mlf_track_data.h:117
bool Init(const char *binary_name)
std::vector< MlfBaseFilter * > filters_
Definition: mlf_tracker.h:77
std::shared_ptr< TrackedObject > TrackedObjectPtr
Definition: tracked_object.h:156