Apollo 10.0
自动驾驶开放平台
mlf_engine.h
浏览该文件的文档.
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
23#include "modules/common_msgs/perception_msgs/perception_obstacle.pb.h"
24
29
30namespace apollo {
31namespace perception {
32namespace lidar {
33
35 public:
36 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
37
38 public:
39 MlfEngine() = default;
40 virtual ~MlfEngine() = default;
48 bool Init(const MultiTargetTrackerInitOptions& options =
50
59 bool Track(const MultiTargetTrackerOptions& options,
60 LidarFrame* frame) override;
66 std::string Name() const override { return "MlfEngine"; };
67
68 protected:
76 const std::vector<base::ObjectPtr>& objects,
77 const base::SensorInfo& sensor_info, double frame_timestamp);
78
88 const MlfTrackObjectMatcherOptions& match_options,
89 const std::vector<TrackedObjectPtr>& objects, const std::string& name,
90 std::vector<MlfTrackDataPtr>* tracks);
91
98 void TrackStateFilter(const std::vector<MlfTrackDataPtr>& tracks,
99 double frame_timestamp);
100
106 void CollectTrackedResult(LidarFrame* frame);
107
115 void RemoveStaleTrackData(const std::string& name, double timestamp,
116 std::vector<MlfTrackDataPtr>* tracks);
117
124 void ObjectsDebugInfo(LidarFrame* frame, bool foreground_log = true);
125 void TrackDebugInfo(LidarFrame* frame);
126
131 void Clear();
132 // void AttachDebugInfo(
133 // std::vector<std::shared_ptr<base::Object>>* foreground_objs);
134
135 // void AttachSemanticPredictedTrajectory(
136 // const std::vector<MlfTrackDataPtr>& tracks);
137
138 protected:
139 // foreground and background track data
140 std::vector<MlfTrackDataPtr> foreground_track_data_;
141 std::vector<MlfTrackDataPtr> background_track_data_;
142 // foreground and background tracked objects
143 std::vector<TrackedObjectPtr> foreground_objects_;
144 std::vector<TrackedObjectPtr> background_objects_;
145 // tracker
146 std::unique_ptr<MlfTracker> tracker_;
147 // track object matcher
148 std::unique_ptr<MlfTrackObjectMatcher> matcher_;
149 // offset maintained for numeric issues
150 Eigen::Vector3d global_to_local_offset_;
151 Eigen::Affine3d sensor_to_local_pose_;
152
153 // params
160 bool use_semantic_map_ = false;
161 bool print_debug_log_ = false;
162 double delay_output_ = 0.3;
164};
165
166} // namespace lidar
167} // namespace perception
168} // namespace apollo
std::unique_ptr< MlfTracker > tracker_
Definition mlf_engine.h:146
std::vector< MlfTrackDataPtr > foreground_track_data_
Definition mlf_engine.h:140
void RemoveStaleTrackData(const std::string &name, double timestamp, std::vector< MlfTrackDataPtr > *tracks)
Remove stale track data for memory management
void TrackDebugInfo(LidarFrame *frame)
bool Track(const MultiTargetTrackerOptions &options, LidarFrame *frame) override
Track segmented objects from multiple lidar sensors
Definition mlf_engine.cc:73
std::unique_ptr< MlfTrackObjectMatcher > matcher_
Definition mlf_engine.h:148
std::vector< TrackedObjectPtr > foreground_objects_
Definition mlf_engine.h:143
void SplitAndTransformToTrackedObjects(const std::vector< base::ObjectPtr > &objects, const base::SensorInfo &sensor_info, double frame_timestamp)
Split foreground/background objects and attach to tracked objects
std::vector< MlfTrackDataPtr > background_track_data_
Definition mlf_engine.h:141
std::string Name() const override
Get class name
Definition mlf_engine.h:66
void ObjectsDebugInfo(LidarFrame *frame, bool foreground_log=true)
Output object-detection-model results and latest track results
void TrackObjectMatchAndAssign(const MlfTrackObjectMatcherOptions &match_options, const std::vector< TrackedObjectPtr > &objects, const std::string &name, std::vector< MlfTrackDataPtr > *tracks)
Match tracks and objets and object-track assignment
void TrackStateFilter(const std::vector< MlfTrackDataPtr > &tracks, double frame_timestamp)
Filter tracks
std::vector< TrackedObjectPtr > background_objects_
Definition mlf_engine.h:144
bool Init(const MultiTargetTrackerInitOptions &options=MultiTargetTrackerInitOptions()) override
Init mlf engine
Definition mlf_engine.cc:43
void CollectTrackedResult(LidarFrame *frame)
Collect track results and store in frame tracked objects
class register implement
Definition arena_queue.h:37