27 namespace perception {
31 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
48 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
53 void Reset()
override;
64 void RemoveStaleHistory(
double timestamp);
66 void PredictState(
double timestamp)
const;
68 void GetAndCleanCachedObjectsInTimeInterval(
69 std::vector<TrackedObjectPtr>* objects);
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();
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();
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;
109 bool is_current_state_predicted_ =
true;
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: point_cloud.h:264
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