Skip to content

Commit

Permalink
Change camera info message to lower case (#1005)
Browse files Browse the repository at this point in the history
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 bc5cab9)

# Conflicts:
#	camera_calibration/src/camera_calibration/camera_checker.py
  • Loading branch information
SFhmichael authored and mergify[bot] committed Jun 25, 2024
1 parent e0ac7ec commit 6221943
Showing 1 changed file with 8 additions and 0 deletions.
8 changes: 8 additions & 0 deletions camera_calibration/src/camera_calibration/camera_checker.py
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down

0 comments on commit 6221943

Please sign in to comment.