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

#include <bevformer_obstacle_detector.h>

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

Public 成员函数

 BEVFORMERObstacleDetector ()=default
 
virtual ~BEVFORMERObstacleDetector ()=default
 
bool Init (const ObstacleDetectorInitOptions &options=ObstacleDetectorInitOptions()) override
 Init ObstacleDetector constructor.
 
bool Detect (CameraFrame *frame) override
 Get obstacles detection result
 
std::string Name () const override
 Interface for obstacle detector name
 
- Public 成员函数 继承自 apollo::perception::camera::BaseObstacleDetector
 BaseObstacleDetector ()=default
 
virtual ~BaseObstacleDetector ()=default
 
virtual bool InitNetwork (const common::ModelInfo &model_info, const std::string &model_root)
 Interface for network initialization
 
 BaseObstacleDetector ()=default
 
virtual ~BaseObstacleDetector ()=default
 
virtual bool InitNetwork (const common::ModelInfo &model_info, const std::string &model_root)
 Interface for network initialization
 
 BaseObstacleDetector ()=default
 
virtual ~BaseObstacleDetector ()=default
 
virtual bool Detect (onboard::CameraFrame *frame)=0
 Interface for obstacle detector main part
 
virtual bool InitNetwork (const common::ModelInfo &model_info, const std::string &model_root)
 Interface for network initialization
 

额外继承的成员函数

- Protected 成员函数 继承自 apollo::perception::camera::BaseObstacleDetector
 DISALLOW_COPY_AND_ASSIGN (BaseObstacleDetector)
 
 DISALLOW_COPY_AND_ASSIGN (BaseObstacleDetector)
 
 DISALLOW_COPY_AND_ASSIGN (BaseObstacleDetector)
 
- Protected 属性 继承自 apollo::perception::camera::BaseObstacleDetector
int gpu_id_ = 0
 
std::shared_ptr< inference::Inferencenet_
 

详细描述

在文件 bevformer_obstacle_detector.h40 行定义.

构造及析构函数说明

◆ BEVFORMERObstacleDetector()

apollo::perception::camera::BEVFORMERObstacleDetector::BEVFORMERObstacleDetector ( )
default

◆ ~BEVFORMERObstacleDetector()

virtual apollo::perception::camera::BEVFORMERObstacleDetector::~BEVFORMERObstacleDetector ( )
virtualdefault

成员函数说明

◆ Detect()

bool apollo::perception::camera::BEVFORMERObstacleDetector::Detect ( CameraFrame frame)
overridevirtual

Get obstacles detection result

参数
framecamera frame
返回
true
false

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

在文件 bevformer_obstacle_detector.cc571 行定义.

571 {
572 if (frame == nullptr) {
573 return false;
574 }
575 // AERROR << "current time is " << std::to_string(frame->timestamp);
576
577 auto model_inputs = model_param_.info().inputs();
578 auto input_blob_img = net_->get_blob(model_inputs[0].name());
579 auto input_blob_prev_bev = net_->get_blob(model_inputs[1].name());
580 auto input_blob_use_prev_bev = net_->get_blob(model_inputs[2].name());
581 auto input_blob_can_bus = net_->get_blob(model_inputs[3].name());
582 auto input_blob_lidar2img = net_->get_blob(model_inputs[4].name());
583 auto input_blob_no_pad_image_shape = net_->get_blob(model_inputs[5].name());
584 auto model_outputs = model_param_.info().outputs();
585
586 PERF_BLOCK("stage bev process")
587 memcpy(input_blob_no_pad_image_shape->mutable_cpu_data(),
588 no_pad_image_shape_.data(),
589 sizeof(float) * no_pad_image_shape_.size());
590 ImageExtrinsicPreprocess(frame, input_blob_lidar2img);
591 ImagePreprocessGPU(frame, input_blob_img);
592 FillCanBus(frame, input_blob_can_bus);
593 memcpy(input_blob_use_prev_bev->mutable_cpu_data(), use_prev_bev_,
594 sizeof(float));
595 if (*use_prev_bev_) {
596 auto bev_embed = net_->get_blob(model_outputs[0].name());
597 cudaMemcpy(input_blob_prev_bev->mutable_gpu_data(), bev_embed->gpu_data(),
598 prev_bev_size_ * sizeof(float), cudaMemcpyHostToDevice);
599 }
601
602 PERF_BLOCK("stage bev infer")
603 net_->Infer();
605
606 PERF_BLOCK("stage bev get objects")
607 auto outputs_classes = net_->get_blob(model_outputs[1].name());
608 auto outputs_coords = net_->get_blob(model_outputs[2].name());
609 const float *outputs_classes_ptr = outputs_classes->cpu_data();
610 const float *outputs_coords_ptr = outputs_coords->cpu_data();
611 GetObjects(frame, outputs_classes_ptr, outputs_coords_ptr,
612 &frame->detected_objects);
614
615 PERF_BLOCK("stage bev get occ")
616 if (model_param_.save_occ_result()) {
617 auto outputs_occupancy =
618 net_->get_blob(model_outputs[occ_blob_index_].name());
619 const float *outputs_occupancy_ptr = outputs_occupancy->cpu_data();
620 GetOccResults(frame, outputs_occupancy_ptr);
621 }
623
624 Nuscenes2Apollo(&frame->detected_objects);
625 *use_prev_bev_ = 1.0;
626 return true;
627}
std::shared_ptr< inference::Inference > net_
#define PERF_BLOCK_END
Definition profiler.h:53
#define PERF_BLOCK(...)
Definition profiler.h:52

