Apollo 10.0
自动驾驶开放平台
apollo::perception::camera::OMTObstacleTracker类 参考

#include <omt_obstacle_tracker.h>

类 apollo::perception::camera::OMTObstacleTracker 继承关系图:
apollo::perception::camera::OMTObstacleTracker 的协作图:

Public 成员函数

EIGEN_MAKE_ALIGNED_OPERATOR_NEW OMTObstacleTracker ()=default
 
 ~OMTObstacleTracker ()=default
 
bool Init (const ObstacleTrackerInitOptions &options) override
 initialize omt obstacle tracker with options
 
bool Process (std::shared_ptr< CameraTrackingFrame > camera_frame)
 main function for tracking
 
bool FeatureExtract (CameraTrackingFrame *frame) override
 extract features from the new frame
 
bool Predict (CameraTrackingFrame *frame) override
 predict candidate obstales in the new frame candidate obstacle 2D boxes should be filled, required
 
bool Associate2D (std::shared_ptr< CameraTrackingFrame > frame) override
 calculate similarity of two objects
 
bool Associate3D (std::shared_ptr< CameraTrackingFrame > frame) override
 associate obstales by 3D information associated obstacles with tracking id should be filled, required, smoothed 3D information can be filled, optional.
 
- Public 成员函数 继承自 apollo::perception::camera::BaseObstacleTracker
 BaseObstacleTracker ()=default
 
virtual ~BaseObstacleTracker ()=default
 
 DISALLOW_COPY_AND_ASSIGN (BaseObstacleTracker)
 

Protected 属性

ObjectTemplateManagerobject_template_manager_ = nullptr
 

详细描述

在文件 omt_obstacle_tracker.h54 行定义.

构造及析构函数说明

◆ OMTObstacleTracker()

EIGEN_MAKE_ALIGNED_OPERATOR_NEW apollo::perception::camera::OMTObstacleTracker::OMTObstacleTracker ( )
default

◆ ~OMTObstacleTracker()

apollo::perception::camera::OMTObstacleTracker::~OMTObstacleTracker ( )
default

成员函数说明

◆ Associate2D()

bool apollo::perception::camera::OMTObstacleTracker::Associate2D ( std::shared_ptr< CameraTrackingFrame frame)
overridevirtual

calculate similarity of two objects

参数
frame
返回
true
false

associate obstales by 2D information associated obstacles with tracking id should be filled, required, smoothed 2D&3D information can be filled, optional.

参数
frame
返回
true
false

实现了 apollo::perception::camera::BaseObstacleTracker.

在文件 omt_obstacle_tracker.cc425 行定义.

426 {
427 // pre-compute appearance similarities between frames
429 frame_buffer_.push_back(frame);
430 // calculate the similarity between the current frame and the previous frames
431 std::shared_ptr<CameraTrackingFrame> cur_frame_ptr = frame_buffer_.back();
432 for (auto frame_ptr : frame_buffer_) {
433 int pre_frame_id = frame_ptr->frame_id;
434 int cur_frame_id = cur_frame_ptr->frame_id;
435 similar_->Calc(frame_ptr.get(), cur_frame_ptr.get(),
436 similar_map_.get(pre_frame_id, cur_frame_id).get());
437 }
438
439 // remove oldest frame in Target
440 for (auto &target : targets_) {
441 target.RemoveOld(frame_buffer_.front()->frame_id);
442 ++target.lost_age;
443 }
444 // clear non Target in targets_
445 ClearTargets();
446 // correct detection 3d size
447 reference_.CorrectSize(frame.get());
448
449 TrackObjectPtrs track_objects;
450 for (size_t i = 0; i < frame->detected_objects.size(); ++i) {
451 TrackObjectPtr track_ptr(new TrackObject);
452 track_ptr->object = frame->detected_objects[i];
453 track_ptr->object->id = static_cast<int>(i);
454 track_ptr->timestamp = frame->timestamp;
455 track_ptr->indicator = PatchIndicator(frame->frame_id, static_cast<int>(i),
456 frame->data_provider->sensor_name());
457 track_ptr->object->camera_supplement.sensor_name =
458 frame->data_provider->sensor_name();
459 ProjectBox(frame->detected_objects[i]->camera_supplement.box,
460 frame->project_matrix, &(track_ptr->projected_box));
461 track_objects.push_back(track_ptr);
462 }
463 // wxt todo: solve reference and calibration_service
464 used_.clear();
465 used_.resize(frame->detected_objects.size(), false);
466 // generate hypothesis between existing Targets
467 // and track_objects in the new frame
468 GenerateHypothesis(track_objects);
469 // create new Targets for track_objects that are not
470 // associated with any existing Targets
471 int new_count = CreateNewTarget(track_objects);
472 AINFO << "Create " << new_count << " new target";
473
474 for (auto &target : targets_) {
475 // remove old Target
476 if (target.lost_age > omt_param_.reserve_age()) {
477 AINFO << "Target " << target.id << " is lost";
478 target.Clear();
479 } else {
480 // update the sub_type and size of the Target
481 target.UpdateType(frame.get());
482 // update the 2D center, width and height of the Target
483 target.Update2D(frame.get());
484 }
485 }
486
487 // combine targets using iou after association
488 CombineDuplicateTargets();
489
490 // return filter reulst to original box
491 Eigen::Matrix3d inverse_project = frame->project_matrix.inverse();
492 for (auto &target : targets_) {
493 if (!target.isLost()) {
494 ProjectBox(target[-1]->projected_box, inverse_project,
495 &(target[-1]->object->camera_supplement.box));
496 RefineBox(target[-1]->object->camera_supplement.box, width_, height_,
497 &(target[-1]->object->camera_supplement.box));
498 }
499 }
500 return true;
501}
static bool set_device_id(int device_id)
#define AINFO
Definition log.h:42
std::vector< TrackObjectPtr > TrackObjectPtrs
std::shared_ptr< TrackObject > TrackObjectPtr
void ProjectBox(const base::BBox2DF &box_origin, const Eigen::Matrix3d &transform, base::BBox2DF *box_projected)
void RefineBox(const base::Rect< T > &box_in, const T width, const T height, base::Rect< T > *box_out)
Definition util.h:92
const std::shared_ptr< base::Blob< float > > get(int frame1, int frame2) const
Definition frame_list.h:92

