Apollo 11.0
自动驾驶开放平台
apollo::perception::radar4d::MrfTrackData类 参考

#include <mrf_track_data.h>

类 apollo::perception::radar4d::MrfTrackData 继承关系图:
apollo::perception::radar4d::MrfTrackData 的协作图:

Public 类型

typedef std::map< double, TrackedObjectPtrTimedObjects
 

Public 成员函数

EIGEN_MAKE_ALIGNED_OPERATOR_NEW MrfTrackData ()=default
 
 ~MrfTrackData ()=default
 
void Reset () override
 Reset
 
void Reset (TrackedObjectPtr obj, int track_id)
 Reset all data
 
void PushTrackedObjectToTrack (TrackedObjectPtr obj)
 Push tracked object to track
 
void PushTrackedObjectToCache (TrackedObjectPtr obj)
 Push tracked object to cache
 
bool ToObject (const Eigen::Vector3d &local_to_global_offset, double timestamp, base::ObjectPtr object) const
 Convert tracked object to base object
 
void RemoveStaleHistory (double timestamp)
 Remove stale history data
 
void PredictState (double timestamp) const
 Predict state
 
void GetAndCleanCachedObjectsInTimeInterval (std::vector< TrackedObjectPtr > *objects)
 Get and clean cached objects in time interval
 
std::pair< double, TrackedObjectPtrGetLatestSensorObject (const std::string &sensor_name)
 Get latest sensor object
 
std::pair< double, TrackedObjectConstPtrGetLatestSensorObject (const std::string &sensor_name) const
 Get latest sensor object
 
- Public 成员函数 继承自 apollo::perception::radar4d::TrackData
 TrackData ()
 
 TrackData (TrackedObjectPtr obj, int track_id)
 
virtual ~TrackData ()
 
std::pair< double, TrackedObjectPtrGetLatestObject ()
 Get latest object
 
std::pair< double, TrackedObjectConstPtrGetLatestObject () const
 Get latest object
 
std::pair< double, TrackedObjectPtrGetOldestObject ()
 Get oldest object
 
std::pair< double, TrackedObjectConstPtrGetOldestObject () const
 Get oldest object
 
std::pair< double, TrackedObjectPtrGetHistoryObject (int idx)
 Get histroy object
 
std::pair< double, TrackedObjectConstPtrGetHistoryObject (int idx) const
 Get histroy object
 
virtual void Reset (TrackedObjectPtr obj, double time, int track_id)
 Reset
 
virtual void PushTrackedObjectToTrack (TrackedObjectPtr obj, double time)
 Push tracked object to track
 

Public 属性

std::map< std::string, TimedObjectssensor_history_objects_
 
TimedObjects cached_objects_
 
MrfPredict predict_
 
double duration_ = 0.0
 
double consecutive_invisible_time_ = 0.0
 
double latest_visible_time_ = 0.0
 
double latest_cached_time_ = 0.0
 
double first_tracked_time_ = 0.0
 
bool is_current_state_predicted_ = true
 
- Public 属性 继承自 apollo::perception::radar4d::TrackData
int track_id_ = -1
 
int age_ = 0
 
int consecutive_invisible_count_ = 0
 
int total_visible_count_ = 0
 
std::map< double, TrackedObjectPtrhistory_objects_
 
int max_history_size_ = 40
 
MotionState motion_state_ = MotionState::STATIC
 
size_t continuous_motion_frames_ = 0
 
size_t continuous_static_frames_ = 0
 
size_t pub_remain_frames_ = 0
 
bool should_check_velocity_consistency_ = true
 
std::deque< double > history_norm_variance_
 
std::deque< double > history_theta_variance_
 

静态 Public 属性

static const double kMaxHistoryTime = 2.0
 
- 静态 Public 属性 继承自 apollo::perception::radar4d::TrackData
static const int kMaxHistorySize = 40
 

详细描述

在文件 mrf_track_data.h47 行定义.

成员类型定义说明

◆ TimedObjects

构造及析构函数说明

◆ MrfTrackData()

EIGEN_MAKE_ALIGNED_OPERATOR_NEW apollo::perception::radar4d::MrfTrackData::MrfTrackData ( )
default

◆ ~MrfTrackData()

apollo::perception::radar4d::MrfTrackData::~MrfTrackData ( )
default

成员函数说明

◆ GetAndCleanCachedObjectsInTimeInterval()

void apollo::perception::radar4d::MrfTrackData::GetAndCleanCachedObjectsInTimeInterval ( std::vector< TrackedObjectPtr > *  objects)

Get and clean cached objects in time interval

参数
objects

在文件 mrf_track_data.cc163 行定义.

