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): make optional to consider lens distortion in the point projection #9233

Merged
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 @@ -4,6 +4,7 @@
timeout_ms: 70.0
match_threshold_ms: 50.0
image_buffer_size: 15
point_project_to_unrectified_image: false
debug_mode: false
filter_scope_min_x: -100.0
filter_scope_min_y: -100.0
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -99,6 +99,8 @@ class FusionNode : public rclcpp::Node
tf2_ros::Buffer tf_buffer_;
tf2_ros::TransformListener tf_listener_;

bool point_project_to_unrectified_image_{false};

// camera_info
std::map<std::size_t, sensor_msgs::msg::CameraInfo> camera_info_map_;
std::vector<rclcpp::Subscription<sensor_msgs::msg::CameraInfo>::SharedPtr> camera_info_subs_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,8 @@ struct PointData
bool checkCameraInfo(const sensor_msgs::msg::CameraInfo & camera_info);

Eigen::Vector2d calcRawImageProjectedPoint(
const image_geometry::PinholeCameraModel & pinhole_camera_model, const cv::Point3d & point3d);
const image_geometry::PinholeCameraModel & pinhole_camera_model, const cv::Point3d & point3d,
const bool & unrectify = false);

std::optional<geometry_msgs::msg::TransformStamped> getTransformStamped(
const tf2_ros::Buffer & tf_buffer, const std::string & target_frame_id,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -127,6 +127,8 @@ FusionNode<TargetMsg3D, ObjType, Msg2D>::FusionNode(
debugger_ =
std::make_shared<Debugger>(this, rois_number_, image_buffer_size, input_camera_topics_);
}
point_project_to_unrectified_image_ =
declare_parameter<bool>("point_project_to_unrectified_image");

// initialize debug tool
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -342,8 +342,8 @@ dc | dc dc dc dc ||zc|
continue;
}
// project
Eigen::Vector2d projected_point =
calcRawImageProjectedPoint(pinhole_camera_model, cv::Point3d(p_x, p_y, p_z));
Eigen::Vector2d projected_point = calcRawImageProjectedPoint(
pinhole_camera_model, cv::Point3d(p_x, p_y, p_z), point_project_to_unrectified_image_);

// iterate 2d bbox
for (const auto & feature_object : objects) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -133,8 +133,9 @@
continue;
}

Eigen::Vector2d projected_point =
calcRawImageProjectedPoint(pinhole_camera_model, cv::Point3d(*iter_x, *iter_y, *iter_z));
Eigen::Vector2d projected_point = calcRawImageProjectedPoint(
pinhole_camera_model, cv::Point3d(*iter_x, *iter_y, *iter_z),

Check warning on line 137 in perception/autoware_image_projection_based_fusion/src/roi_cluster_fusion/node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_image_projection_based_fusion/src/roi_cluster_fusion/node.cpp#L137

Added line #L137 was not covered by tests
point_project_to_unrectified_image_);

Check warning on line 138 in perception/autoware_image_projection_based_fusion/src/roi_cluster_fusion/node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

RoiClusterFusionNode::fuseOnSingleImage already has high cyclomatic complexity, and now it increases in Lines of Code from 120 to 121. 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.
if (
0 <= static_cast<int>(projected_point.x()) &&
static_cast<int>(projected_point.x()) <= static_cast<int>(camera_info.width) - 1 &&
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -150,7 +150,8 @@
}

Eigen::Vector2d proj_point = calcRawImageProjectedPoint(
pinhole_camera_model, cv::Point3d(point.x(), point.y(), point.z()));
pinhole_camera_model, cv::Point3d(point.x(), point.y(), point.z()),
point_project_to_unrectified_image_);

Check warning on line 154 in perception/autoware_image_projection_based_fusion/src/roi_detected_object_fusion/node.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

RoiDetectedObjectFusionNode::generateDetectedObjectRoIs already has high cyclomatic complexity, and now it increases in Lines of Code from 74 to 75. 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.

min_x = std::min(proj_point.x(), min_x);
min_y = std::min(proj_point.y(), min_y);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -145,7 +145,8 @@ void RoiPointCloudFusionNode::fuseOnSingleImage(
continue;
}
Eigen::Vector2d projected_point = calcRawImageProjectedPoint(
pinhole_camera_model, cv::Point3d(transformed_x, transformed_y, transformed_z));
pinhole_camera_model, cv::Point3d(transformed_x, transformed_y, transformed_z),
point_project_to_unrectified_image_);
for (std::size_t i = 0; i < output_objs.size(); ++i) {
auto & feature_obj = output_objs.at(i);
const auto & check_roi = feature_obj.feature.roi;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -137,7 +137,8 @@
}

Eigen::Vector2d projected_point = calcRawImageProjectedPoint(
pinhole_camera_model, cv::Point3d(transformed_x, transformed_y, transformed_z));
pinhole_camera_model, cv::Point3d(transformed_x, transformed_y, transformed_z),

Check warning on line 140 in perception/autoware_image_projection_based_fusion/src/segmentation_pointcloud_fusion/node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_image_projection_based_fusion/src/segmentation_pointcloud_fusion/node.cpp#L140

Added line #L140 was not covered by tests
point_project_to_unrectified_image_);

bool is_inside_image = projected_point.x() > 0 && projected_point.x() < camera_info.width &&
projected_point.y() > 0 && projected_point.y() < camera_info.height;
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2022 TIER IV, Inc.

Check warning on line 1 in perception/autoware_image_projection_based_fusion/src/utils/utils.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Overall Code Complexity

This module has a mean cyclomatic complexity of 4.14 across 7 functions. The mean complexity threshold is 4. This file has many conditional statements (e.g. if, for, while) across its implementation, leading to lower code health. Avoid adding more conditionals.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -41,10 +41,14 @@
}

Eigen::Vector2d calcRawImageProjectedPoint(
const image_geometry::PinholeCameraModel & pinhole_camera_model, const cv::Point3d & point3d)
const image_geometry::PinholeCameraModel & pinhole_camera_model, const cv::Point3d & point3d,
const bool & unrectify)
{
const cv::Point2d rectified_image_point = pinhole_camera_model.project3dToPixel(point3d);

if (!unrectify) {
return Eigen::Vector2d(rectified_image_point.x, rectified_image_point.y);
}
const cv::Point2d raw_image_point = pinhole_camera_model.unrectifyPoint(rectified_image_point);

return Eigen::Vector2d(raw_image_point.x, raw_image_point.y);
Expand Down
Loading