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

#include <location_refiner_postprocessor.h>

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

Public 成员函数

 LocationRefinerPostprocessor ()
 
virtual ~LocationRefinerPostprocessor ()=default
 
bool Init (const PostprocessorInitOptions &options=PostprocessorInitOptions()) override
 : set location refiner param
 
bool Process (const PostprocessorOptions &options, onboard::CameraFrame *frame) override
 post refine location of 3D obstacles
 
std::string Name () const override
 
- Public 成员函数 继承自 apollo::perception::camera::BasePostprocessor
 BasePostprocessor ()=default
 
virtual ~BasePostprocessor ()=default
 
 DISALLOW_COPY_AND_ASSIGN (BasePostprocessor)
 

详细描述

在文件 location_refiner_postprocessor.h31 行定义.

构造及析构函数说明

◆ LocationRefinerPostprocessor()

apollo::perception::camera::LocationRefinerPostprocessor::LocationRefinerPostprocessor ( )

在文件 location_refiner_postprocessor.cc29 行定义.

29 {
30 postprocessor_.reset(new ObjPostProcessor);
31}

◆ ~LocationRefinerPostprocessor()

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

成员函数说明

◆ Init()

bool apollo::perception::camera::LocationRefinerPostprocessor::Init ( const PostprocessorInitOptions options = PostprocessorInitOptions())
overridevirtual

: set location refiner param

参数
options
返回
true
false

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

在文件 location_refiner_postprocessor.cc33 行定义.

34 {
35 std::string config_file =
36 GetConfigFile(options.config_path, options.config_file);
37
38 if (!cyber::common::GetProtoFromFile(config_file, &location_refiner_param_)) {
39 AERROR << "Read config failed: " << config_file;
40 return false;
41 }
42
43 calibration_service_ = options.calibration_service;
44 ACHECK(calibration_service_ != nullptr);
45 return true;
46}
#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

◆ Name()

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

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

在文件 location_refiner_postprocessor.h56 行定义.

56{ return "LocationRefinerPostprocessor"; }

◆ Process()

bool apollo::perception::camera::LocationRefinerPostprocessor::Process ( const PostprocessorOptions options,
onboard::CameraFrame frame 
)
overridevirtual

post refine location of 3D obstacles

参数
optionsoptions for post refine
frame
返回
true
false

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

在文件 location_refiner_postprocessor.cc48 行定义.