164 {
165 objects->clear();
166 auto iter = cached_objects_.begin();
167 while (iter != cached_objects_.end()) {
168 const auto& timestamp = iter->first;
169 if (timestamp <= latest_visible_time_) {
170 cached_objects_.erase(iter++);
171 } else if (timestamp <= latest_cached_time_) {
172 objects->push_back(iter->second);
173 cached_objects_.erase(iter++);
174 } else {
175 break;
176 }
177 }
178}

◆ GetLatestSensorObject() [1/2]

std::pair< double, TrackedObjectPtr > apollo::perception::radar4d::MrfTrackData::GetLatestSensorObject ( const std::string &  sensor_name)
inline

Get latest sensor object

参数
sensor_name
返回
std::pair<double, TrackedObjectPtr>

在文件 mrf_track_data.h121 行定义.

122 {
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 }
std::map< std::string, TimedObjects > sensor_history_objects_
std::shared_ptr< TrackedObject > TrackedObjectPtr

◆ GetLatestSensorObject() [2/2]

std::pair< double, TrackedObjectConstPtr > apollo::perception::radar4d::MrfTrackData::GetLatestSensorObject ( const std::string &  sensor_name) const
inline

Get latest sensor object

参数
sensor_name
返回
std::pair<double, TrackedObjectConstPtr>

在文件 mrf_track_data.h138 行定义.

139 {
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 }

◆ PredictState()

void apollo::perception::radar4d::MrfTrackData::PredictState ( double  timestamp) const

Predict state

参数
timestamp

在文件 mrf_track_data.cc135 行定义.

135 {
136 if (history_objects_.empty()) {
137 return;
138 }
139 auto latest_iter = history_objects_.rbegin();
140 const double latest_time = latest_iter->first;
141 const auto& latest_object = latest_iter->second;
142 double time_diff = timestamp - latest_time;
143
144 const Eigen::Vector3d& latest_anchor_point =
145 latest_object->belief_anchor_point;
146 const Eigen::Vector3d& latest_velocity = latest_object->output_velocity;
147
148 predict_.state.resize(6);
149 predict_.state(0) = static_cast<float>(latest_anchor_point(0) +
150 latest_velocity(0) * time_diff);
151 predict_.state(1) = static_cast<float>(latest_anchor_point(1) +
152 latest_velocity(1) * time_diff);
153 predict_.state(2) = static_cast<float>(latest_anchor_point(2) +
154 latest_velocity(2) * time_diff);
155 predict_.state(3) = static_cast<float>(latest_velocity(0));
156 predict_.state(4) = static_cast<float>(latest_velocity(1));
157 predict_.state(5) = static_cast<float>(latest_velocity(2));
158
160 // TODO(.): predict cloud and polygon if needed in future.
161}
std::map< double, TrackedObjectPtr > history_objects_
Definition track_data.h:130

◆ PushTrackedObjectToCache()

void apollo::perception::radar4d::MrfTrackData::PushTrackedObjectToCache ( TrackedObjectPtr  obj)

Push tracked object to cache

参数
obj

在文件 mrf_track_data.cc82 行定义.

82 {
83 double timestamp = obj->object_ptr->latest_tracked_time;
84 if (cached_objects_.find(timestamp) == cached_objects_.end()) {
85 cached_objects_.insert(std::make_pair(timestamp, obj));
87 } else {
88 AINFO << "Push object timestamp " << timestamp << " from sensor "
89 << obj->sensor_info.name << " already exist in cache, ignore push.";
90 }
91}
#define AINFO
Definition log.h:42

◆ PushTrackedObjectToTrack()

void apollo::perception::radar4d::MrfTrackData::PushTrackedObjectToTrack ( TrackedObjectPtr  obj)

Push tracked object to track

参数
obj

在文件 mrf_track_data.cc48 行定义.

48 {
49 double timestamp = obj->object_ptr->latest_tracked_time;
50 if (history_objects_.find(timestamp) == history_objects_.end()) {
51 auto pair = std::make_pair(timestamp, obj);
52 history_objects_.insert(pair);
53 sensor_history_objects_[obj->sensor_info.name].insert(pair);
54 age_++;
55 if (age_ == 1) { // the first timestamp
56 if (obj->is_fake) {
57 AERROR << "obj is fake";
58 return;
59 }
62 }
63 obj->track_id = track_id_;
64 obj->tracking_time = timestamp - first_tracked_time_;
65 duration_ = obj->tracking_time;
66 if (obj->is_fake) {
69 } else {
74 }
76 } else {
77 AINFO << "Push object timestamp " << timestamp << " from sensor "
78 << obj->sensor_info.name << " already exist in track, ignore push.";
79 }
80}
void RemoveStaleHistory(double timestamp)
Remove stale history data
#define AERROR
Definition log.h:44