◆ Associate3D()

bool apollo::perception::camera::OMTObstacleTracker::Associate3D ( std::shared_ptr< CameraTrackingFrame frame)
overridevirtual

associate obstales by 3D information associated obstacles with tracking id should be filled, required, smoothed 3D information can be filled, optional.

参数
frame
返回
true
false

实现了 apollo::perception::camera::BaseObstacleTracker.

在文件 omt_obstacle_tracker.cc522 行定义.

523 {
524 reference_.UpdateReference(frame.get(), targets_);
525 frame->tracked_objects.clear();
526 TrackObjectPtrs track_objects;
527 // mismatch may lead to an abnormal movement
528 // if an abnormal movement is found, remove old target and create new one
529 for (auto &target : targets_) {
530 if (target.isLost() || target.Size() == 1) {
531 continue;
532 }
533 auto obj = target[-1]->object;
534 if (obj->type != base::ObjectType::UNKNOWN_UNMOVABLE) {
535 Eigen::VectorXd x = target.world_center.get_state();
536 double move = sqr(x[0] - obj->center[0]) + sqr(x[1] - obj->center[1]);
537 float obj_2_car_x = obj->camera_supplement.local_center[0];
538 float obj_2_car_y = obj->camera_supplement.local_center[2];
539 float dis = obj_2_car_x * obj_2_car_x + obj_2_car_y * obj_2_car_y;
540 if (move > sqr(omt_param_.abnormal_movement()) * dis) {
541 AINFO << "Target " << target.id << " is removed for abnormal movement";
542 track_objects.push_back(target.latest_object);
543 target.Clear();
544 }
545 }
546 }
547 ClearTargets();
548 used_.clear();
549 used_.resize(track_objects.size(), false);
550 int new_count = CreateNewTarget(track_objects);
551 AINFO << "Create " << new_count << " new target";
552 for (int j = 0; j < new_count; ++j) {
553 targets_[targets_.size() - j - 1].Update2D(frame.get());
554 targets_[targets_.size() - j - 1].UpdateType(frame.get());
555 }
556 for (Target &target : targets_) {
557 target.Update3D(frame.get());
558 if (!target.isLost()) {
559 frame->tracked_objects.push_back(target[-1]->object);
560 ADEBUG << "Target " << target.id
561 << " velocity: " << target.world_center.get_state().transpose()
562 << " % " << target.world_center.variance_.diagonal().transpose()
563 << " % " << target[-1]->object->velocity.transpose();
564 }
565 }
566 return true;
567}
void UpdateReference(const CameraTrackingFrame *frame, const apollo::common::EigenVector< Target > &targets)
#define ADEBUG
Definition log.h:41

◆ FeatureExtract()

bool apollo::perception::camera::OMTObstacleTracker::FeatureExtract ( CameraTrackingFrame frame)
overridevirtual

extract features from the new frame

参数
frame
返回
true
false

实现了 apollo::perception::camera::BaseObstacleTracker.

在文件 omt_obstacle_tracker.cc124 行定义.

124 {
125 FeatureExtractorOptions feature_options;
126 feature_options.normalized = true;
127 bool res = feature_extractor_->Extract(feature_options, frame);
128 return res;
129}

◆ Init()

bool apollo::perception::camera::OMTObstacleTracker::Init ( const ObstacleTrackerInitOptions options)
overridevirtual

initialize omt obstacle tracker with options

参数
options
返回
true
false

实现了 apollo::perception::camera::BaseObstacleTracker.

在文件 omt_obstacle_tracker.cc31 行定义.

