Skip to content

Commit

Permalink
fix variable names
Browse files Browse the repository at this point in the history
Signed-off-by: a-maumau <[email protected]>
  • Loading branch information
a-maumau committed Dec 20, 2024
1 parent edce9da commit 542ed48
Showing 1 changed file with 14 additions and 11 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -51,14 +51,17 @@ CameraProjection::CameraProjection(
const double ocy = static_cast<double>(camera_info.k.at(5));
// for checking pincushion shape case
const cv::Point3d ray_top_left = camera_model_.projectPixelTo3dRay(cv::Point(0, 0));
const cv::Point3d ray_top_right = camera_model_.projectPixelTo3dRay(cv::Point(image_width_ - 1, 0));
const cv::Point3d ray_bottom_left = camera_model_.projectPixelTo3dRay(cv::Point(0, image_height_ - 1));
const cv::Point3d ray_top_right =
camera_model_.projectPixelTo3dRay(cv::Point(image_width_ - 1, 0));
const cv::Point3d ray_bottom_left =
camera_model_.projectPixelTo3dRay(cv::Point(0, image_height_ - 1));
const cv::Point3d ray_bottom_right =
camera_model_.projectPixelTo3dRay(cv::Point(image_width_ - 1, image_height_ - 1));
// for checking barrel shape case
const cv::Point3d ray_mid_top = camera_model_.projectPixelTo3dRay(cv::Point(ocx, 0));
const cv::Point3d ray_mid_left = camera_model_.projectPixelTo3dRay(cv::Point(0, ocy));
const cv::Point3d ray_mid_right = camera_model_.projectPixelTo3dRay(cv::Point(image_width_ - 1, ocy));
const cv::Point3d ray_mid_right =
camera_model_.projectPixelTo3dRay(cv::Point(image_width_ - 1, ocy));
const cv::Point3d ray_mid_bottom =
camera_model_.projectPixelTo3dRay(cv::Point(ocx, image_height_ - 1));

Expand Down Expand Up @@ -137,11 +140,11 @@ void CameraProjection::initializeCache()
for (int idx_y = 0; idx_y < grid_height_; idx_y++) {
for (int idx_x = 0; idx_x < grid_width_; idx_x++) {
const uint32_t grid_index = idx_y * grid_width_ + idx_x;
const float qx = (idx_x + 0.5f) * cell_width_;
const float qy = (idx_y + 0.5f) * cell_height_;
const float px = (idx_x + 0.5f) * cell_width_;
const float py = (idx_y + 0.5f) * cell_height_;

Check warning on line 144 in perception/autoware_image_projection_based_fusion/src/camera_projection.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_image_projection_based_fusion/src/camera_projection.cpp#L142-L144

Added lines #L142 - L144 were not covered by tests

// precompute projected point
cv::Point2d raw_image_point = camera_model_.unrectifyPoint(cv::Point2d(qx, qy));
cv::Point2d raw_image_point = camera_model_.unrectifyPoint(cv::Point2d(px, py));
projection_cache_[grid_index] =
PixelPos{static_cast<float>(raw_image_point.x), static_cast<float>(raw_image_point.y)};

Check warning on line 149 in perception/autoware_image_projection_based_fusion/src/camera_projection.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_image_projection_based_fusion/src/camera_projection.cpp#L147-L149

Added lines #L147 - L149 were not covered by tests
}
Expand All @@ -158,8 +161,8 @@ bool CameraProjection::calcRectifiedImageProjectedPoint(
const cv::Point2d rectified_image_point = camera_model_.project3dToPixel(point3d);

Check warning on line 161 in perception/autoware_image_projection_based_fusion/src/camera_projection.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_image_projection_based_fusion/src/camera_projection.cpp#L161

Added line #L161 was not covered by tests

if (

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

View check run for this annotation

Codecov / codecov/patch

perception/autoware_image_projection_based_fusion/src/camera_projection.cpp#L163

Added line #L163 was not covered by tests
rectified_image_point.x < 0.0 || rectified_image_point.x >= image_w_ ||
rectified_image_point.y < 0.0 || rectified_image_point.y >= image_h_) {
rectified_image_point.x < 0.0 || rectified_image_point.x >= image_width_ ||
rectified_image_point.y < 0.0 || rectified_image_point.y >= image_height_) {

Check warning on line 165 in perception/autoware_image_projection_based_fusion/src/camera_projection.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Complex Conditional

CameraProjection::calcRectifiedImageProjectedPoint has 1 complex conditionals with 3 branches, threshold = 2. A complex conditional is an expression inside a branch (e.g. if, for, while) which consists of multiple, logical operators such as AND/OR. The more logical operators in an expression, the more severe the code smell.
return false;
} else {
projected_point << rectified_image_point.x, rectified_image_point.y;
Expand All @@ -178,8 +181,8 @@ bool CameraProjection::calcRawImageProjectedPoint(
const cv::Point2d raw_image_point = camera_model_.unrectifyPoint(rectified_image_point);

Check warning on line 181 in perception/autoware_image_projection_based_fusion/src/camera_projection.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_image_projection_based_fusion/src/camera_projection.cpp#L180-L181

Added lines #L180 - L181 were not covered by tests

if (

Check warning on line 183 in perception/autoware_image_projection_based_fusion/src/camera_projection.cpp

View check run for this annotation

Codecov / codecov/patch

perception/autoware_image_projection_based_fusion/src/camera_projection.cpp#L183

Added line #L183 was not covered by tests
rectified_image_point.x < 0.0 || rectified_image_point.x >= image_w_ ||
rectified_image_point.y < 0.0 || rectified_image_point.y >= image_h_) {
rectified_image_point.x < 0.0 || rectified_image_point.x >= image_width_ ||
rectified_image_point.y < 0.0 || rectified_image_point.y >= image_height_) {

Check warning on line 185 in perception/autoware_image_projection_based_fusion/src/camera_projection.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ New issue: Complex Conditional

CameraProjection::calcRawImageProjectedPoint has 1 complex conditionals with 3 branches, threshold = 2. A complex conditional is an expression inside a branch (e.g. if, for, while) which consists of multiple, logical operators such as AND/OR. The more logical operators in an expression, the more severe the code smell.
return false;
} else {
projected_point << raw_image_point.x, raw_image_point.y;
Expand Down

0 comments on commit 542ed48

Please sign in to comment.