Apollo 11.0
自动驾驶开放平台
mrf_track_data.h
浏览该文件的文档.
1/******************************************************************************
2 * Copyright 2023 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
26namespace apollo {
27namespace perception {
28namespace radar4d {
29
30struct MrfPredict {
31 Eigen::VectorXf state;
34 double timestamp;
39 void Reset() {
40 state.setZero();
41 polygon.clear();
42 cloud.clear();
43 timestamp = 0.0;
44 }
45};
46
47class MrfTrackData : public TrackData {
48 public:
49 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
50
51 MrfTrackData() = default;
52 ~MrfTrackData() = default;
53
58 void Reset() override;
65 void Reset(TrackedObjectPtr obj, int track_id);
66
73
80
90 bool ToObject(const Eigen::Vector3d& local_to_global_offset, double timestamp,
91 base::ObjectPtr object) const;
92
98 void RemoveStaleHistory(double timestamp);
99
105 void PredictState(double timestamp) const;
106
113 std::vector<TrackedObjectPtr>* objects);
114
121 std::pair<double, TrackedObjectPtr> GetLatestSensorObject(
122 const std::string& sensor_name) {
123 auto iter = sensor_history_objects_.find(sensor_name);
124 if (iter != sensor_history_objects_.end()) {
125 auto& history_objects = iter->second;
126 if (history_objects.size() != 0) {
127 return *history_objects.rbegin();
128 }
129 }
130 return std::pair<double, TrackedObjectPtr>(0.0, TrackedObjectPtr(nullptr));
131 }
138 std::pair<double, TrackedObjectConstPtr> GetLatestSensorObject(
139 const std::string& sensor_name) const {
140 auto iter = sensor_history_objects_.find(sensor_name);
141 if (iter != sensor_history_objects_.end()) {
142 auto& history_objects = iter->second;
143 if (history_objects.size() != 0) {
144 return *history_objects.rbegin();
145 }
146 }
147 return std::pair<double, TrackedObjectPtr>(0.0, TrackedObjectPtr(nullptr));
148 }
149
150 public:
151 typedef std::map<double, TrackedObjectPtr> TimedObjects;
152 std::map<std::string, TimedObjects> sensor_history_objects_;
154
155 // buffer for predict data
157
158 double duration_ = 0.0;
163
165
166 // @debug feature to be used for semantic mapping based tracking
167 // std::shared_ptr<apollo::prediction::Feature> feature_;
168
169 static const double kMaxHistoryTime;
170};
171
172typedef std::shared_ptr<MrfTrackData> MrfTrackDataPtr;
173typedef std::shared_ptr<const MrfTrackData> MrfTrackDataConstPtr;
174
175} // namespace radar4d
176} // namespace perception
177} // namespace apollo
void PredictState(double timestamp) const
Predict state
void PushTrackedObjectToCache(TrackedObjectPtr obj)
Push tracked object to cache
std::map< double, TrackedObjectPtr > TimedObjects
std::pair< double, TrackedObjectConstPtr > GetLatestSensorObject(const std::string &sensor_name) const
Get latest sensor object
void RemoveStaleHistory(double timestamp)
Remove stale history data
void PushTrackedObjectToTrack(TrackedObjectPtr obj)
Push tracked object to track
EIGEN_MAKE_ALIGNED_OPERATOR_NEW MrfTrackData()=default
bool ToObject(const Eigen::Vector3d &local_to_global_offset, double timestamp, base::ObjectPtr object) const
Convert tracked object to base object
void GetAndCleanCachedObjectsInTimeInterval(std::vector< TrackedObjectPtr > *objects)
Get and clean cached objects in time interval
std::map< std::string, TimedObjects > sensor_history_objects_
std::pair< double, TrackedObjectPtr > GetLatestSensorObject(const std::string &sensor_name)
Get latest sensor object
AttributeRadarPointCloud< RadarPointD > RadarPointDCloud
std::shared_ptr< Object > ObjectPtr
Definition object.h:127
std::shared_ptr< MrfTrackData > MrfTrackDataPtr
std::shared_ptr< TrackedObject > TrackedObjectPtr
std::shared_ptr< const MrfTrackData > MrfTrackDataConstPtr
class register implement
Definition arena_queue.h:37