Apollo  6.0
Open source self driving car software
mlf_track_data.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 <map>
19 #include <memory>
20 #include <string>
21 #include <utility>
22 #include <vector>
23 
25 
26 namespace apollo {
27 namespace perception {
28 namespace lidar {
29 
30 struct MlfPredict {
31  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
32 
33  Eigen::VectorXf state;
36  double timestamp;
37 
38  void Reset() {
39  state.setZero();
40  polygon.clear();
41  cloud.clear();
42  timestamp = 0.0;
43  }
44 };
45 
46 class MlfTrackData : public TrackData {
47  public:
48  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
49 
50  MlfTrackData() = default;
51  ~MlfTrackData() = default;
52 
53  void Reset() override;
54 
55  void Reset(TrackedObjectPtr obj, int track_id);
56 
57  void PushTrackedObjectToTrack(TrackedObjectPtr obj);
58 
59  void PushTrackedObjectToCache(TrackedObjectPtr obj);
60 
61  bool ToObject(const Eigen::Vector3d& local_to_global_offset, double timestamp,
62  base::ObjectPtr object) const;
63 
64  void RemoveStaleHistory(double timestamp);
65 
66  void PredictState(double timestamp) const;
67 
68  void GetAndCleanCachedObjectsInTimeInterval(
69  std::vector<TrackedObjectPtr>* objects);
70 
71  std::pair<double, TrackedObjectPtr> GetLatestSensorObject(
72  const std::string& sensor_name) {
73  auto iter = sensor_history_objects_.find(sensor_name);
74  if (iter != sensor_history_objects_.end()) {
75  auto& history_objects = iter->second;
76  if (history_objects.size() != 0) {
77  return *history_objects.rbegin();
78  }
79  }
80  return std::pair<double, TrackedObjectPtr>(0.0, TrackedObjectPtr(nullptr));
81  }
82 
83  std::pair<double, TrackedObjectConstPtr> GetLatestSensorObject(
84  const std::string& sensor_name) const {
85  auto iter = sensor_history_objects_.find(sensor_name);
86  if (iter != sensor_history_objects_.end()) {
87  auto& history_objects = iter->second;
88  if (history_objects.size() != 0) {
89  return *history_objects.rbegin();
90  }
91  }
92  return std::pair<double, TrackedObjectPtr>(0.0, TrackedObjectPtr(nullptr));
93  }
94 
95  public:
96  typedef std::map<double, TrackedObjectPtr> TimedObjects;
97  std::map<std::string, TimedObjects> sensor_history_objects_;
98  TimedObjects cached_objects_;
99 
100  // buffer for predict data
102 
103  double duration_ = 0.0;
104  double consecutive_invisible_time_ = 0.0;
105  double latest_visible_time_ = 0.0;
106  double latest_cached_time_ = 0.0;
107  double first_tracked_time_ = 0.0;
108 
109  bool is_current_state_predicted_ = true;
110 
111  // @debug feature to be used for semantic mapping based tracking
112 // std::shared_ptr<apollo::prediction::Feature> feature_;
113 
114  static const double kMaxHistoryTime;
115 };
116 
117 typedef std::shared_ptr<MlfTrackData> MlfTrackDataPtr;
118 typedef std::shared_ptr<const MlfTrackData> MlfTrackDataConstPtr;
119 
120 } // namespace lidar
121 } // namespace perception
122 } // namespace apollo
static const double kMaxHistoryTime
Definition: mlf_track_data.h:114
TimedObjects cached_objects_
Definition: mlf_track_data.h:98
std::pair< double, TrackedObjectConstPtr > GetLatestSensorObject(const std::string &sensor_name) const
Definition: mlf_track_data.h:83
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
std::map< double, TrackedObjectPtr > TimedObjects
Definition: mlf_track_data.h:96
void Reset()
Definition: mlf_track_data.h:38
void clear() override
Definition: point_cloud.h:357
MlfPredict predict_
Definition: mlf_track_data.h:101
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::VectorXf state
Definition: mlf_track_data.h:33
Eigen::Vector3d Vector3d
Definition: frame_transform.h:27
Definition: mlf_track_data.h:30
Definition: mlf_track_data.h:46
base::PointDCloud cloud
Definition: mlf_track_data.h:35
std::pair< double, TrackedObjectPtr > GetLatestSensorObject(const std::string &sensor_name)
Definition: mlf_track_data.h:71
std::shared_ptr< const MlfTrackData > MlfTrackDataConstPtr
Definition: mlf_track_data.h:118
std::shared_ptr< MlfTrackData > MlfTrackDataPtr
Definition: mlf_track_data.h:117
std::map< std::string, TimedObjects > sensor_history_objects_
Definition: mlf_track_data.h:97
base::PolygonDType polygon
Definition: mlf_track_data.h:34
Definition: track_data.h:35
std::shared_ptr< TrackedObject > TrackedObjectPtr
Definition: tracked_object.h:156
double timestamp
Definition: mlf_track_data.h:36
std::shared_ptr< Object > ObjectPtr
Definition: object.h:123