31 {
32 std::string config_file =
33 GetConfigFile(options.config_path, options.config_file);
34 if (!cyber::common::GetProtoFromFile(config_file, &omt_param_)) {
35 AERROR << "Read config failed: " << config_file;
36 return false;
37 }
38 track_id_ = 0;
39 frame_num_ = 0;
40 // frame list
41 frame_buffer_.set_capacity(omt_param_.img_capability());
42 // similar map
43 gpu_id_ = options.gpu_id;
44 similar_map_.Init(omt_param_.img_capability(), gpu_id_);
45 similar_.reset(new GPUSimilar);
46 // reference
47 width_ = options.image_width;
48 height_ = options.image_height;
49 reference_.Init(omt_param_.reference(), width_, height_);
50 // type change cost file
51 std::string type_change_cost_file =
52 GetConfigFile(options.config_path, omt_param_.type_change_cost_file());
53 std::ifstream fin(type_change_cost_file);
54 ACHECK(fin.is_open());
55 kTypeAssociatedCost_.clear();
56 int n_type = static_cast<int>(base::ObjectSubType::MAX_OBJECT_TYPE);
57 for (int i = 0; i < n_type; ++i) {
58 kTypeAssociatedCost_.emplace_back(std::vector<float>(n_type, 0));
59 for (int j = 0; j < n_type; ++j) {
60 fin >> kTypeAssociatedCost_[i][j];
61 }
62 }
63 targets_.clear();
64 used_.clear();
65
66 // reset object template
67 object_template_manager_ = ObjectTemplateManager::Instance();
68
69 // reset feature_extractor_;
70 PluginParam plugin_param = omt_param_.plugin_param();
71 feature_extractor_.reset(
72 BaseFeatureExtractorRegisterer::GetInstanceByName(plugin_param.name()));
73 if (nullptr == feature_extractor_) {
74 AERROR << "Failed to get tracking instance.";
75 return false;
76 }
77
78 // init feature_extractor_
79 FeatureExtractorInitOptions feature_init_options;
80
81 feature_init_options.input_height = omt_param_.feature_input_height();
82 feature_init_options.input_width = omt_param_.feature_input_width();
83 feature_init_options.gpu_id = gpu_id_;
84 feature_init_options.config_path = plugin_param.config_path();
85 feature_init_options.config_file = plugin_param.config_file();
86
87 if (!feature_extractor_->Init(feature_init_options)) {
88 AERROR << "feature_extracotr init false";
89 return false;
90 }
91
92 // init object template
93 ACHECK(ObjectTemplateManager::Instance()->Init());
94
95 return true;
96}
bool Init(const ObstacleTrackerInitOptions &options) override
initialize omt obstacle tracker with options
EIGEN_MAKE_ALIGNED_OPERATOR_NEW void Init(const ReferenceParam &ref_param, float width, float height)
#define ACHECK(cond)
Definition log.h:80
#define AERROR
Definition log.h:44
bool GetProtoFromFile(const std::string &file_name, google::protobuf::Message *message)
Parses the content of the file specified by the file_name as a representation of protobufs,...
Definition file.cc:132
std::string GetConfigFile(const std::string &config_path, const std::string &config_file)
Definition util.cc:80
optional ReferenceParam reference
Definition omt.proto:98
optional perception::PluginParam plugin_param
Definition omt.proto:103
optional string type_change_cost_file
Definition omt.proto:99
EIGEN_MAKE_ALIGNED_OPERATOR_NEW bool Init(int dim, int gpu_id=0, int init_size=128)
Definition frame_list.h:66

◆ Predict()

bool apollo::perception::camera::OMTObstacleTracker::Predict ( CameraTrackingFrame frame)
overridevirtual

predict candidate obstales in the new frame candidate obstacle 2D boxes should be filled, required

参数
frame
返回
true
false

实现了 apollo::perception::camera::BaseObstacleTracker.

在文件 omt_obstacle_tracker.cc147 行定义.

147 {
148 for (auto &target : targets_) {
149 // use kalman filter to predict the image_center,
150 // world_center, world_center_const
151 target.Predict(frame);
152 auto obj = target.latest_object;
153 frame->proposed_objects.push_back(obj->object);
154 }
155 return true;
156}

◆ Process()

bool apollo::perception::camera::OMTObstacleTracker::Process ( std::shared_ptr< CameraTrackingFrame camera_frame)
virtual

main function for tracking

参数
camera_frame
返回
true
false

实现了 apollo::perception::camera::BaseObstacleTracker.

在文件 omt_obstacle_tracker.cc98 行定义.

98 {
99 if (nullptr == frame) {
100 return false;
101 }
102 if (!FeatureExtract(frame.get())) {
103 AERROR << "FeatureExtract failed!";
104 return false;
105 }
106
107 if (!Predict(frame.get())) {
108 AERROR << "Predict failed!";
109 return false;
110 }
111
112 if (!Associate2D(frame)) {
113 AERROR << "Associate2D failed!";
114 return false;
115 }
116
117 if (!Associate3D(frame)) {
118 AERROR << "Associate3D failed!";
119 return false;
120 }
121 return true;
122}
bool FeatureExtract(CameraTrackingFrame *frame) override
extract features from the new frame

类成员变量说明

◆ object_template_manager_

ObjectTemplateManager* apollo::perception::camera::OMTObstacleTracker::object_template_manager_ = nullptr
protected

在文件 omt_obstacle_tracker.h206 行定义.


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