#include <track_data.h>
|
| | TrackData () |
| |
| | TrackData (TrackedObjectPtr obj, int track_id) |
| |
| virtual | ~TrackData () |
| |
| std::pair< double, TrackedObjectPtr > | GetLatestObject () |
| | Get latest object
|
| |
| std::pair< double, TrackedObjectConstPtr > | GetLatestObject () const |
| | Get latest object
|
| |
| std::pair< double, TrackedObjectPtr > | GetOldestObject () |
| | Get oldest object
|
| |
| std::pair< double, TrackedObjectConstPtr > | GetOldestObject () const |
| | Get oldest object
|
| |
| std::pair< double, TrackedObjectPtr > | GetHistoryObject (int idx) |
| | Get histroy object
|
| |
| std::pair< double, TrackedObjectConstPtr > | GetHistoryObject (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
|
| |
◆ TrackData() [1/2]
| apollo::perception::radar4d::TrackData::TrackData |
( |
| ) |
|
◆ TrackData() [2/2]
| apollo::perception::radar4d::TrackData::TrackData |
( |
TrackedObjectPtr |
obj, |
|
|
int |
track_id |
|
) |
| |
◆ ~TrackData()
| apollo::perception::radar4d::TrackData::~TrackData |
( |
| ) |
|
|
virtual |
◆ GetHistoryObject() [1/2]
| std::pair< double, TrackedObjectPtr > apollo::perception::radar4d::TrackData::GetHistoryObject |
( |
int |
idx | ) |
|
Get histroy object
- 参数
-
| idx | when 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.cc 第 30 行定义.
30 {
32 AWARN <<
"no object in track";
34 }
38
39 if (idx > 0) {
40 std::map<double, TrackedObjectPtr>::iterator cur_obj =
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 =
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_
T abs(const T &x)
Get absolute value of x
std::shared_ptr< TrackedObject > TrackedObjectPtr
◆ GetHistoryObject() [2/2]
| std::pair< double, TrackedObjectConstPtr > apollo::perception::radar4d::TrackData::GetHistoryObject |
( |
int |
idx | ) |
const |
Get histroy object
- 参数
-
- 返回
- std::pair<double, TrackedObjectConstPtr>
在文件 track_data.cc 第 56 行定义.
57 {
59 AINFO <<
"no object in track";
61 }
65
66 if (idx > 0) {
67 std::map<double, TrackedObjectPtr>::const_iterator cur_obj =
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 =
76 for (int i = 0; i < max_idx; ++i) {
77 ++cur_obj;
78 }
79 return *cur_obj;
80 }
81}
◆ GetLatestObject() [1/2]
| std::pair< double, TrackedObjectPtr > apollo::perception::radar4d::TrackData::GetLatestObject |
( |
| ) |
|
|
inline |
Get latest object
- 返回
- std::pair<double, TrackedObjectPtr>
在文件 track_data.h 第 45 行定义.
◆ GetLatestObject() [2/2]
| std::pair< double, TrackedObjectConstPtr > apollo::perception::radar4d::TrackData::GetLatestObject |
( |
| ) |
const |
|
inline |
Get latest object
- 返回
- std::pair<double, TrackedObjectConstPtr>
在文件 track_data.h 第 56 行定义.
◆ GetOldestObject() [1/2]
| std::pair< double, TrackedObjectPtr > apollo::perception::radar4d::TrackData::GetOldestObject |
( |
| ) |
|
|
inline |
Get oldest object
- 返回
- std::pair<double, TrackedObjectPtr>
在文件 track_data.h 第 67 行定义.
◆ GetOldestObject() [2/2]
| std::pair< double, TrackedObjectConstPtr > apollo::perception::radar4d::TrackData::GetOldestObject |
( |
| ) |
const |
|
inline |
Get oldest object
- 返回
- std::pair<double, TrackedObjectConstPtr>
在文件 track_data.h 第 78 行定义.
◆ PushTrackedObjectToTrack()
| void apollo::perception::radar4d::TrackData::PushTrackedObjectToTrack |
( |
TrackedObjectPtr |
obj, |
|
|
double |
time |
|
) |
| |
|
virtual |
Push tracked object to track
- 参数
-
在文件 track_data.cc 第 105 行定义.
105 {
111 if (obj->is_fake) {
113 } else {
116 }
119 }
120 } else {
121 AWARN <<
"push object time " << time
122 << " already exist in track, ignore insert.";
123 }
124}
static const int kMaxHistorySize
int consecutive_invisible_count_
◆ Reset() [1/2]
| void apollo::perception::radar4d::TrackData::Reset |
( |
| ) |
|
|
virtual |
Reset
被 apollo::perception::radar4d::MrfTrackData 重载.
在文件 track_data.cc 第 83 行定义.
83 {
97}
size_t continuous_motion_frames_
size_t pub_remain_frames_
std::deque< double > history_norm_variance_
bool should_check_velocity_consistency_
size_t continuous_static_frames_
MotionState motion_state_
std::deque< double > history_theta_variance_
◆ Reset() [2/2]
| void apollo::perception::radar4d::TrackData::Reset |
( |
TrackedObjectPtr |
obj, |
|
|
double |
time, |
|
|
int |
track_id |
|
) |
| |
|
virtual |
Reset
- 参数
-
在文件 track_data.cc 第 99 行定义.
99 {
103}
virtual void PushTrackedObjectToTrack(TrackedObjectPtr obj, double time)
Push tracked object to track
◆ age_
| int apollo::perception::radar4d::TrackData::age_ = 0 |
◆ consecutive_invisible_count_
| int apollo::perception::radar4d::TrackData::consecutive_invisible_count_ = 0 |
◆ continuous_motion_frames_
| size_t apollo::perception::radar4d::TrackData::continuous_motion_frames_ = 0 |
◆ continuous_static_frames_
| size_t apollo::perception::radar4d::TrackData::continuous_static_frames_ = 0 |
◆ history_norm_variance_
| std::deque<double> apollo::perception::radar4d::TrackData::history_norm_variance_ |
◆ history_objects_
| std::map<double, TrackedObjectPtr> apollo::perception::radar4d::TrackData::history_objects_ |
◆ history_theta_variance_
| std::deque<double> apollo::perception::radar4d::TrackData::history_theta_variance_ |
◆ kMaxHistorySize
| const int apollo::perception::radar4d::TrackData::kMaxHistorySize = 40 |
|
static |
◆ max_history_size_
| int apollo::perception::radar4d::TrackData::max_history_size_ = 40 |
◆ motion_state_
◆ pub_remain_frames_
| size_t apollo::perception::radar4d::TrackData::pub_remain_frames_ = 0 |
◆ should_check_velocity_consistency_
| bool apollo::perception::radar4d::TrackData::should_check_velocity_consistency_ = true |
◆ total_visible_count_
| int apollo::perception::radar4d::TrackData::total_visible_count_ = 0 |
◆ track_id_
| int apollo::perception::radar4d::TrackData::track_id_ = -1 |
该类的文档由以下文件生成:
- modules/perception/radar4d_detection/lib/tracker/common/track_data.h
- modules/perception/radar4d_detection/lib/tracker/common/track_data.cc