23#include "modules/common_msgs/perception_msgs/perception_obstacle.pb.h"
38 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
68 std::string
Name()
const override {
return "MrfEngine"; };
78 const std::vector<base::ObjectPtr>& objects,
91 const std::vector<TrackedObjectPtr>& objects,
const std::string& name,
92 std::vector<MrfTrackDataPtr>* tracks);
101 double frame_timestamp);
118 std::vector<MrfTrackDataPtr>* tracks);
void SplitAndTransformToTrackedObjects(const std::vector< base::ObjectPtr > &objects, const base::SensorInfo &sensor_info)
Split foreground/background objects and attach to tracked objects
Eigen::Affine3d sensor_to_local_pose_
bool use_frame_timestamp_
void TrackObjectMatchAndAssign(const MrfTrackObjectMatcherOptions &match_options, const std::vector< TrackedObjectPtr > &objects, const std::string &name, std::vector< MrfTrackDataPtr > *tracks)
Match tracks and objets and object-track assignment
Eigen::Vector3d global_to_local_offset_
std::vector< TrackedObjectPtr > foreground_objects_
std::set< std::string > main_sensors_
std::unique_ptr< MrfTracker > tracker_
std::vector< TrackedObjectPtr > background_objects_
bool Track(const MultiTargetTrackerOptions &options, RadarFrame *frame) override
Track segmented objects from multiple radar sensors
void Clear()
Clear all data
std::vector< MrfTrackDataPtr > background_track_data_
apollo::prediction::PoseContainer pose_container_
std::string Name() const override
Get class name
apollo::prediction::ObstaclesContainer obstacle_container_
double reserved_invisible_time_
void CollectTrackedResult(RadarFrame *frame)
Collect track results and store in frame tracked objects
bool use_histogram_for_match_
apollo::perception::onboard::MsgSerializer serializer_
size_t histogram_bin_size_
void TrackStateFilter(const std::vector< MrfTrackDataPtr > &tracks, double frame_timestamp)
Filter tracks
void RemoveStaleTrackData(const std::string &name, double timestamp, std::vector< MrfTrackDataPtr > *tracks)
Remove stale track data for memory management
std::unique_ptr< MrfTrackObjectMatcher > matcher_
std::vector< MrfTrackDataPtr > foreground_track_data_
bool Init(const MultiTargetTrackerInitOptions &options=MultiTargetTrackerInitOptions()) override
Init mrf engine
bool output_predict_objects_
virtual ~MrfEngine()=default