◆ Init()

bool apollo::perception::camera::BEVFORMERObstacleDetector::Init ( const ObstacleDetectorInitOptions options = ObstacleDetectorInitOptions())
overridevirtual

Init ObstacleDetector constructor.

参数
optionsthe option object of obstacle
返回
true
false

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

在文件 bevformer_obstacle_detector.cc117 行定义.

118 {
119 options_ = options;
120 gpu_id_ = options.gpu_id;
121 BASE_GPU_CHECK(cudaSetDevice(gpu_id_));
122 BASE_GPU_CHECK(cudaStreamCreate(&stream_));
123
124 std::string config_file =
125 GetConfigFile(options_.config_path, options_.config_file);
126 std::cout << " config file is " << config_file << std::endl;
127 if (!cyber::common::GetProtoFromFile(config_file, &model_param_)) {
128 AERROR << "Read model param failed!";
129 return false;
130 }
131
132 InitTypes(model_param_);
133 InitImageSize(model_param_);
134
135 common::Normalize normalize = model_param_.normalize();
136 mean_bgr_ = {normalize.mean()[0], normalize.mean()[1], normalize.mean()[2]};
137 std_bgr_ = {normalize.std()[0], normalize.std()[1], normalize.std()[2]};
138
139 const auto &model_info = model_param_.info();
140 std::string model_path = GetModelPath(model_info.name());
141
142 if (!InitNetwork(model_param_.info(), model_path)) {
143 AERROR << "Init network failed!";
144 return false;
145 }
146 std::cout << "bevformer model init success from "
147 << model_info.proto_file().file() << std::endl;
148
149 auto model_outputs = model_param_.info().outputs();
150 num_decoder_layer_ = model_outputs[1].shape()[0];
151 num_queries_ = model_outputs[1].shape()[2];
152 num_classes_det_ = model_outputs[1].shape()[3];
153 code_size_ = model_outputs[2].shape()[3];
154 class_blob_start_index_ =
155 (num_decoder_layer_ - 1) * num_queries_ * num_classes_det_;
156 class_blob_end_index_ =
157 (num_decoder_layer_)*num_queries_ * num_classes_det_;
158 box_blob_start_index_ =
159 (num_decoder_layer_ - 1) * num_queries_ * code_size_;
160 AINFO << "number of decoder layer:" << num_decoder_layer_
161 << " number of query: " << num_queries_
162 << " number of classes: " << num_classes_det_
163 << " code size: " << code_size_
164 << " class blob start index: " << class_blob_start_index_
165 << " class blob end index: " << class_blob_end_index_
166 << " box blob start index: " << box_blob_start_index_;
167
168 num_voxels_ = model_outputs[occ_blob_index_].shape()[1];
169 num_classes_occ_ = model_outputs[occ_blob_index_].shape()[2];
170 AINFO << " number of occ voxels " << num_voxels_
171 << " number of occ classes " << num_classes_occ_;
172 occ_xmin_ = model_param_.occ_xmin();
173 occ_xmax_ = model_param_.occ_xmax();
174 occ_ymin_ = model_param_.occ_ymin();
175 occ_ymax_ = model_param_.occ_ymax();
176 occ_zmin_ = model_param_.occ_zmin();
177 occ_zmax_ = model_param_.occ_zmax();
178 voxel_size_ = model_param_.voxel_size();
179 occ_x_grid_ = (occ_xmax_ - occ_xmin_) / voxel_size_;
180 occ_y_grid_ = (occ_ymax_ - occ_ymin_) / voxel_size_;
181 occ_z_grid_ = (occ_zmax_ - occ_zmin_) / voxel_size_;
182
183
184 auto model_inputs = model_param_.info().inputs();
185 auto prev_bev_shape = model_inputs[1].shape();
186 for (auto size : prev_bev_shape) {
187 prev_bev_size_ *= size;
188 }
189 use_prev_bev_ = new float(0.0);
190
191 float no_pad_image_width = model_param_.no_pad_image_width();
192 float no_pad_image_height = model_param_.no_pad_image_height();
193 CHECK(no_pad_image_width <= model_inputs[0].shape()[3]);
194 CHECK(no_pad_image_height <= model_inputs[0].shape()[4]);
195 no_pad_image_shape_[0] = no_pad_image_width;
196 no_pad_image_shape_[1] = no_pad_image_height;
197 occ_threshold_ = model_param_.occ_threshold();
198
199 trans_wrapper_.reset(new onboard::TransformWrapper());
200 // tf_camera_frame_id
201 trans_wrapper_->Init("CAM_FRONT");
202 return true;
203}
virtual bool InitNetwork(const common::ModelInfo &model_info, const std::string &model_root)
Interface for network initialization
#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::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

◆ Name()

std::string apollo::perception::camera::BEVFORMERObstacleDetector::Name ( ) const
inlineoverridevirtual

Interface for obstacle detector name

返回
std::string

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

在文件 bevformer_obstacle_detector.h62 行定义.

62{ return "BEVObstacleDetector"; }

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