From bfdd7aca5250acd69398eea2b87813c37ec5da54 Mon Sep 17 00:00:00 2001 From: Scott Monaghan Date: Mon, 22 Apr 2024 19:53:35 -0500 Subject: [PATCH] Update for compatibility with image_pipeline 4.1.0 --- camera_calibration/src/camera_calibration/calibrator.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/camera_calibration/src/camera_calibration/calibrator.py b/camera_calibration/src/camera_calibration/calibrator.py index 1e3ef4d0b..b9d724be0 100644 --- a/camera_calibration/src/camera_calibration/calibrator.py +++ b/camera_calibration/src/camera_calibration/calibrator.py @@ -1317,9 +1317,9 @@ def chessboard_size(self, lcorners, rcorners, board, msg = None): cam = image_geometry.StereoCameraModel() if msg == None: msg = self.as_message() - cam.fromCameraInfo(*msg) + cam.from_camera_info(*msg) disparities = lcorners[:,:,0] - rcorners[:,:,0] - pt3d = [cam.projectPixelTo3d((lcorners[i,0,0], lcorners[i,0,1]), disparities[i,0]) for i in range(lcorners.shape[0]) ] + pt3d = [cam.project_pixel_to_3d((lcorners[i,0,0], lcorners[i,0,1]), disparities[i,0]) for i in range(lcorners.shape[0]) ] def l2(p0, p1): return math.sqrt(sum([(c0 - c1) ** 2 for (c0, c1) in zip(p0, p1)]))