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

#include <track_data.h>

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

Public 成员函数

 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 ()
 Reset
 
virtual void Reset (TrackedObjectPtr obj, double time, int track_id)
 Reset
 
virtual void PushTrackedObjectToTrack (TrackedObjectPtr obj, double time)
 Push tracked object to track
 

Public 属性

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 int kMaxHistorySize = 40
 

详细描述

在文件 track_data.h35 行定义.

构造及析构函数说明

◆ TrackData() [1/2]

apollo::perception::radar4d::TrackData::TrackData ( )

在文件 track_data.cc24 行定义.

24{ Reset(); }

◆ TrackData() [2/2]

apollo::perception::radar4d::TrackData::TrackData ( TrackedObjectPtr  obj,
int  track_id 
)

在文件 track_data.cc26 行定义.

26{}

◆ ~TrackData()

apollo::perception::radar4d::TrackData::~TrackData ( )
virtual

在文件 track_data.cc28 行定义.

28{}

成员函数说明

◆ GetHistoryObject() [1/2]

std::pair< double, TrackedObjectPtr > apollo::perception::radar4d::TrackData::GetHistoryObject ( int  idx)

Get histroy object

参数
idxwhen idx > 0, get object from oldest when idx <= 0, get object from latest when abs_idx is large than history size, return farest object close to idx
返回
std::pair<double, TrackedObjectPtr>

在文件 track_data.cc30 行定义.

30 {
31 if (history_objects_.empty()) {
32 AWARN << "no object in track";
33 return std::pair<double, TrackedObjectPtr>(0.0, TrackedObjectPtr(nullptr));
34 }
35 int max_idx = std::abs(idx) >= static_cast<int>(history_objects_.size())
36 ? static_cast<int>(history_objects_.size()) - 1
37 : abs(idx);
38 // from oldest
39 if (idx > 0) {
40 std::map<double, TrackedObjectPtr>::iterator cur_obj =
41 history_objects_.begin();
42 for (int i = 0; i < max_idx; ++i) {
43 ++cur_obj;
44 }
45 return *cur_obj;
46 } else {
47 std::map<double, TrackedObjectPtr>::reverse_iterator cur_obj =
48 history_objects_.rbegin();
49 for (int i = 0; i < max_idx; ++i) {
50 ++cur_obj;
51 }
52 return *cur_obj;
53 }
54}
std::map< double, TrackedObjectPtr > history_objects_
Definition track_data.h:130
#define AWARN
Definition log.h:43
T abs(const T &x)
Get absolute value of x
Definition misc.h:63
std::shared_ptr< TrackedObject > TrackedObjectPtr

◆ GetHistoryObject() [2/2]

std::pair< double, TrackedObjectConstPtr > apollo::perception::radar4d::TrackData::GetHistoryObject ( int  idx) const

Get histroy object

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

在文件 track_data.cc56 行定义.

57 {
58 if (history_objects_.empty()) {
59 AINFO << "no object in track";
60 return std::pair<double, TrackedObjectPtr>(0.0, TrackedObjectPtr(nullptr));
61 }
62 int max_idx = static_cast<size_t>(abs(idx)) >= history_objects_.size()
63 ? static_cast<int>(history_objects_.size()) - 1
64 : abs(idx);
65 // from oldest
66 if (idx > 0) {
67 std::map<double, TrackedObjectPtr>::const_iterator cur_obj =
68 history_objects_.cbegin();
69 for (int i = 0; i < max_idx; ++i) {
70 ++cur_obj;
71 }
72 return *cur_obj;
73 } else {
74 std::map<double, TrackedObjectPtr>::const_reverse_iterator cur_obj =
75 history_objects_.crbegin();
76 for (int i = 0; i < max_idx; ++i) {
77 ++cur_obj;
78 }
79 return *cur_obj;
80 }
81}
#define AINFO
Definition log.h:42

◆ GetLatestObject() [1/2]

std::pair< double, TrackedObjectPtr > apollo::perception::radar4d::TrackData::GetLatestObject ( )
inline

Get latest object

返回
std::pair<double, TrackedObjectPtr>

在文件 track_data.h45 行定义.

45 {
46 if (history_objects_.size() != 0) {
47 return *history_objects_.rbegin();
48 }
49 return std::pair<double, TrackedObjectPtr>(0.0, TrackedObjectPtr(nullptr));
50 }

◆ GetLatestObject() [2/2]

std::pair< double, TrackedObjectConstPtr > apollo::perception::radar4d::TrackData::GetLatestObject ( ) const
inline

Get latest object

返回
std::pair<double, TrackedObjectConstPtr>

在文件 track_data.h56 行定义.

56 {
57 if (history_objects_.size() != 0) {
58 return *history_objects_.rbegin();
59 }
60 return std::pair<double, TrackedObjectPtr>(0.0, TrackedObjectPtr(nullptr));
61 }

