diff --git a/sensor_calibration_manager/launch/drs/mapping_based_base_lidar_calibrator.launch.xml b/sensor_calibration_manager/launch/drs/mapping_based_base_lidar_calibrator.launch.xml new file mode 100644 index 00000000..18472445 --- /dev/null +++ b/sensor_calibration_manager/launch/drs/mapping_based_base_lidar_calibrator.launch.xml @@ -0,0 +1,80 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sensor_calibration_manager/launch/drs/tag_based_pnp_calibrator.launch.xml b/sensor_calibration_manager/launch/drs/tag_based_pnp_calibrator.launch.xml new file mode 100644 index 00000000..3a5a0bc7 --- /dev/null +++ b/sensor_calibration_manager/launch/drs/tag_based_pnp_calibrator.launch.xml @@ -0,0 +1,162 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + op + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sensor_calibration_manager/sensor_calibration_manager/calibrators/__init__.py b/sensor_calibration_manager/sensor_calibration_manager/calibrators/__init__.py index 0d7af762..d6771494 100644 --- a/sensor_calibration_manager/sensor_calibration_manager/calibrators/__init__.py +++ b/sensor_calibration_manager/sensor_calibration_manager/calibrators/__init__.py @@ -1,4 +1,5 @@ from .default_project import * # noqa: F401, F403 +from .drs import * # noqa: F401, F403 from .rdv import * # noqa: F401, F403 from .x1 import * # noqa: F401, F403 from .x2 import * # noqa: F401, F403 diff --git a/sensor_calibration_manager/sensor_calibration_manager/calibrators/drs/__init__.py b/sensor_calibration_manager/sensor_calibration_manager/calibrators/drs/__init__.py new file mode 100644 index 00000000..b68bd981 --- /dev/null +++ b/sensor_calibration_manager/sensor_calibration_manager/calibrators/drs/__init__.py @@ -0,0 +1,7 @@ +from .mapping_based_lidar_lidar_calibrator import MappingBasedLidarLidarCalibrator +from .tag_based_pnp_calibrator import TagBasedPNPCalibrator + +__all__ = [ + "MappingBasedLidarLidarCalibrator", + "TagBasedPNPCalibrator", +] diff --git a/sensor_calibration_manager/sensor_calibration_manager/calibrators/drs/mapping_based_lidar_lidar_calibrator.py b/sensor_calibration_manager/sensor_calibration_manager/calibrators/drs/mapping_based_lidar_lidar_calibrator.py new file mode 100644 index 00000000..4bd89582 --- /dev/null +++ b/sensor_calibration_manager/sensor_calibration_manager/calibrators/drs/mapping_based_lidar_lidar_calibrator.py @@ -0,0 +1,92 @@ +#!/usr/bin/env python3 + +# Copyright 2024 Tier IV, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +from typing import Dict + +import numpy as np + +from sensor_calibration_manager.calibrator_base import CalibratorBase +from sensor_calibration_manager.calibrator_registry import CalibratorRegistry +from sensor_calibration_manager.ros_interface import RosInterface +from sensor_calibration_manager.types import FramePair + + +@CalibratorRegistry.register_calibrator( + project_name="drs", calibrator_name="mapping_based_lidar_lidar_calibrator" +) +class MappingBasedLidarLidarCalibrator(CalibratorBase): + required_frames = [] + + def __init__(self, ros_interface: RosInterface, **kwargs): + super().__init__(ros_interface) + + self.sensor_kit_frame = "sensor_kit_base_link" + self.mapping_lidar_frame = "pandar_top" + self.calibration_lidar_frames = ["pandar_front", "pandar_left", "pandar_right"] + self.calibration_base_lidar_frames = [ + "pandar_front_base_link", + "pandar_left_base_link", + "pandar_right_base_link", + ] + + self.required_frames.extend( + [ + self.sensor_kit_frame, + self.mapping_lidar_frame, + *self.calibration_lidar_frames, + *self.calibration_base_lidar_frames, + ] + ) + + self.add_calibrator( + service_name="calibrate_lidar_lidar", + expected_calibration_frames=[ + FramePair(parent=self.mapping_lidar_frame, child=calibration_lidar_frame) + for calibration_lidar_frame in self.calibration_lidar_frames + ], + ) + + def post_process(self, calibration_transforms: Dict[str, Dict[str, np.array]]): + sensor_kit_to_lidar_transform = self.get_transform_matrix( + self.sensor_kit_frame, self.mapping_lidar_frame + ) + + calibration_lidar_to_base_lidar_transforms = [ + self.get_transform_matrix(calibration_lidar_frame, calibration_base_lidar_frame) + for calibration_lidar_frame, calibration_base_lidar_frame in zip( + self.calibration_lidar_frames, self.calibration_base_lidar_frames + ) + ] + + sensor_kit_to_calibration_lidar_transforms = [ + sensor_kit_to_lidar_transform + @ calibration_transforms[self.mapping_lidar_frame][calibration_lidar_frame] + @ calibration_lidar_to_base_lidar_transform + for calibration_lidar_frame, calibration_lidar_to_base_lidar_transform in zip( + self.calibration_lidar_frames, calibration_lidar_to_base_lidar_transforms + ) + ] + + result = { + self.sensor_kit_frame: { + calibration_base_lidar_frame: transform + for calibration_base_lidar_frame, transform in zip( + self.calibration_base_lidar_frames, sensor_kit_to_calibration_lidar_transforms + ) + } + } + + return result diff --git a/sensor_calibration_manager/sensor_calibration_manager/calibrators/drs/tag_based_pnp_calibrator.py b/sensor_calibration_manager/sensor_calibration_manager/calibrators/drs/tag_based_pnp_calibrator.py new file mode 100644 index 00000000..19dc48ce --- /dev/null +++ b/sensor_calibration_manager/sensor_calibration_manager/calibrators/drs/tag_based_pnp_calibrator.py @@ -0,0 +1,65 @@ +#!/usr/bin/env python3 + +# Copyright 2024 Tier IV, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +from typing import Dict + +import numpy as np + +from sensor_calibration_manager.calibrator_base import CalibratorBase +from sensor_calibration_manager.calibrator_registry import CalibratorRegistry +from sensor_calibration_manager.ros_interface import RosInterface +from sensor_calibration_manager.types import FramePair + + +@CalibratorRegistry.register_calibrator( + project_name="drs", calibrator_name="tag_based_pnp_calibrator" +) +class TagBasedPNPCalibrator(CalibratorBase): + required_frames = [] + + def __init__(self, ros_interface: RosInterface, **kwargs): + super().__init__(ros_interface) + + self.camera_name = kwargs["camera_name"] + self.lidar_frame = kwargs["lidar_frame"] + self.required_frames.append(self.lidar_frame) + self.required_frames.append(f"{self.camera_name}/camera_link") + self.required_frames.append(f"{self.camera_name}/camera_optical_link") + + self.add_calibrator( + service_name="calibrate_camera_lidar", + expected_calibration_frames=[ + FramePair(parent=f"{self.camera_name}/camera_optical_link", child=self.lidar_frame), + ], + ) + + def post_process(self, calibration_transforms: Dict[str, Dict[str, np.array]]): + optical_link_to_lidar_transform = calibration_transforms[ + f"{self.camera_name}/camera_optical_link" + ][self.lidar_frame] + + camera_to_optical_link_transform = self.get_transform_matrix( + f"{self.camera_name}/camera_link", f"{self.camera_name}/camera_optical_link" + ) + + lidar_camera_link_transform = np.linalg.inv( + camera_to_optical_link_transform @ optical_link_to_lidar_transform + ) + + result = { + self.lidar_frame: {f"{self.camera_name}/camera_link": lidar_camera_link_transform} + } + return result