From 5fd07beba8ee0d5d4661175015e93276a55a2c27 Mon Sep 17 00:00:00 2001
From: "mergify[bot]" <37929162+mergify[bot]@users.noreply.github.com>
Date: Tue, 25 Jun 2024 14:34:53 +0200
Subject: [PATCH] Change camera info message to lower case (backport #1005)
(#1008)
MIME-Version: 1.0
Content-Type: text/plain; charset=UTF-8
Content-Transfer-Encoding: 8bit
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)
This
is an automatic backport of pull request #1005 done by
[Mergify](https://mergify.com).
---------
Signed-off-by: Alejandro Hernández Cordero
Co-authored-by: SFhmichael <146928033+SFhmichael@users.noreply.github.com>
Co-authored-by: Alejandro Hernández Cordero
---
camera_calibration/src/camera_calibration/camera_checker.py | 6 +++---
1 file changed, 3 insertions(+), 3 deletions(-)
diff --git a/camera_calibration/src/camera_calibration/camera_checker.py b/camera_calibration/src/camera_calibration/camera_checker.py
index 19149b5ec..a0d27a245 100755
--- a/camera_calibration/src/camera_calibration/camera_checker.py
+++ b/camera_calibration/src/camera_calibration/camera_checker.py
@@ -164,9 +164,9 @@ 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))
- 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] ] ] )
+ 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)
# Convert rotation into a 3x3 Rotation Matrix
rot3x3, _ = cv2.Rodrigues(rot)