Skip to content

Commit 4d6292d

Browse files
interimaddTakahisa.Ishikawa
andauthored
refactor(autoware_traffic_light_map_based_detector): rename functions to snake_case (#12551)
* refactor(autoware_traffic_light_map_based_detector): rename functions to snake_case Rename camelCase function names to snake_case per Autoware coding conventions. Test suite/case names in test_utils.cpp are aligned to PascalCase to match the other test suites in the package and comply with Google Test naming guidance. Signed-off-by: Takahisa.Ishikawa <takahisa.ishikawa@tier4.jp> * 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> --------- Signed-off-by: Takahisa.Ishikawa <takahisa.ishikawa@tier4.jp> Co-authored-by: Takahisa.Ishikawa <takahisa.ishikawa@tier4.jp>
1 parent 54af299 commit 4d6292d

8 files changed

Lines changed: 102 additions & 94 deletions

perception/autoware_traffic_light_map_based_detector/src/traffic_light_map_based_detector.cpp

Lines changed: 30 additions & 28 deletions
Original file line numberDiff line numberDiff line change
@@ -42,10 +42,10 @@ TrafficLightMapBasedDetector::TrafficLightMapBasedDetector(
4242
if (config_.max_detection_range <= 0) {
4343
throw std::invalid_argument("max_detection_range must be positive");
4444
}
45-
setMap(map_msg);
45+
set_map(map_msg);
4646
}
4747

48-
void TrafficLightMapBasedDetector::setMap(const autoware_map_msgs::msg::LaneletMapBin & map_msg)
48+
void TrafficLightMapBasedDetector::set_map(const autoware_map_msgs::msg::LaneletMapBin & map_msg)
4949
{
5050
lanelet_map_ptr_ = autoware::experimental::lanelet2_utils::remove_const(
5151
autoware::experimental::lanelet2_utils::from_autoware_map_msgs(map_msg));
@@ -89,7 +89,7 @@ void TrafficLightMapBasedDetector::setMap(const autoware_map_msgs::msg::LaneletM
8989
std::make_shared<const lanelet::routing::RoutingGraphContainer>(overall_graphs);
9090
}
9191

92-
std::optional<SetRouteError> TrafficLightMapBasedDetector::setRoute(
92+
std::optional<SetRouteError> TrafficLightMapBasedDetector::set_route(
9393
const autoware_planning_msgs::msg::LaneletRoute & route_msg)
9494
{
9595
lanelet::ConstLanelets route_lanelets;
@@ -150,7 +150,7 @@ std::optional<SetRouteError> TrafficLightMapBasedDetector::setRoute(
150150
return std::nullopt;
151151
}
152152

153-
const tf2::Transform & findClosestTransform(
153+
const tf2::Transform & find_closest_transform(
154154
const std::vector<StampedTransform> & samples, const rclcpp::Time & target_time)
155155
{
156156
const auto closest_iter = std::min_element(
@@ -181,18 +181,18 @@ DetectionResult TrafficLightMapBasedDetector::detect(
181181
// Use route traffic lights if available, otherwise all traffic lights
182182
std::vector<lanelet::ConstLineString3d> visible_traffic_lights;
183183
if (route_traffic_lights_ptr_ != nullptr) {
184-
getVisibleTrafficLights(
184+
get_visible_traffic_lights(
185185
*route_traffic_lights_ptr_, tf_map2camera_samples, pinhole_camera_model,
186186
visible_traffic_lights);
187187
} else {
188-
getVisibleTrafficLights(
188+
get_visible_traffic_lights(
189189
*all_traffic_lights_ptr_, tf_map2camera_samples, pinhole_camera_model,
190190
visible_traffic_lights);
191191
}
192192

193193
// set all offset to zero when calculating the expect roi
194194
const tf2::Transform tf_map2camera_closest =
195-
findClosestTransform(tf_map2camera_samples, camera_info.header.stamp);
195+
find_closest_transform(tf_map2camera_samples, camera_info.header.stamp);
196196
TrafficLightMapBasedDetectorConfig expect_roi_config = config_;
197197
expect_roi_config.max_vibration_depth = 0;
198198
expect_roi_config.max_vibration_height = 0;
@@ -202,12 +202,12 @@ DetectionResult TrafficLightMapBasedDetector::detect(
202202

203203
for (const auto & traffic_light : visible_traffic_lights) {
204204
tier4_perception_msgs::msg::TrafficLightRoi rough_roi, expect_roi;
205-
if (!getTrafficLightRoi(
205+
if (!get_traffic_light_roi(
206206
tf_map2camera_closest, pinhole_camera_model, traffic_light, expect_roi_config,
207207
expect_roi)) {
208208
continue;
209209
}
210-
if (!getTrafficLightRoi(
210+
if (!get_traffic_light_roi(
211211
tf_map2camera_samples, pinhole_camera_model, traffic_light, config_, rough_roi)) {
212212
continue;
213213
}
@@ -216,12 +216,12 @@ DetectionResult TrafficLightMapBasedDetector::detect(
216216
}
217217

218218
result.markers =
219-
createTrafficLightMarkers(tf_map2camera_closest, camera_info.header, visible_traffic_lights);
219+
create_traffic_light_markers(tf_map2camera_closest, camera_info.header, visible_traffic_lights);
220220

221221
return result;
222222
}
223223

224-
void TrafficLightMapBasedDetector::getVisibleTrafficLights(
224+
void TrafficLightMapBasedDetector::get_visible_traffic_lights(
225225
const TrafficLightSet & all_traffic_lights,
226226
const std::vector<StampedTransform> & tf_map2camera_samples,
227227
const image_geometry::PinholeCameraModel & pinhole_camera_model,
@@ -248,19 +248,19 @@ void TrafficLightMapBasedDetector::getVisibleTrafficLights(
248248
for (const auto & sample : tf_map2camera_samples) {
249249
const auto & tf_map2camera = sample.transform;
250250
// check distance range
251-
if (!utils::isInDistanceRange(
251+
if (!utils::is_in_distance_range(
252252
traffic_light_center, tf_map2camera.getOrigin(), config_.max_detection_range)) {
253253
continue;
254254
}
255255

256256
// check angle range
257257
// adjust tl_yaw so that perpendicular to ray means 0 angle difference
258-
double traffic_light_yaw = utils::getTrafficLightYaw(traffic_light);
258+
double traffic_light_yaw = utils::get_traffic_light_yaw(traffic_light);
259259
traffic_light_yaw =
260260
autoware_utils::normalize_radian(traffic_light_yaw + M_PI_2); // adjust to perpendicular
261261
// get camera yaw
262-
const double camera_yaw = utils::getCameraYaw(tf_map2camera);
263-
if (!utils::isInAngleRange(traffic_light_yaw, camera_yaw, max_angle_range)) {
262+
const double camera_yaw = utils::get_camera_yaw(tf_map2camera);
263+
if (!utils::is_in_angle_range(traffic_light_yaw, camera_yaw, max_angle_range)) {
264264
continue;
265265
}
266266

@@ -270,8 +270,8 @@ void TrafficLightMapBasedDetector::getVisibleTrafficLights(
270270
tf2::Vector3 bottom_right_camera_optical =
271271
tf_map2camera.inverse() * traffic_light_utils::getTrafficLightBottomRight(traffic_light);
272272
if (
273-
!utils::isInImageFrame(pinhole_camera_model, top_left_camera_optical) &&
274-
!utils::isInImageFrame(pinhole_camera_model, bottom_right_camera_optical)) {
273+
!utils::is_in_image_frame(pinhole_camera_model, top_left_camera_optical) &&
274+
!utils::is_in_image_frame(pinhole_camera_model, bottom_right_camera_optical)) {
275275
continue;
276276
}
277277
visible_traffic_lights.push_back(traffic_light);
@@ -280,7 +280,7 @@ void TrafficLightMapBasedDetector::getVisibleTrafficLights(
280280
}
281281
}
282282

283-
bool TrafficLightMapBasedDetector::getTrafficLightRoi(
283+
bool TrafficLightMapBasedDetector::get_traffic_light_roi(
284284
const tf2::Transform & tf_map2camera,
285285
const image_geometry::PinholeCameraModel & pinhole_camera_model,
286286
const lanelet::ConstLineString3d traffic_light, const TrafficLightMapBasedDetectorConfig & config,
@@ -298,7 +298,7 @@ bool TrafficLightMapBasedDetector::getTrafficLightRoi(
298298
tf2::Vector3 top_left_map = traffic_light_utils::getTrafficLightTopLeft(traffic_light);
299299
tf2::Vector3 top_left_camera_optical = tf_map2camera.inverse() * top_left_map;
300300
// max vibration
301-
tf2::Vector3 margin = utils::getVibrationMargin(
301+
tf2::Vector3 margin = utils::get_vibration_margin(
302302
top_left_camera_optical.z(), config.max_vibration_pitch, config.max_vibration_yaw,
303303
config.max_vibration_height, config.max_vibration_width, config.max_vibration_depth);
304304
tf2::Vector3 point3d = top_left_camera_optical - margin;
@@ -307,8 +307,9 @@ bool TrafficLightMapBasedDetector::getTrafficLightRoi(
307307
}
308308
// enlarged target position in camera coordinate
309309
{
310-
cv::Point2d point2d = utils::calcRawImagePointFromPoint3D(pinhole_camera_model, point3d);
311-
utils::roundInImageFrame(
310+
cv::Point2d point2d =
311+
utils::calc_raw_image_point_from_point_3d(pinhole_camera_model, point3d);
312+
utils::round_in_image_frame(
312313
pinhole_camera_model.cameraInfo().width, pinhole_camera_model.cameraInfo().height, point2d);
313314
roi.roi.x_offset = point2d.x;
314315
roi.roi.y_offset = point2d.y;
@@ -320,7 +321,7 @@ bool TrafficLightMapBasedDetector::getTrafficLightRoi(
320321
tf2::Vector3 bottom_right_map = traffic_light_utils::getTrafficLightBottomRight(traffic_light);
321322
tf2::Vector3 bottom_right_camera_optical = tf_map2camera.inverse() * bottom_right_map;
322323
// max vibration
323-
tf2::Vector3 margin = utils::getVibrationMargin(
324+
tf2::Vector3 margin = utils::get_vibration_margin(
324325
bottom_right_camera_optical.z(), config.max_vibration_pitch, config.max_vibration_yaw,
325326
config.max_vibration_height, config.max_vibration_width, config.max_vibration_depth);
326327
tf2::Vector3 point3d = bottom_right_camera_optical + margin;
@@ -329,8 +330,9 @@ bool TrafficLightMapBasedDetector::getTrafficLightRoi(
329330
}
330331
// enlarged target position in camera coordinate
331332
{
332-
cv::Point2d point2d = utils::calcRawImagePointFromPoint3D(pinhole_camera_model, point3d);
333-
utils::roundInImageFrame(
333+
cv::Point2d point2d =
334+
utils::calc_raw_image_point_from_point_3d(pinhole_camera_model, point3d);
335+
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;
336338
roi.roi.height = point2d.y - roi.roi.y_offset;
@@ -343,7 +345,7 @@ bool TrafficLightMapBasedDetector::getTrafficLightRoi(
343345
return true;
344346
}
345347

346-
bool TrafficLightMapBasedDetector::getTrafficLightRoi(
348+
bool TrafficLightMapBasedDetector::get_traffic_light_roi(
347349
const std::vector<StampedTransform> & tf_map2camera_samples,
348350
const image_geometry::PinholeCameraModel & pinhole_camera_model,
349351
const lanelet::ConstLineString3d traffic_light, const TrafficLightMapBasedDetectorConfig & config,
@@ -353,21 +355,21 @@ bool TrafficLightMapBasedDetector::getTrafficLightRoi(
353355
for (const auto & sample : tf_map2camera_samples) {
354356
const auto & tf_map2camera = sample.transform;
355357
tier4_perception_msgs::msg::TrafficLightRoi roi;
356-
if (getTrafficLightRoi(tf_map2camera, pinhole_camera_model, traffic_light, config, roi)) {
358+
if (get_traffic_light_roi(tf_map2camera, pinhole_camera_model, traffic_light, config, roi)) {
357359
rois.push_back(roi);
358360
}
359361
}
360362
if (rois.empty()) {
361363
return false;
362364
}
363365
out_roi = rois.front();
364-
utils::computeBoundingRoi(
366+
utils::compute_bounding_roi(
365367
pinhole_camera_model.cameraInfo().width, pinhole_camera_model.cameraInfo().height, rois,
366368
out_roi);
367369
return true;
368370
}
369371

370-
visualization_msgs::msg::MarkerArray TrafficLightMapBasedDetector::createTrafficLightMarkers(
372+
visualization_msgs::msg::MarkerArray TrafficLightMapBasedDetector::create_traffic_light_markers(
371373
const tf2::Transform & tf_map2camera, const std_msgs::msg::Header & camera_header,
372374
const std::vector<lanelet::ConstLineString3d> & visible_traffic_lights)
373375
{

perception/autoware_traffic_light_map_based_detector/src/traffic_light_map_based_detector.hpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -89,15 +89,15 @@ class TrafficLightMapBasedDetector
8989
const TrafficLightMapBasedDetectorConfig & config,
9090
const autoware_map_msgs::msg::LaneletMapBin & map_msg);
9191

92-
std::optional<SetRouteError> setRoute(
92+
std::optional<SetRouteError> set_route(
9393
const autoware_planning_msgs::msg::LaneletRoute & route_msg);
9494

9595
DetectionResult detect(
9696
const std::vector<StampedTransform> & tf_map2camera_samples,
9797
const sensor_msgs::msg::CameraInfo & camera_info) const;
9898

9999
private:
100-
void setMap(const autoware_map_msgs::msg::LaneletMapBin & map_msg);
100+
void set_map(const autoware_map_msgs::msg::LaneletMapBin & map_msg);
101101

102102
/**
103103
* @brief Filter traffic lights that are visible from the camera
@@ -107,7 +107,7 @@ class TrafficLightMapBasedDetector
107107
* @param pinhole_camera_model pinhole model calculated from camera_info
108108
* @param visible_traffic_lights the visible traffic lights output
109109
*/
110-
void getVisibleTrafficLights(
110+
void get_visible_traffic_lights(
111111
const TrafficLightSet & all_traffic_lights,
112112
const std::vector<StampedTransform> & tf_map2camera_samples,
113113
const image_geometry::PinholeCameraModel & pinhole_camera_model,
@@ -124,7 +124,7 @@ class TrafficLightMapBasedDetector
124124
* @return true the computation succeeded
125125
* @return false the computation failed
126126
*/
127-
bool getTrafficLightRoi(
127+
bool get_traffic_light_roi(
128128
const tf2::Transform & tf_map2camera,
129129
const image_geometry::PinholeCameraModel & pinhole_camera_model,
130130
const lanelet::ConstLineString3d traffic_light,
@@ -142,7 +142,7 @@ class TrafficLightMapBasedDetector
142142
* @return true the computation succeeded
143143
* @return false the computation failed
144144
*/
145-
bool getTrafficLightRoi(
145+
bool get_traffic_light_roi(
146146
const std::vector<StampedTransform> & tf_map2camera_samples,
147147
const image_geometry::PinholeCameraModel & pinhole_camera_model,
148148
const lanelet::ConstLineString3d traffic_light,
@@ -157,7 +157,7 @@ class TrafficLightMapBasedDetector
157157
* @param visible_traffic_lights the visible traffic light object vector
158158
* @return visualization marker array
159159
*/
160-
static visualization_msgs::msg::MarkerArray createTrafficLightMarkers(
160+
static visualization_msgs::msg::MarkerArray create_traffic_light_markers(
161161
const tf2::Transform & tf_map2camera, const std_msgs::msg::Header & camera_header,
162162
const std::vector<lanelet::ConstLineString3d> & visible_traffic_lights);
163163

perception/autoware_traffic_light_map_based_detector/src/traffic_light_map_based_detector_node.cpp

Lines changed: 10 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -63,13 +63,13 @@ MapBasedDetector::MapBasedDetector(const rclcpp::NodeOptions & node_options)
6363
// subscribers
6464
map_sub_ = create_subscription<autoware_map_msgs::msg::LaneletMapBin>(
6565
"~/input/vector_map", rclcpp::QoS{1}.transient_local(),
66-
std::bind(&MapBasedDetector::mapCallback, this, _1));
66+
std::bind(&MapBasedDetector::map_callback, this, _1));
6767
camera_info_sub_ = create_subscription<sensor_msgs::msg::CameraInfo>(
6868
"~/input/camera_info", rclcpp::SensorDataQoS(),
69-
std::bind(&MapBasedDetector::cameraInfoCallback, this, _1));
69+
std::bind(&MapBasedDetector::camera_info_callback, this, _1));
7070
route_sub_ = create_subscription<autoware_planning_msgs::msg::LaneletRoute>(
7171
"~/input/route", rclcpp::QoS{1}.transient_local(),
72-
std::bind(&MapBasedDetector::routeCallback, this, _1));
72+
std::bind(&MapBasedDetector::route_callback, this, _1));
7373

7474
// publishers
7575
roi_pub_ =
@@ -79,7 +79,7 @@ MapBasedDetector::MapBasedDetector(const rclcpp::NodeOptions & node_options)
7979
viz_pub_ = this->create_publisher<visualization_msgs::msg::MarkerArray>("~/debug/markers", 1);
8080
}
8181

82-
bool MapBasedDetector::getTransform(
82+
bool MapBasedDetector::get_transform(
8383
const rclcpp::Time & t, const std::string & frame_id, tf2::Transform & tf) const
8484
{
8585
try {
@@ -92,7 +92,7 @@ bool MapBasedDetector::getTransform(
9292
return true;
9393
}
9494

95-
void MapBasedDetector::cameraInfoCallback(
95+
void MapBasedDetector::camera_info_callback(
9696
const sensor_msgs::msg::CameraInfo::ConstSharedPtr input_msg)
9797
{
9898
if (!detector_) {
@@ -108,13 +108,13 @@ void MapBasedDetector::cameraInfoCallback(
108108
rclcpp::Duration interval = rclcpp::Duration::from_seconds(0.01);
109109
for (auto t = t1; t <= t2; t += interval) {
110110
tf2::Transform tf;
111-
if (getTransform(t, input_msg->header.frame_id, tf)) {
111+
if (get_transform(t, input_msg->header.frame_id, tf)) {
112112
tf_map2camera_samples.push_back({t, tf});
113113
}
114114
}
115115
/* Camera pose at the exact moment */
116116
tf2::Transform tf_map2camera;
117-
if (!getTransform(
117+
if (!get_transform(
118118
rclcpp::Time(input_msg->header.stamp), input_msg->header.frame_id, tf_map2camera)) {
119119
RCLCPP_WARN_THROTTLE(
120120
get_logger(), *get_clock(), 5000, "failed to get transform from map frame to camera frame");
@@ -129,20 +129,20 @@ void MapBasedDetector::cameraInfoCallback(
129129
viz_pub_->publish(result.markers);
130130
}
131131

132-
void MapBasedDetector::mapCallback(
132+
void MapBasedDetector::map_callback(
133133
const autoware_map_msgs::msg::LaneletMapBin::ConstSharedPtr input_msg)
134134
{
135135
detector_ = std::make_unique<TrafficLightMapBasedDetector>(detector_config_, *input_msg);
136136
}
137137

138-
void MapBasedDetector::routeCallback(
138+
void MapBasedDetector::route_callback(
139139
const autoware_planning_msgs::msg::LaneletRoute::ConstSharedPtr input_msg)
140140
{
141141
if (!detector_) {
142142
RCLCPP_WARN(get_logger(), "failed to set traffic lights in route: map not received");
143143
return;
144144
}
145-
auto error = detector_->setRoute(*input_msg);
145+
auto error = detector_->set_route(*input_msg);
146146
if (error) {
147147
RCLCPP_ERROR(get_logger(), "%s", error->message.c_str());
148148
}

perception/autoware_traffic_light_map_based_detector/src/traffic_light_map_based_detector_node.hpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -58,11 +58,11 @@ class MapBasedDetector : public rclcpp::Node
5858
TrafficLightMapBasedDetectorConfig detector_config_;
5959
TransformSamplingConfig transform_sampling_config_;
6060

61-
bool getTransform(
61+
bool get_transform(
6262
const rclcpp::Time & t, const std::string & frame_id, tf2::Transform & tf) const;
63-
void mapCallback(const autoware_map_msgs::msg::LaneletMapBin::ConstSharedPtr input_msg);
64-
void cameraInfoCallback(const sensor_msgs::msg::CameraInfo::ConstSharedPtr input_msg);
65-
void routeCallback(const autoware_planning_msgs::msg::LaneletRoute::ConstSharedPtr input_msg);
63+
void map_callback(const autoware_map_msgs::msg::LaneletMapBin::ConstSharedPtr input_msg);
64+
void camera_info_callback(const sensor_msgs::msg::CameraInfo::ConstSharedPtr input_msg);
65+
void route_callback(const autoware_planning_msgs::msg::LaneletRoute::ConstSharedPtr input_msg);
6666
};
6767
} // namespace autoware::traffic_light
6868
#endif // TRAFFIC_LIGHT_MAP_BASED_DETECTOR_NODE_HPP_

0 commit comments

Comments
 (0)