diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index b8c7d8b3..96e8fca9 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -25,7 +25,7 @@ repos: args: [--markdown-linebreak-ext=md] - repo: https://github.com/igorshubovych/markdownlint-cli - rev: v0.47.0 + rev: v0.48.0 hooks: - id: markdownlint args: [-c, .markdownlint.yaml, --fix] @@ -37,7 +37,7 @@ repos: args: [--no-error-on-unmatched-pattern] - repo: https://github.com/adrienverge/yamllint - rev: v1.37.1 + rev: v1.38.0 hooks: - id: yamllint @@ -47,7 +47,7 @@ repos: - id: check-package-depends - repo: https://github.com/tier4/pre-commit-hooks-ros - rev: v0.10.0 + rev: v0.10.2 hooks: - id: flake8-ros - id: prettier-xacro @@ -62,25 +62,25 @@ repos: - id: shellcheck - repo: https://github.com/scop/pre-commit-shfmt - rev: v3.12.0-2 + rev: v3.13.0-1 hooks: - id: shfmt args: [-w, -s, -i=4] - repo: https://github.com/pycqa/isort - rev: 7.0.0 + rev: 8.0.1 hooks: - id: isort args: [--profile=black, --line-length=100] - repo: https://github.com/psf/black-pre-commit-mirror - rev: 25.12.0 + rev: 26.3.1 hooks: - id: black args: [--line-length=100] - repo: https://github.com/pre-commit/mirrors-clang-format - rev: v21.1.8 + rev: v22.1.2 hooks: - id: clang-format types_or: [c++, c, cuda] @@ -93,7 +93,7 @@ repos: exclude: .cu - repo: https://github.com/python-jsonschema/check-jsonschema - rev: 0.36.0 + rev: 0.37.1 hooks: - id: check-metaschema files: ^.+/schema/.*schema\.json$ diff --git a/calibrators/intrinsic_camera_calibrator/intrinsic_camera_calibrator/intrinsic_camera_calibrator/board_detections/board_detection.py b/calibrators/intrinsic_camera_calibrator/intrinsic_camera_calibrator/intrinsic_camera_calibrator/board_detections/board_detection.py index e18856b6..61c4bf28 100644 --- a/calibrators/intrinsic_camera_calibrator/intrinsic_camera_calibrator/intrinsic_camera_calibrator/board_detections/board_detection.py +++ b/calibrators/intrinsic_camera_calibrator/intrinsic_camera_calibrator/intrinsic_camera_calibrator/board_detections/board_detection.py @@ -219,7 +219,7 @@ def get_normalized_size(self) -> float: if self._cached_normalized_size is not None: return self._cached_normalized_size - (up_left, up_right, down_right, down_left) = self._get_border_image_points() + up_left, up_right, down_right, down_left = self._get_border_image_points() a = up_right - up_left b = down_right - up_right c = down_left - down_right diff --git a/calibrators/intrinsic_camera_calibrator/intrinsic_camera_calibrator/intrinsic_camera_calibrator/board_detectors/apriltag_grid_detector.py b/calibrators/intrinsic_camera_calibrator/intrinsic_camera_calibrator/intrinsic_camera_calibrator/board_detectors/apriltag_grid_detector.py index ac952e0f..6e6d9494 100644 --- a/calibrators/intrinsic_camera_calibrator/intrinsic_camera_calibrator/intrinsic_camera_calibrator/board_detectors/apriltag_grid_detector.py +++ b/calibrators/intrinsic_camera_calibrator/intrinsic_camera_calibrator/intrinsic_camera_calibrator/board_detectors/apriltag_grid_detector.py @@ -95,7 +95,7 @@ def detect(self, img, stamp): min_margin = self.min_margin.value max_hamming = self.max_hamming_error.value min_detection_ratio = self.min_detection_ratio.value - (cols, rows) = (self.board_parameters.cols.value, self.board_parameters.rows.value) + cols, rows = (self.board_parameters.cols.value, self.board_parameters.rows.value) min_index = self.board_parameters.min_index.value tag_size = self.board_parameters.tag_size.value tag_spacing = self.board_parameters.tag_spacing.value diff --git a/calibrators/intrinsic_camera_calibrator/intrinsic_camera_calibrator/intrinsic_camera_calibrator/board_detectors/chessboard_detector.py b/calibrators/intrinsic_camera_calibrator/intrinsic_camera_calibrator/intrinsic_camera_calibrator/board_detectors/chessboard_detector.py index ef009566..df41a7ee 100644 --- a/calibrators/intrinsic_camera_calibrator/intrinsic_camera_calibrator/intrinsic_camera_calibrator/board_detectors/chessboard_detector.py +++ b/calibrators/intrinsic_camera_calibrator/intrinsic_camera_calibrator/intrinsic_camera_calibrator/board_detectors/chessboard_detector.py @@ -52,7 +52,7 @@ def detect(self, img: np.array, stamp: float): return with self.lock: - (cols, rows) = (self.board_parameters.cols.value, self.board_parameters.rows.value) + cols, rows = (self.board_parameters.cols.value, self.board_parameters.rows.value) cell_size = self.board_parameters.cell_size.value flags = 0 @@ -110,9 +110,7 @@ def do_corner_sub_pix(corners): grayscale = to_grayscale(img) if not resized_detection or max(h, w) <= resized_max_resolution: if self.roi is None or self.lost_frames >= max_lost_frames: - (detected, corners) = cv2.findChessboardCorners( - grayscale, (cols, rows), flags=flags - ) + detected, corners = cv2.findChessboardCorners(grayscale, (cols, rows), flags=flags) # if chessboard was found, keep track of the region to try to detect easily in the next frame if detected: self.roi = get_roi(corners, img.shape[:2]) @@ -123,9 +121,7 @@ def do_corner_sub_pix(corners): return else: roi_frame = grayscale[self.roi[1] : self.roi[3], self.roi[0] : self.roi[2]] - (detected, corners) = cv2.findChessboardCorners( - roi_frame, (cols, rows), flags=flags - ) + detected, corners = cv2.findChessboardCorners(roi_frame, (cols, rows), flags=flags) if detected: corners += (self.roi[0], self.roi[1]) self.roi = get_roi(corners, img.shape[:2]) @@ -141,7 +137,7 @@ def do_corner_sub_pix(corners): resized = cv2.resize(grayscale, (resized_w, resized_h), interpolation=cv2.INTER_NEAREST) # Run the detector on the resized image - (ok, resized_corners) = cv2.findChessboardCorners(resized, (cols, rows), flags=flags) + ok, resized_corners = cv2.findChessboardCorners(resized, (cols, rows), flags=flags) if not ok: self.detection_results_signal.emit(img, None, stamp) @@ -159,7 +155,7 @@ def do_corner_sub_pix(corners): roi = grayscale[roi_min_j:roi_max_j, roi_min_i:roi_max_i] # Run the detector again - (ok, roi_corners) = cv2.findChessboardCorners(roi, (cols, rows), flags=flags) + ok, roi_corners = cv2.findChessboardCorners(roi, (cols, rows), flags=flags) if not ok: self.detection_results_signal.emit(img, None, stamp) diff --git a/calibrators/intrinsic_camera_calibrator/intrinsic_camera_calibrator/intrinsic_camera_calibrator/board_detectors/dotboard_detector.py b/calibrators/intrinsic_camera_calibrator/intrinsic_camera_calibrator/intrinsic_camera_calibrator/board_detectors/dotboard_detector.py index 66c7f43d..82149c69 100644 --- a/calibrators/intrinsic_camera_calibrator/intrinsic_camera_calibrator/intrinsic_camera_calibrator/board_detectors/dotboard_detector.py +++ b/calibrators/intrinsic_camera_calibrator/intrinsic_camera_calibrator/intrinsic_camera_calibrator/board_detectors/dotboard_detector.py @@ -50,7 +50,7 @@ def detect(self, img: np.array, stamp: float): with self.lock: h, w = img.shape[0:2] - (cols, rows) = (self.board_parameters.cols.value, self.board_parameters.rows.value) + cols, rows = (self.board_parameters.cols.value, self.board_parameters.rows.value) cell_size = self.board_parameters.cell_size.value filter_by_area = self.filter_by_area.value @@ -100,12 +100,12 @@ def detect(self, img: np.array, stamp: float): grayscale = to_grayscale(img) def detect(detection_image, detector): - (ok, corners) = cv2.findCirclesGrid( + ok, corners = cv2.findCirclesGrid( detection_image, (cols, rows), flags=flags, blobDetector=detector ) if not ok: - (ok, corners) = cv2.findCirclesGrid( + ok, corners = cv2.findCirclesGrid( detection_image, (cols, rows), flags=flags, blobDetector=detector ) @@ -118,7 +118,7 @@ def detect(detection_image, detector): return (ok, corners) if not resized_detection or max(h, w) <= resized_max_resolution: - (ok, corners) = detect(grayscale, full_res_detector) + ok, corners = detect(grayscale, full_res_detector) if not ok: self.detection_results_signal.emit(img, None, stamp) @@ -129,7 +129,7 @@ def detect(detection_image, detector): resized = cv2.resize(img, (resized_w, resized_h), interpolation=cv2.INTER_NEAREST) # Run the detector on the resized image - (ok, resized_corners) = detect(resized, resized_detector) + ok, resized_corners = detect(resized, resized_detector) if not ok: self.detection_results_signal.emit(img, None, stamp) @@ -155,7 +155,7 @@ def detect(detection_image, detector): roi = grayscale[roi_min_j:roi_max_j, roi_min_i:roi_max_i] # Run the detector again - (ok, roi_corners) = detect(roi, full_res_detector) + ok, roi_corners = detect(roi, full_res_detector) if not ok: self.detection_results_signal.emit(img, None, stamp) diff --git a/calibrators/intrinsic_camera_calibrator/intrinsic_camera_calibrator/intrinsic_camera_calibrator/camera_calibrator.py b/calibrators/intrinsic_camera_calibrator/intrinsic_camera_calibrator/intrinsic_camera_calibrator/camera_calibrator.py index b3b4f16b..9f5c51f4 100644 --- a/calibrators/intrinsic_camera_calibrator/intrinsic_camera_calibrator/intrinsic_camera_calibrator/camera_calibrator.py +++ b/calibrators/intrinsic_camera_calibrator/intrinsic_camera_calibrator/intrinsic_camera_calibrator/camera_calibrator.py @@ -1365,7 +1365,7 @@ def main(args=None): parser = OptionParser() parser.add_option("-c", "--config-file", type="string", help="calibration file path") - (options, args) = parser.parse_args(rclpy.utilities.remove_ros_args()) + options, args = parser.parse_args(rclpy.utilities.remove_ros_args()) if len(args) != 1: parser.error(f"incorrect number of arguments: {len(args)}") diff --git a/calibrators/intrinsic_camera_calibrator/intrinsic_camera_calibrator/intrinsic_camera_calibrator/camera_models/camera_model.py b/calibrators/intrinsic_camera_calibrator/intrinsic_camera_calibrator/intrinsic_camera_calibrator/camera_models/camera_model.py index 0ddcae64..137bc38c 100644 --- a/calibrators/intrinsic_camera_calibrator/intrinsic_camera_calibrator/intrinsic_camera_calibrator/camera_models/camera_model.py +++ b/calibrators/intrinsic_camera_calibrator/intrinsic_camera_calibrator/intrinsic_camera_calibrator/camera_models/camera_model.py @@ -267,7 +267,7 @@ def get_rectangles(camera_matrix, dist_coeffs, img_size, new_camera_matrix=None) return inner, outer size = (self.width, self.height) - (image_width, image_height) = size + image_width, image_height = size camera_matrix = self.k distortion_coefficients = self.d force_aspect_ratio = True diff --git a/calibrators/intrinsic_camera_calibrator/intrinsic_camera_calibrator/intrinsic_camera_calibrator/data_sources/ros_bag_data_source.py b/calibrators/intrinsic_camera_calibrator/intrinsic_camera_calibrator/intrinsic_camera_calibrator/data_sources/ros_bag_data_source.py index b0c98b2d..547c7079 100644 --- a/calibrators/intrinsic_camera_calibrator/intrinsic_camera_calibrator/intrinsic_camera_calibrator/data_sources/ros_bag_data_source.py +++ b/calibrators/intrinsic_camera_calibrator/intrinsic_camera_calibrator/intrinsic_camera_calibrator/data_sources/ros_bag_data_source.py @@ -110,7 +110,7 @@ def start(self): self.reader.set_filter(storage_filter) if self.reader.has_next(): - (topic, data, t) = self.reader.read_next() + topic, data, t = self.reader.read_next() self.send_data(topic, data) def consumed(self): @@ -123,7 +123,7 @@ def on_consumed(self): return if self.reader.has_next(): - (topic, data, t) = self.reader.read_next() + topic, data, t = self.reader.read_next() self.send_data(topic, data) else: logging.info("bag ended !") diff --git a/calibrators/marker_radar_lidar_calibrator/src/marker_radar_lidar_calibrator.cpp b/calibrators/marker_radar_lidar_calibrator/src/marker_radar_lidar_calibrator.cpp index 9d1d3b63..a57cf755 100644 --- a/calibrators/marker_radar_lidar_calibrator/src/marker_radar_lidar_calibrator.cpp +++ b/calibrators/marker_radar_lidar_calibrator/src/marker_radar_lidar_calibrator.cpp @@ -1136,11 +1136,12 @@ bool ExtrinsicReflectorBasedCalibrator::trackMatches( // Update tracks for (const auto & [lidar_detection, radar_detection] : matches) { - if (std::any_of( - converged_tracks_.begin(), converged_tracks_.end(), - [&lidar_detection, &radar_detection](auto & track) { - return track.partialMatch(lidar_detection, radar_detection); - })) { + if ( + std::any_of( + converged_tracks_.begin(), converged_tracks_.end(), + [&lidar_detection, &radar_detection](auto & track) { + return track.partialMatch(lidar_detection, radar_detection); + })) { continue; }