Skip to content

Commit ef8b145

Browse files
author
Takahisa.Ishikawa
committed
style(autoware_traffic_light_map_based_detector): wrap long lines after rename
Wrap lines that exceeded the 100-character limit after renaming functions to snake_case, fixing cpplint failures in CI. Signed-off-by: Takahisa.Ishikawa <takahisa.ishikawa@tier4.jp>
1 parent 687227d commit ef8b145

4 files changed

Lines changed: 16 additions & 8 deletions

File tree

perception/autoware_traffic_light_map_based_detector/src/traffic_light_map_based_detector.cpp

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -307,7 +307,8 @@ bool TrafficLightMapBasedDetector::get_traffic_light_roi(
307307
}
308308
// enlarged target position in camera coordinate
309309
{
310-
cv::Point2d point2d = utils::calc_raw_image_point_from_point_3d(pinhole_camera_model, point3d);
310+
cv::Point2d point2d =
311+
utils::calc_raw_image_point_from_point_3d(pinhole_camera_model, point3d);
311312
utils::round_in_image_frame(
312313
pinhole_camera_model.cameraInfo().width, pinhole_camera_model.cameraInfo().height, point2d);
313314
roi.roi.x_offset = point2d.x;
@@ -329,7 +330,8 @@ bool TrafficLightMapBasedDetector::get_traffic_light_roi(
329330
}
330331
// enlarged target position in camera coordinate
331332
{
332-
cv::Point2d point2d = utils::calc_raw_image_point_from_point_3d(pinhole_camera_model, point3d);
333+
cv::Point2d point2d =
334+
utils::calc_raw_image_point_from_point_3d(pinhole_camera_model, point3d);
333335
utils::round_in_image_frame(
334336
pinhole_camera_model.cameraInfo().width, pinhole_camera_model.cameraInfo().height, point2d);
335337
roi.roi.width = point2d.x - roi.roi.x_offset;

perception/autoware_traffic_light_map_based_detector/src/traffic_light_map_based_detector_process.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -57,7 +57,8 @@ bool is_in_distance_range(
5757
return sq_dist < (max_distance_range * max_distance_range);
5858
}
5959

60-
bool is_in_angle_range(const double & tl_yaw, const double & camera_yaw, const double max_angle_range)
60+
bool is_in_angle_range(
61+
const double & tl_yaw, const double & camera_yaw, const double max_angle_range)
6162
{
6263
Eigen::Vector2d vec1, vec2;
6364
vec1 << std::cos(tl_yaw), std::sin(tl_yaw);

perception/autoware_traffic_light_map_based_detector/src/traffic_light_map_based_detector_process.hpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -48,7 +48,8 @@ void round_in_image_frame(const uint32_t & width, const uint32_t & height, cv::P
4848
bool is_in_distance_range(
4949
const tf2::Vector3 & p1, const tf2::Vector3 & p2, const double max_distance_range);
5050

51-
bool is_in_angle_range(const double & tl_yaw, const double & camera_yaw, const double max_angle_range);
51+
bool is_in_angle_range(
52+
const double & tl_yaw, const double & camera_yaw, const double max_angle_range);
5253

5354
bool is_in_image_frame(
5455
const image_geometry::PinholeCameraModel & pinhole_camera_model, const tf2::Vector3 & point);

perception/autoware_traffic_light_map_based_detector/test/test_utils.cpp

Lines changed: 8 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -57,7 +57,8 @@ TEST(IsInDistanceRangeTest, InRange)
5757
const tf2::Vector3 v1(1.0, 1.0, 3.0);
5858
const tf2::Vector3 v2(4.0, 5.0, 6.0);
5959
const double max_distance_range = 6.0;
60-
const bool result = autoware::traffic_light::utils::is_in_distance_range(v1, v2, max_distance_range);
60+
const bool result =
61+
autoware::traffic_light::utils::is_in_distance_range(v1, v2, max_distance_range);
6162
EXPECT_TRUE(result);
6263
}
6364

@@ -66,7 +67,8 @@ TEST(IsInDistanceRangeTest, OutOfRange)
6667
const tf2::Vector3 v1(1.0, 1.0, 3.0);
6768
const tf2::Vector3 v2(4.0, 5.0, 6.0);
6869
const double max_distance_range = 5.0;
69-
const bool result = autoware::traffic_light::utils::is_in_distance_range(v1, v2, max_distance_range);
70+
const bool result =
71+
autoware::traffic_light::utils::is_in_distance_range(v1, v2, max_distance_range);
7072
EXPECT_FALSE(result);
7173
}
7274

@@ -85,7 +87,8 @@ TEST(IsInAngleRangeTest, OutOfRange)
8587
const double tl_yaw = M_PI / 2;
8688
const double camera_yaw = M_PI;
8789
const double max_angle_range = M_PI / 4;
88-
bool result = autoware::traffic_light::utils::is_in_angle_range(tl_yaw, camera_yaw, max_angle_range);
90+
bool result =
91+
autoware::traffic_light::utils::is_in_angle_range(tl_yaw, camera_yaw, max_angle_range);
8992
EXPECT_FALSE(result);
9093
}
9194

@@ -94,7 +97,8 @@ TEST(IsInAngleRangeTest, InRangeBoundary)
9497
const double tl_yaw = M_PI - M_PI / 16;
9598
const double camera_yaw = -M_PI + M_PI / 16;
9699
const double max_angle_range = M_PI / 4;
97-
bool result = autoware::traffic_light::utils::is_in_angle_range(tl_yaw, camera_yaw, max_angle_range);
100+
bool result =
101+
autoware::traffic_light::utils::is_in_angle_range(tl_yaw, camera_yaw, max_angle_range);
98102
EXPECT_TRUE(result);
99103
}
100104

0 commit comments

Comments
 (0)