From 0ee3cb917f2a504f8da18d32427b8f6f52901e92 Mon Sep 17 00:00:00 2001 From: SFhmichael <146928033+SFhmichael@users.noreply.github.com> Date: Tue, 25 Jun 2024 20:17:13 +0800 Subject: [PATCH] Change camera info message to lower case (#1005) Change camera info message to lower case since message type had been change in rolling and humble. [](https://github.com/ros2/common_interfaces/blob/rolling/sensor_msgs/msg/CameraInfo.msg) (cherry picked from commit bc5cab9516e274744dd062b66863139a2bfb035d) # Conflicts: # camera_calibration/src/camera_calibration/camera_checker.py --- .../src/camera_calibration/camera_checker.py | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/camera_calibration/src/camera_calibration/camera_checker.py b/camera_calibration/src/camera_calibration/camera_checker.py index 19149b5ec..2c86fd99c 100755 --- a/camera_calibration/src/camera_calibration/camera_checker.py +++ b/camera_calibration/src/camera_calibration/camera_checker.py @@ -164,10 +164,18 @@ def handle_monocular(self, msg): image_points = C object_points = self.mc.mk_object_points([self.board], use_board_size=True)[0] dist_coeffs = numpy.zeros((4, 1)) +<<<<<<< HEAD camera_matrix = numpy.array( [ [ camera.P[0], camera.P[1], camera.P[2] ], [ camera.P[4], camera.P[5], camera.P[6] ], [ camera.P[8], camera.P[9], camera.P[10] ] ] ) ok, rot, trans = cv2.solvePnP(object_points, image_points, camera_matrix, dist_coeffs) +======= + camera_matrix = numpy.array([[camera.p[0], camera.p[1], camera.p[2]], + [camera.p[4], camera.p[5], camera.p[6]], + [camera.p[8], camera.p[9], camera.p[10]]]) + ok, rot, trans = cv2.solvePnP( + object_points, image_points, camera_matrix, dist_coeffs) +>>>>>>> bc5cab9 (Change camera info message to lower case (#1005)) # Convert rotation into a 3x3 Rotation Matrix rot3x3, _ = cv2.Rodrigues(rot) # Reproject model points into image