Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix(autoware_image_projection_based_fusion): fix bug of fov checker in pointpainting #9637

Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,9 @@ class PointPaintingFusionNode

rclcpp::Publisher<DetectedObjects>::SharedPtr obj_pub_ptr_;

std::vector<double> tan_h_; // horizontal field of view
// horizontal field of view
std::vector<double> fov_left_;
std::vector<double> fov_right_;

int omp_num_threads_{1};
float score_threshold_{0.0};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -159,11 +159,11 @@
sub_ = this->create_subscription<sensor_msgs::msg::PointCloud2>(
"~/input/pointcloud", rclcpp::SensorDataQoS().keep_last(3), sub_callback);

tan_h_.resize(rois_number_);
fov_left_.resize(rois_number_);
fov_right_.resize(rois_number_);

Check warning on line 163 in perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp#L162-L163

Added lines #L162 - L163 were not covered by tests
for (std::size_t roi_i = 0; roi_i < rois_number_; ++roi_i) {
auto fx = camera_info_map_[roi_i].k.at(0);
auto x0 = camera_info_map_[roi_i].k.at(2);
tan_h_[roi_i] = x0 / fx;
fov_left_[roi_i] = 0;
fov_right_[roi_i] = 0;

Check warning on line 166 in perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp#L165-L166

Added lines #L165 - L166 were not covered by tests
}

detection_class_remapper_.setParameters(
Expand Down Expand Up @@ -251,6 +251,15 @@
painted_pointcloud_msg.point_step);
painted_pointcloud_msg.row_step =
static_cast<uint32_t>(painted_pointcloud_msg.data.size() / painted_pointcloud_msg.height);

// update camera fov
for (std::size_t roi_i = 0; roi_i < rois_number_; ++roi_i) {
const auto fx = camera_info_map_[roi_i].k.at(0);
const auto x0 = camera_info_map_[roi_i].k.at(2);
const auto width = camera_info_map_[roi_i].width;
fov_left_[roi_i] = -x0 / fx;
fov_right_[roi_i] = (-x0 + width) / fx;

Check warning on line 261 in perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp#L257-L261

Added lines #L257 - L261 were not covered by tests
}

Check notice on line 262 in perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

ℹ Getting worse: Complex Method

PointPaintingFusionNode::preprocess increases in cyclomatic complexity from 9 to 10, threshold = 9. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.
}

void PointPaintingFusionNode::fuseOnSingleImage(
Expand Down Expand Up @@ -338,9 +347,11 @@
p_y = point_camera.y();
p_z = point_camera.z();

if (p_z <= 0.0 || p_x > (tan_h_.at(image_id) * p_z) || p_x < (-tan_h_.at(image_id) * p_z)) {
continue;
}
/// check if the point is in the camera view
if (p_z <= 0.0) continue;
if (p_x < fov_left_.at(image_id) * p_z) continue;
if (p_x > fov_right_.at(image_id) * p_z) continue;

// project
Eigen::Vector2d projected_point = calcRawImageProjectedPoint(
pinhole_camera_model, cv::Point3d(p_x, p_y, p_z), point_project_to_unrectified_image_);
Expand Down
Loading