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

#include <singlestage_transformer.h>

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

Public 成员函数

 SingleStageTransformer ()=default
 
virtual ~SingleStageTransformer ()=default
 
bool Init (const TransformerInitOptions &options=TransformerInitOptions()) override
 Init transformer by setting parameters
 
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)
 

详细描述

在文件 singlestage_transformer.h43 行定义.

构造及析构函数说明

◆ SingleStageTransformer()

apollo::perception::camera::SingleStageTransformer::SingleStageTransformer ( )
default

◆ ~SingleStageTransformer()

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

成员函数说明

◆ Init()

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

Init transformer by setting parameters

参数
options
返回
true
false

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

在文件 singlestage_transformer.cc40 行定义.

40 {
41 std::string config_file =
42 GetConfigFile(options.config_path, options.config_file);
43
44 if (!cyber::common::GetProtoFromFile(config_file, &singlestage_param_)) {
45 AERROR << "Read config failed: " << config_file;
46 return false;
47 }
48 AINFO << "Load transformer parameters from " << config_file
49 << " \nmin dimension: " << singlestage_param_.min_dimension_val()
50 << " \ndo template search: " << singlestage_param_.check_dimension();
51
52 return true;
53}
#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::SingleStageTransformer::Name ( ) const
inlineoverridevirtual

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

在文件 singlestage_transformer.h66 行定义.

66{ return "SingleStageTransformer"; }

◆ Transform()

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

transform 2D detections to 3D bounding box

参数
framecamera frame
返回
true
false

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

在文件 singlestage_transformer.cc101 行定义.

101 {
102 if (frame->detected_objects.empty()) {
103 ADEBUG << "No object input to transformer.";
104 return true;
105 }
106
107 const auto &camera_k_matrix = frame->camera_k_matrix;
108 float k_mat[9] = {0};
109 for (size_t i = 0; i < 3; i++) {
110 size_t i3 = i * 3;
111 for (size_t j = 0; j < 3; j++) {
112 k_mat[i3 + j] = camera_k_matrix(i, j);
113 }
114 }
115 ADEBUG << "Camera k matrix input to transformer: \n"
116 << k_mat[0] << ", " << k_mat[1] << ", " << k_mat[2] << "\n"
117 << k_mat[3] << ", " << k_mat[4] << ", " << k_mat[5] << "\n"
118 << k_mat[6] << ", " << k_mat[7] << ", " << k_mat[8] << "\n";
119 const auto &camera2world_pose = frame->camera2world_pose;
120
121 int height = frame->data_provider->src_height();
122 int width = frame->data_provider->src_width();
123 int nr_transformed_obj = 0;
124 const float PI = algorithm::Constant<float>::PI();
125 for (auto &obj : frame->detected_objects) {
126 if (obj == nullptr) {
127 ADEBUG << "Empty object input to transformer.";
128 continue;
129 }
130
131 // set object mapper options
132 float theta_ray = atan2(obj->camera_supplement.local_center[0],
133 obj->camera_supplement.local_center[2]);
134
135 // process
136 float object_center[3] = {obj->camera_supplement.local_center[0],
137 obj->camera_supplement.local_center[1],
138 obj->camera_supplement.local_center[2]};
139 float dimension_hwl[3] = {obj->size(2), obj->size(1), obj->size(0)};
140 float rotation_y =
141 theta_ray + static_cast<float>(obj->camera_supplement.alpha);
142 if (rotation_y < -PI) {
143 rotation_y += 2 * PI;
144 } else if (rotation_y >= PI) {
145 rotation_y -= 2 * PI;
146 }
147
148 // adjust center point
149 float bbox[4] = {0};
150 bbox[0] = obj->camera_supplement.box.xmin;
151 bbox[1] = obj->camera_supplement.box.ymin;
152 bbox[2] = obj->camera_supplement.box.xmax;
153 bbox[3] = obj->camera_supplement.box.ymax;
154 float center2d[3] = {0};
155
156 CenterPointFromBbox(bbox, dimension_hwl, rotation_y, object_center,
157 center2d, k_mat, height, width);
158 // fill back results
159 FillResults(object_center, dimension_hwl, rotation_y, camera2world_pose,
160 theta_ray, obj);
161
162 ++nr_transformed_obj;
163 }
164 return nr_transformed_obj > 0;
165}
#define ADEBUG
Definition log.h:41
uint32_t height
Height of point cloud
uint32_t width
Width of point cloud
#define PI

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