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

#include <project_feature.h>

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

Public 成员函数

 ProjectFeature ()=default
 
 ~ProjectFeature ()=default
 
bool Init (const FeatureExtractorInitOptions &init_options) override
 
bool Extract (const FeatureExtractorOptions &options, CameraTrackingFrame *frame) override
 
- Public 成员函数 继承自 apollo::perception::camera::BaseFeatureExtractor
 BaseFeatureExtractor ()=default
 
virtual ~BaseFeatureExtractor ()=default
 
void set_roi (int x, int y, int w, int h)
 
void decode_bbox (std::vector< std::shared_ptr< base::Object > > *objects)
 
void encode_bbox (std::vector< std::shared_ptr< base::Object > > *objects)
 

额外继承的成员函数

- Protected 属性 继承自 apollo::perception::camera::BaseFeatureExtractor
std::shared_ptr< base::Blob< float > > feat_blob_ = nullptr
 
int roi_x_ = 0
 
int roi_y_ = 0
 
int roi_w_ = 0
 
int roi_h_ = 0
 

详细描述

在文件 project_feature.h32 行定义.

构造及析构函数说明

◆ ProjectFeature()

apollo::perception::camera::ProjectFeature::ProjectFeature ( )
default

◆ ~ProjectFeature()

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

成员函数说明

◆ Extract()

bool apollo::perception::camera::ProjectFeature::Extract ( const FeatureExtractorOptions options,
CameraTrackingFrame frame 
)
overridevirtual

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

在文件 project_feature.cc78 行定义.

79 {
80 auto input_blob = net_->get_blob(model_param_.info().inputs(0).name());
81 auto output_blob = net_->get_blob(model_param_.info().outputs(0).name());
82 if (frame->detected_objects.empty()) {
83 return true;
84 }
85 input_blob->Reshape(frame->track_feature_blob->shape());
86 cudaMemcpy(
87 input_blob->mutable_gpu_data(), frame->track_feature_blob->gpu_data(),
88 frame->track_feature_blob->count() * sizeof(float), cudaMemcpyDefault);
89
90 cudaDeviceSynchronize();
91 net_->Infer();
92 cudaDeviceSynchronize();
93 frame->track_feature_blob->Reshape(
94 {static_cast<int>(frame->detected_objects.size()), output_blob->shape(1),
95 output_blob->shape(2), output_blob->shape(3)});
96
97 cudaMemcpy(
98 frame->track_feature_blob->mutable_gpu_data(), output_blob->gpu_data(),
99 frame->track_feature_blob->count() * sizeof(float), cudaMemcpyDefault);
100
101 norm_.L2Norm(frame->track_feature_blob.get());
102 return true;
103}
void L2Norm(base::Blob< float > *input_data)

◆ Init()

bool apollo::perception::camera::ProjectFeature::Init ( const FeatureExtractorInitOptions init_options)
overridevirtual

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

在文件 project_feature.cc33 行定义.

33 {
34 std::string config_file =
35 GetConfigFile(options.config_path, options.config_file);
36 if (!cyber::common::GetProtoFromFile(config_file, &model_param_)) {
37 AERROR << "Read config failed: " << config_file;
38 return false;
39 }
40
41 AINFO << "Load config Success: " << model_param_.ShortDebugString();
42
43 const auto &model_info = model_param_.info();
44 std::string model_path = GetModelPath(model_info.name());
45 std::string proto_file =
46 GetModelFile(model_path, model_info.proto_file().file());
47 std::string weight_file =
48 GetModelFile(model_path, model_info.weight_file().file());
49
50 // Network input and output names
51 std::vector<std::string> input_names =
52 inference::GetBlobNames(model_info.inputs());
53 std::vector<std::string> output_names =
54 inference::GetBlobNames(model_info.outputs());
55
57 model_info.framework(), proto_file, weight_file, output_names,
58 input_names, model_path));
59 ACHECK(nullptr != net_) << "Failed to init CNNAdapter";
60
61 gpu_id_ = GlobalConfig::Instance()->track_feature_gpu_id;
62 net_->set_gpu_id(gpu_id_);
63 net_->set_max_batch_size(100);
64
65 std::map<std::string, std::vector<int>> shape_map;
66 inference::AddShape(&shape_map, model_info.inputs());
67 inference::AddShape(&shape_map, model_info.outputs());
68
69 if (!net_->Init(shape_map)) {
70 AERROR << model_info.name() << "init failed!";
71 return false;
72 }
73
74 net_->Infer();
75 return true;
76}
#define ACHECK(cond)
Definition log.h:80
#define AERROR
Definition log.h:44
#define AINFO
Definition log.h:42
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::vector< std::string > GetBlobNames(const google::protobuf::RepeatedPtrField< common::ModelBlob > &model_blobs)
Definition model_util.cc:23
void AddShape(std::map< std::string, std::vector< int > > *shape_map, const google::protobuf::RepeatedPtrField< common::ModelBlob > &model_blobs)
Definition model_util.cc:32
Inference * CreateInferenceByName(const std::string &frame_work, const std::string &proto_file, const std::string &weight_file, const std::vector< std::string > &outputs, const std::vector< std::string > &inputs, const std::string &model_root)
std::string GetModelFile(const std::string &model_name, const std::string &file_name)
Get the model file path by model path and file name
Definition util.cc:55
std::string GetConfigFile(const std::string &config_path, const std::string &config_file)
Definition util.cc:80
std::string GetModelPath(const std::string &model_name)
Get the model path by model name, search from APOLLO_MODEL_PATH
Definition util.cc:44

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