◆ GetOldestObject() [1/2]

std::pair< double, TrackedObjectPtr > apollo::perception::radar4d::TrackData::GetOldestObject ( )
inline

Get oldest object

返回
std::pair<double, TrackedObjectPtr>

在文件 track_data.h67 行定义.

67 {
68 if (history_objects_.size() != 0) {
69 return *history_objects_.begin();
70 }
71 return std::pair<double, TrackedObjectPtr>(0.0, TrackedObjectPtr(nullptr));
72 }

◆ GetOldestObject() [2/2]

std::pair< double, TrackedObjectConstPtr > apollo::perception::radar4d::TrackData::GetOldestObject ( ) const
inline

Get oldest object

返回
std::pair<double, TrackedObjectConstPtr>

在文件 track_data.h78 行定义.

78 {
79 if (history_objects_.size() != 0) {
80 return *history_objects_.begin();
81 }
82 return std::pair<double, TrackedObjectPtr>(0.0, TrackedObjectPtr(nullptr));
83 }

◆ PushTrackedObjectToTrack()

void apollo::perception::radar4d::TrackData::PushTrackedObjectToTrack ( TrackedObjectPtr  obj,
double  time 
)
virtual

Push tracked object to track

参数
obj
time

在文件 track_data.cc105 行定义.

105 {
106 if (history_objects_.find(time) == history_objects_.end()) {
107 history_objects_.insert(std::make_pair(time, obj));
108 age_++;
109 obj->track_id = track_id_;
110 obj->tracking_time = time - history_objects_.begin()->first;
111 if (obj->is_fake) {
113 } else {
116 }
117 if (history_objects_.size() > kMaxHistorySize) {
118 history_objects_.erase(history_objects_.begin());
119 }
120 } else {
121 AWARN << "push object time " << time
122 << " already exist in track, ignore insert.";
123 }
124}

◆ Reset() [1/2]

void apollo::perception::radar4d::TrackData::Reset ( )
virtual

Reset

apollo::perception::radar4d::MrfTrackData 重载.

在文件 track_data.cc83 行定义.

◆ Reset() [2/2]

void apollo::perception::radar4d::TrackData::Reset ( TrackedObjectPtr  obj,
double  time,
int  track_id 
)
virtual

Reset

参数
obj
time
track_id

在文件 track_data.cc99 行定义.

99 {
100 Reset();
101 track_id_ = track_id;
102 PushTrackedObjectToTrack(obj, time);
103}
virtual void PushTrackedObjectToTrack(TrackedObjectPtr obj, double time)
Push tracked object to track

类成员变量说明

◆ age_

int apollo::perception::radar4d::TrackData::age_ = 0

在文件 track_data.h126 行定义.

◆ consecutive_invisible_count_

int apollo::perception::radar4d::TrackData::consecutive_invisible_count_ = 0

在文件 track_data.h127 行定义.

◆ continuous_motion_frames_

size_t apollo::perception::radar4d::TrackData::continuous_motion_frames_ = 0

在文件 track_data.h135 行定义.

◆ continuous_static_frames_

size_t apollo::perception::radar4d::TrackData::continuous_static_frames_ = 0

在文件 track_data.h136 行定义.

◆ history_norm_variance_

std::deque<double> apollo::perception::radar4d::TrackData::history_norm_variance_

在文件 track_data.h146 行定义.

◆ history_objects_

std::map<double, TrackedObjectPtr> apollo::perception::radar4d::TrackData::history_objects_

在文件 track_data.h130 行定义.

◆ history_theta_variance_

std::deque<double> apollo::perception::radar4d::TrackData::history_theta_variance_

在文件 track_data.h147 行定义.

◆ kMaxHistorySize

const int apollo::perception::radar4d::TrackData::kMaxHistorySize = 40
static

在文件 track_data.h129 行定义.

◆ max_history_size_

int apollo::perception::radar4d::TrackData::max_history_size_ = 40

在文件 track_data.h131 行定义.

◆ motion_state_

MotionState apollo::perception::radar4d::TrackData::motion_state_ = MotionState::STATIC

在文件 track_data.h134 行定义.

◆ pub_remain_frames_

size_t apollo::perception::radar4d::TrackData::pub_remain_frames_ = 0

在文件 track_data.h140 行定义.

◆ should_check_velocity_consistency_

bool apollo::perception::radar4d::TrackData::should_check_velocity_consistency_ = true

在文件 track_data.h144 行定义.

◆ total_visible_count_

int apollo::perception::radar4d::TrackData::total_visible_count_ = 0

在文件 track_data.h128 行定义.

◆ track_id_

int apollo::perception::radar4d::TrackData::track_id_ = -1

在文件 track_data.h125 行定义.


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