23#include "modules/common_msgs/perception_msgs/perception_obstacle.pb.h"
36 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
66 std::string
Name()
const override {
return "MlfEngine"; };
76 const std::vector<base::ObjectPtr>& objects,
89 const std::vector<TrackedObjectPtr>& objects,
const std::string& name,
90 std::vector<MlfTrackDataPtr>* tracks);
99 double frame_timestamp);
116 std::vector<MlfTrackDataPtr>* tracks);
std::unique_ptr< MlfTracker > tracker_
std::vector< MlfTrackDataPtr > foreground_track_data_
double reserved_invisible_time_
bool use_histogram_for_match_
void RemoveStaleTrackData(const std::string &name, double timestamp, std::vector< MlfTrackDataPtr > *tracks)
Remove stale track data for memory management
void TrackDebugInfo(LidarFrame *frame)
bool Track(const MultiTargetTrackerOptions &options, LidarFrame *frame) override
Track segmented objects from multiple lidar sensors
std::unique_ptr< MlfTrackObjectMatcher > matcher_
Eigen::Vector3d global_to_local_offset_
std::vector< TrackedObjectPtr > foreground_objects_
void Clear()
Clear all data
bool set_static_outside_hdmap_
void SplitAndTransformToTrackedObjects(const std::vector< base::ObjectPtr > &objects, const base::SensorInfo &sensor_info, double frame_timestamp)
Split foreground/background objects and attach to tracked objects
bool use_frame_timestamp_
std::vector< MlfTrackDataPtr > background_track_data_
std::string Name() const override
Get class name
void ObjectsDebugInfo(LidarFrame *frame, bool foreground_log=true)
Output object-detection-model results and latest track results
void TrackObjectMatchAndAssign(const MlfTrackObjectMatcherOptions &match_options, const std::vector< TrackedObjectPtr > &objects, const std::string &name, std::vector< MlfTrackDataPtr > *tracks)
Match tracks and objets and object-track assignment
size_t histogram_bin_size_
bool output_predict_objects_
void TrackStateFilter(const std::vector< MlfTrackDataPtr > &tracks, double frame_timestamp)
Filter tracks
std::vector< TrackedObjectPtr > background_objects_
bool Init(const MultiTargetTrackerInitOptions &options=MultiTargetTrackerInitOptions()) override
Init mlf engine
void CollectTrackedResult(LidarFrame *frame)
Collect track results and store in frame tracked objects
Eigen::Affine3d sensor_to_local_pose_
virtual ~MlfEngine()=default