◆ RemoveStaleHistory()

void apollo::perception::radar4d::MrfTrackData::RemoveStaleHistory ( double  timestamp)

Remove stale history data

参数
timestamp

在文件 mrf_track_data.cc192 行定义.

192 {
194 for (auto& map : sensor_history_objects_) {
195 RemoveStaleDataFromMap(timestamp, &map.second);
196 }
197}
void RemoveStaleDataFromMap(double timestamp, std::map< double, TrackedObjectPtr > *data)

◆ Reset() [1/2]

void apollo::perception::radar4d::MrfTrackData::Reset ( )
overridevirtual

◆ Reset() [2/2]

void apollo::perception::radar4d::MrfTrackData::Reset ( TrackedObjectPtr  obj,
int  track_id 
)

Reset all data

参数
obj
track_id

在文件 mrf_track_data.cc42 行定义.

42 {
43 Reset();
44 track_id_ = track_id;
46}
void PushTrackedObjectToCache(TrackedObjectPtr obj)
Push tracked object to cache

◆ ToObject()

bool apollo::perception::radar4d::MrfTrackData::ToObject ( const Eigen::Vector3d &  local_to_global_offset,
double  timestamp,
base::ObjectPtr  object 
) const

Convert tracked object to base object

参数
local_to_global_offset
timestamp
object
返回
true
false

在文件 mrf_track_data.cc93 行定义.

94 {
95 if (history_objects_.empty()) {
96 return false;
97 }
98 auto latest_iter = history_objects_.rbegin();
99 const double latest_time = latest_iter->first;
100 const auto& latest_object = latest_iter->second;
101 latest_object->ToObject(object);
102 // predict object
103 double time_diff = timestamp - latest_time;
104 double offset_x = time_diff * object->velocity(0) + local_to_global_offset(0);
105 double offset_y = time_diff * object->velocity(1) + local_to_global_offset(1);
106 double offset_z = time_diff * object->velocity(2) + local_to_global_offset(2);
107 // a). update polygon
108 for (auto& pt : object->polygon) {
109 pt.x += offset_x;
110 pt.y += offset_y;
111 pt.z += offset_z;
112 }
113
114 // b). update center
115 object->center(0) += offset_x;
116 object->center(1) += offset_y;
117 object->center(2) += offset_z;
118 // c). update anchor point
119 object->anchor_point(0) += offset_x;
120 object->anchor_point(1) += offset_y;
121 object->anchor_point(2) += offset_z;
122 // d). update tracking timestamp
123 object->tracking_time += time_diff;
124 // e). update latest track timestamp
125 object->latest_tracked_time += time_diff;
126 // f). update cloud world in radar4d supplement
127 for (auto& pt : object->radar4d_supplement.cloud_world) {
128 pt.x += offset_x;
129 pt.y += offset_y;
130 pt.z += offset_z;
131 }
132 return true;
133}

类成员变量说明

◆ cached_objects_

TimedObjects apollo::perception::radar4d::MrfTrackData::cached_objects_

在文件 mrf_track_data.h153 行定义.

◆ consecutive_invisible_time_

double apollo::perception::radar4d::MrfTrackData::consecutive_invisible_time_ = 0.0

在文件 mrf_track_data.h159 行定义.

◆ duration_

double apollo::perception::radar4d::MrfTrackData::duration_ = 0.0

在文件 mrf_track_data.h158 行定义.

◆ first_tracked_time_

double apollo::perception::radar4d::MrfTrackData::first_tracked_time_ = 0.0

在文件 mrf_track_data.h162 行定义.

◆ is_current_state_predicted_

bool apollo::perception::radar4d::MrfTrackData::is_current_state_predicted_ = true

在文件 mrf_track_data.h164 行定义.

◆ kMaxHistoryTime

const double apollo::perception::radar4d::MrfTrackData::kMaxHistoryTime = 2.0
static

在文件 mrf_track_data.h169 行定义.

◆ latest_cached_time_

double apollo::perception::radar4d::MrfTrackData::latest_cached_time_ = 0.0

在文件 mrf_track_data.h161 行定义.

◆ latest_visible_time_

double apollo::perception::radar4d::MrfTrackData::latest_visible_time_ = 0.0

在文件 mrf_track_data.h160 行定义.

◆ predict_

MrfPredict apollo::perception::radar4d::MrfTrackData::predict_
mutable

在文件 mrf_track_data.h156 行定义.

◆ sensor_history_objects_

std::map<std::string, TimedObjects> apollo::perception::radar4d::MrfTrackData::sensor_history_objects_

在文件 mrf_track_data.h152 行定义.


该类的文档由以下文件生成: