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

#include <multicue_transformer.h>

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

Public 成员函数

 MultiCueTransformer ()=default
 
virtual ~MultiCueTransformer ()=default
 
bool Init (const TransformerInitOptions &options=TransformerInitOptions()) override
 Init for ObjectTemplate and Object map
 
bool Transform (onboard::CameraFrame *frame) override
 Transform 2D detections to 3D bounding box
 
std::string Name () const override
 
- Public 成员函数 继承自 apollo::perception::camera::BaseTransformer
 BaseTransformer ()=default
 
virtual ~BaseTransformer ()=default
 
 DISALLOW_COPY_AND_ASSIGN (BaseTransformer)
 

Protected 属性

ObjectTemplateManagerobject_template_manager_ = nullptr
 

详细描述

在文件 multicue_transformer.h35 行定义.

构造及析构函数说明

◆ MultiCueTransformer()

apollo::perception::camera::MultiCueTransformer::MultiCueTransformer ( )
default

◆ ~MultiCueTransformer()

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

成员函数说明

◆ Init()

bool apollo::perception::camera::MultiCueTransformer::Init ( const TransformerInitOptions options = TransformerInitOptions())
overridevirtual

Init for ObjectTemplate and Object map

参数
optionsconfiguration for object template and object map
返回
true
false

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

在文件 multicue_transformer.cc32 行定义.

32 {
33 std::string config_file =
34 GetConfigFile(options.config_path, options.config_file);
35
36 if (!cyber::common::GetProtoFromFile(config_file, &multicue_param_)) {
37 AERROR << "Read config failed: " << config_file;
38 return false;
39 }
40 AINFO << multicue_param_.DebugString();
41
42 // Init object template
43 object_template_manager_ = ObjectTemplateManager::Instance();
45 mapper_.reset(new ObjMapper);
46
47 return true;
48}
#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::string GetConfigFile(const std::string &config_path, const std::string &config_file)
Definition util.cc:80

◆ Name()

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

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

在文件 multicue_transformer.h59 行定义.

59{ return "MultiCueTransformer"; }

◆ Transform()

bool apollo::perception::camera::MultiCueTransformer::Transform ( onboard::CameraFrame frame)
overridevirtual

Transform 2D detections to 3D bounding box

参数
frameinput camera frame
返回
true
false

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

在文件 multicue_transformer.cc223 行定义.

223 {
224 if (frame->detected_objects.empty()) {
225 ADEBUG << "No object input to transformer.";
226 return true;
227 }
228
229 const auto &camera_k_matrix = frame->camera_k_matrix;
230 float k_mat[9] = {0};
231 for (size_t i = 0; i < 3; ++i) {
232 for (size_t j = 0; j < 3; ++j) {
233 k_mat[i * 3 + j] = camera_k_matrix(i, j);
234 }
235 }
236 ADEBUG << "Camera k matrix input to transformer: \n"
237 << k_mat[0] << ", " << k_mat[1] << ", " << k_mat[2] << "\n"
238 << k_mat[3] << ", " << k_mat[4] << ", " << k_mat[5] << "\n"
239 << k_mat[6] << ", " << k_mat[7] << ", " << k_mat[8] << "\n";
240
241 const int width_image = frame->data_provider->src_width();
242 const int height_image = frame->data_provider->src_height();
243 const auto &camera2world_pose = frame->camera2world_pose;
244 mapper_->Init(k_mat, width_image, height_image);
245
246 ObjMapperOptions obj_mapper_options;
247 float object_center[3] = {0};
248 float dimension_hwl[3] = {0};
249 float rotation_y = 0.0f;
250 int nr_transformed_obj = 0;
251
252 for (auto &obj : frame->detected_objects) {
253 if (obj == nullptr) {
254 ADEBUG << "Empty object input to transformer.";
255 continue;
256 }
257
258 // set object mapper options
259 float theta_ray = 0.0f;
260 SetObjMapperOptions(obj, camera_k_matrix, width_image, height_image,
261 &obj_mapper_options, &theta_ray);
262
263 // process
264 mapper_->Solve3dBbox(obj_mapper_options, object_center, dimension_hwl,
265 &rotation_y);
266
267 // fill back results
268 FillResults(object_center, dimension_hwl, rotation_y, camera2world_pose,
269 theta_ray, obj);
270
271 ++nr_transformed_obj;
272 }
273
274 return nr_transformed_obj > 0;
275}
#define ADEBUG
Definition log.h:41

类成员变量说明

◆ object_template_manager_

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

在文件 multicue_transformer.h77 行定义.


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