49 {
50 if (frame->detected_objects.empty() ||
51 !options.do_refinement_with_calibration_service) {
52 ADEBUG << "Do not run obstacle postprocessor.";
53 return true;
54 }
55
56 Eigen::Vector4d plane;
57 if (!calibration_service_->QueryGroundPlaneInCameraFrame(&plane)) {
58 AINFO << "No valid ground plane in the service.";
59 }
60
61 float query_plane[4] = {
62 static_cast<float>(plane(0)), static_cast<float>(plane(1)),
63 static_cast<float>(plane(2)), static_cast<float>(plane(3))};
64
65 const auto &camera_k_matrix = frame->camera_k_matrix;
66 float k_mat[9] = {0};
67 for (size_t i = 0; i < 3; ++i) {
68 for (size_t j = 0; j < 3; ++j) {
69 k_mat[i * 3 + j] = camera_k_matrix(i, j);
70 }
71 }
72 AINFO << "Camera k matrix input to obstacle postprocessor: \n"
73 << k_mat[0] << ", " << k_mat[1] << ", " << k_mat[2] << "\n"
74 << k_mat[3] << ", " << k_mat[4] << ", " << k_mat[5] << "\n"
75 << k_mat[6] << ", " << k_mat[7] << ", " << k_mat[8] << "\n";
76
77 const int width_image = frame->data_provider->src_width();
78 const int height_image = frame->data_provider->src_height();
79 postprocessor_->Init(k_mat, width_image, height_image);
80
81 ObjPostProcessorOptions obj_postprocessor_options;
82 int nr_valid_obj = 0;
83
84 for (auto &obj : frame->detected_objects) {
85 ++nr_valid_obj;
86 float object_center[3] = {obj->camera_supplement.local_center(0),
87 obj->camera_supplement.local_center(1),
88 obj->camera_supplement.local_center(2)};
89 float bbox2d[4] = {
90 obj->camera_supplement.box.xmin, obj->camera_supplement.box.ymin,
91 obj->camera_supplement.box.xmax, obj->camera_supplement.box.ymax};
92
93 float bottom_center[2] = {(bbox2d[0] + bbox2d[2]) / 2, bbox2d[3]};
94 float h_down = (static_cast<float>(height_image) - k_mat[5]) *
95 location_refiner_param_.roi_h2bottom_scale();
96 bool is_in_rule_roi =
97 is_in_roi(bottom_center, static_cast<float>(width_image),
98 static_cast<float>(height_image), k_mat[5], h_down);
99 float dist2camera = algorithm::ISqrt(algorithm::ISqr(object_center[0]) +
100 algorithm::ISqr(object_center[2]));
101
102 if (dist2camera > location_refiner_param_.min_dist_to_camera() ||
103 !is_in_rule_roi) {
104 ADEBUG << "Pass for obstacle postprocessor.";
105 continue;
106 }
107
108 float dimension_hwl[3] = {obj->size(2), obj->size(1), obj->size(0)};
109 float box_cent_x = (bbox2d[0] + bbox2d[2]) / 2;
110 Eigen::Vector3f image_point_low_center(box_cent_x, bbox2d[3], 1);
111 Eigen::Vector3f point_in_camera =
112 static_cast<Eigen::Matrix<float, 3, 1, 0, 3, 1>>(
113 camera_k_matrix.inverse() * image_point_low_center);
114 float theta_ray =
115 static_cast<float>(atan2(point_in_camera.x(), point_in_camera.z()));
116 float rotation_y =
117 theta_ray + static_cast<float>(obj->camera_supplement.alpha);
118
119 // enforce the ry to be in the range [-pi, pi)
120 const float PI = algorithm::Constant<float>::PI();
121 if (rotation_y < -PI) {
122 rotation_y += 2 * PI;
123 } else if (rotation_y >= PI) {
124 rotation_y -= 2 * PI;
125 }
126
127 // process
128 memcpy(obj_postprocessor_options.bbox, bbox2d, sizeof(float) * 4);
129 obj_postprocessor_options.check_lowerbound = true;
130 camera::LineSegment2D<float> line_seg(bbox2d[0], bbox2d[3], bbox2d[2],
131 bbox2d[3]);
132 obj_postprocessor_options.line_segs.push_back(line_seg);
133 memcpy(obj_postprocessor_options.hwl, dimension_hwl, sizeof(float) * 3);
134 obj_postprocessor_options.ry = rotation_y;
135 // refine with calibration service, support ground plane model currently
136 // {0.0f, cos(tilt), -sin(tilt), -camera_ground_height}
137 memcpy(obj_postprocessor_options.plane, query_plane, sizeof(float) * 4);
138
139 // changed to touching-ground center
140 object_center[1] += dimension_hwl[0] / 2;
141 postprocessor_->PostProcessObjWithGround(
142 obj_postprocessor_options, object_center, dimension_hwl, &rotation_y);
143 object_center[1] -= dimension_hwl[0] / 2;
144
145 float z_diff_camera =
146 object_center[2] - obj->camera_supplement.local_center(2);
147
148 // fill back results
149 obj->camera_supplement.local_center(0) = object_center[0];
150 obj->camera_supplement.local_center(1) = object_center[1];
151 obj->camera_supplement.local_center(2) = object_center[2];
152
153 obj->center(0) = static_cast<double>(object_center[0]);
154 obj->center(1) = static_cast<double>(object_center[1]);
155 obj->center(2) = static_cast<double>(object_center[2]);
156 obj->center = frame->camera2world_pose * obj->center;
157
158 AINFO << "diff on camera z: " << z_diff_camera;
159 AINFO << "Obj center from postprocessor: " << obj->center.transpose();
160 }
161
162 return true;
163}
#define ADEBUG
Definition log.h:41
#define AINFO
Definition log.h:42
#define PI

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