Apollo  v5.5.0
Open source self driving car software
mlf_engine.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 <set>
20 #include <string>
21 #include <vector>
22 
26 
27 namespace apollo {
28 namespace perception {
29 namespace lidar {
30 
32  public:
33  MlfEngine() = default;
34  ~MlfEngine() = default;
35 
36  bool Init(const MultiTargetTrackerInitOptions& options =
38 
39  // @brief: track segmented objects from multiple lidar sensors
40  // @params [in]: tracker options
41  // @params [in/out]: lidar frame
42  bool Track(const MultiTargetTrackerOptions& options,
43  LidarFrame* frame) override;
44 
45  std::string Name() const override { return "MlfEngine"; };
46 
47  protected:
48  // @brief: split foreground/background objects and attach to tracked objects
49  // @params [in]: objects
50  // @params [in]: sensor info
52  const std::vector<base::ObjectPtr>& objects,
53  const base::SensorInfo& sensor_info);
54 
55  // @brief: match tracks and objects and object-track assignment
56  // @params [in]: match options
57  // @params [in]: objects for match
58  // @params [in]: name
59  // @params [in/out]: tracks for match and assignment
61  const MlfTrackObjectMatcherOptions& match_options,
62  const std::vector<TrackedObjectPtr>& objects, const std::string& name,
63  std::vector<MlfTrackDataPtr>* tracks);
64 
65  // @brief: filter tracks
66  // @params [in]: tracks for filter
67  // @params [in]: frame timestamp
68  void TrackStateFilter(const std::vector<MlfTrackDataPtr>& tracks,
69  double frame_timestamp);
70 
71  // @brief: collect track results and store in frame tracked objects
72  // @params [in/out]: lidar frame
73  void CollectTrackedResult(LidarFrame* frame);
74 
75  // @brief: remove stale track data for memory management
76  // @params: name
77  // @params: timestamp
78  // @params [in/out]: tracks to be cleaned
79  void RemoveStaleTrackData(const std::string& name, double timestamp,
80  std::vector<MlfTrackDataPtr>* tracks);
81 
82  protected:
83  // foreground and background track data
84  std::vector<MlfTrackDataPtr> foreground_track_data_;
85  std::vector<MlfTrackDataPtr> background_track_data_;
86  // foreground and background tracked objects
87  std::vector<TrackedObjectPtr> foreground_objects_;
88  std::vector<TrackedObjectPtr> background_objects_;
89  // tracker
90  std::unique_ptr<MlfTracker> tracker_;
91  // track object matcher
92  std::unique_ptr<MlfTrackObjectMatcher> matcher_;
93  // offset maintained for numeric issues
94  Eigen::Vector3d global_to_local_offset_;
95  Eigen::Affine3d sensor_to_local_pose_;
96  // main sensor info
97  std::set<std::string> main_sensor_;
98  // params
100  size_t histogram_bin_size_ = 10;
103  bool use_frame_timestamp_ = false;
104 };
105 
106 } // namespace lidar
107 } // namespace perception
108 } // namespace apollo
Definition: mlf_engine.h:31
bool output_predict_objects_
Definition: mlf_engine.h:101
double reserved_invisible_time_
Definition: mlf_engine.h:102
size_t histogram_bin_size_
Definition: mlf_engine.h:100
Definition: blob.h:72
Definition: base_multi_target_tracker.h:27
Definition: base_multi_target_tracker.h:31
std::vector< TrackedObjectPtr > foreground_objects_
Definition: mlf_engine.h:87
void TrackObjectMatchAndAssign(const MlfTrackObjectMatcherOptions &match_options, const std::vector< TrackedObjectPtr > &objects, const std::string &name, std::vector< MlfTrackDataPtr > *tracks)
Eigen::Vector3d global_to_local_offset_
Definition: mlf_engine.h:94
std::set< std::string > main_sensor_
Definition: mlf_engine.h:97
Definition: base_multi_target_tracker.h:29
std::string Name() const override
Definition: mlf_engine.h:45
Definition: mlf_track_object_matcher.h:34
void CollectTrackedResult(LidarFrame *frame)
bool use_frame_timestamp_
Definition: mlf_engine.h:103
bool use_histogram_for_match_
Definition: mlf_engine.h:99
std::unique_ptr< MlfTracker > tracker_
Definition: mlf_engine.h:90
std::vector< MlfTrackDataPtr > background_track_data_
Definition: mlf_engine.h:85
void SplitAndTransformToTrackedObjects(const std::vector< base::ObjectPtr > &objects, const base::SensorInfo &sensor_info)
Definition: sensor_meta.h:57
Definition: lidar_frame.h:33
std::vector< MlfTrackDataPtr > foreground_track_data_
Definition: mlf_engine.h:84
bool Init(const MultiTargetTrackerInitOptions &options=MultiTargetTrackerInitOptions()) override
Eigen::Affine3d sensor_to_local_pose_
Definition: mlf_engine.h:95
std::unique_ptr< MlfTrackObjectMatcher > matcher_
Definition: mlf_engine.h:92
void RemoveStaleTrackData(const std::string &name, double timestamp, std::vector< MlfTrackDataPtr > *tracks)
bool Track(const MultiTargetTrackerOptions &options, LidarFrame *frame) override
void TrackStateFilter(const std::vector< MlfTrackDataPtr > &tracks, double frame_timestamp)
std::vector< TrackedObjectPtr > background_objects_
Definition: mlf_engine.h:88